From 2d409188f8c1df586f0b34082ae5de1c3dabede5 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Wed, 1 May 2013 12:59:07 +0200 Subject: [PATCH 01/39] OP-935 Adds checkbox for 'real time updates' to basic screen. Disables controls when no board is connected. --- .../src/libs/utils/mytabbedstackwidget.cpp | 7 + .../src/libs/utils/mytabbedstackwidget.h | 2 + .../src/plugins/config/configgadgetwidget.cpp | 9 +- .../config/configstabilizationwidget.cpp | 58 +++--- .../src/plugins/config/defaulthwsettings.ui | 7 +- .../src/plugins/config/stabilization.ui | 195 +++++++++++------- 6 files changed, 170 insertions(+), 108 deletions(-) diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index 639052e57..a9610c0e5 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -91,6 +91,13 @@ void MyTabbedStackWidget::removeTab(int index) delete item; } +void MyTabbedStackWidget::setWidgetsEnabled(bool enabled) +{ + for(int i = 0; i < m_stackWidget->count(); i++) { + m_stackWidget->widget(i)->setEnabled(enabled); + } +} + int MyTabbedStackWidget::currentIndex() const { return m_listWidget->currentRow(); diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h index 5faad8222..7307673b1 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h @@ -47,6 +47,8 @@ public: void removeTab(int index); void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); } + void setWidgetsEnabled(bool enabled); + int currentIndex() const; void insertCornerWidget(int index, QWidget *widget); diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 3c6fa9569..52a0ab875 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -49,8 +49,6 @@ #include #include - - ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) { setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -144,6 +142,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) oplinkTimeout = new QTimer(this); connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect())); oplinkConnected = false; + + ftw->setWidgetsEnabled(false); } ConfigGadgetWidget::~ConfigGadgetWidget() @@ -165,6 +165,8 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) } void ConfigGadgetWidget::onAutopilotDisconnect() { + ftw->setWidgetsEnabled(false); + int selectedIndex = ftw->currentIndex(); QIcon *icon = new QIcon(); @@ -234,8 +236,9 @@ void ConfigGadgetWidget::onAutopilotConnect() { //Unknown board qDebug() << "Unknown board " << board; } - ftw->setCurrentIndex(selectedIndex); + ftw->setCurrentIndex(selectedIndex); } + ftw->setWidgetsEnabled(true); emit autopilotConnected(); } diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 5469403ae..949d76529 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file configstabilizationwidget.h + * @file configstabilizationwidget.cpp * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ @@ -36,42 +36,42 @@ #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()) + 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(realtimeUpdates,SIGNAL(timeout()),this,SLOT(apply())); + realtimeUpdates = new QTimer(this); - connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_2,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_8,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_3,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); + connect(m_stabilization->realTimeUpdates_6, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + connect(m_stabilization->realTimeUpdates_8, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply())); - connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*))); + connect(m_stabilization->checkBox_7, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(m_stabilization->checkBox_2, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(m_stabilization->checkBox_8, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(m_stabilization->checkBox_3, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + + connect(this, SIGNAL(widgetContentsChanged(QWidget*)), this, SLOT(processLinkedWidgets(QWidget*))); + + // Link by default + m_stabilization->checkBox_7->setChecked(true); + m_stabilization->checkBox_8->setChecked(true); disableMouseWheelEvents(); - - } - ConfigStabilizationWidget::~ConfigStabilizationWidget() { // Do nothing @@ -80,22 +80,30 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) { m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - if(value==Qt::Checked && !realtimeUpdates->isActive()) + m_stabilization->realTimeUpdates_8->setCheckState((Qt::CheckState)value); + + if(value == Qt::Checked && !realtimeUpdates->isActive()) { realtimeUpdates->start(300); - else if(value==Qt::Unchecked) + } + else if(value == Qt::Unchecked) { realtimeUpdates->stop(); + } } void ConfigStabilizationWidget::linkCheckBoxes(int value) { - if(sender()== m_stabilization->checkBox_7) + if(sender() == m_stabilization->checkBox_7) { m_stabilization->checkBox_3->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_3) + } + else if(sender() == m_stabilization->checkBox_3) { m_stabilization->checkBox_7->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_8) + } + else if(sender( )== m_stabilization->checkBox_8) { m_stabilization->checkBox_2->setCheckState((Qt::CheckState)value); - else if(sender()== m_stabilization->checkBox_2) + } + else if(sender() == m_stabilization->checkBox_2) { m_stabilization->checkBox_8->setCheckState((Qt::CheckState)value); + } } void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) diff --git a/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui b/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui index d1ef7d913..b4272ab22 100644 --- a/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui +++ b/ground/openpilotgcs/src/plugins/config/defaulthwsettings.ui @@ -25,15 +25,18 @@ + + true + <!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-family:'Ubuntu'; font-size:11pt; font-weight:600;">Hardware 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-family:'Ubuntu'; font-size:11pt; font-weight:600;"></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; font-weight:600;"><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;">This panel will be updated to provide the relevant controls to let you configure your hardware once telemetry is connected and running.</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></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;"><br /></p></body></html> diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index a133279db..d1110d6fd 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 965 - 687 + 1076 + 834 @@ -600,17 +600,11 @@ 0 0 - 937 - 595 + 1046 + 751 - - - 12 - - - 12 - + @@ -6770,71 +6764,118 @@ border-radius: 5; - - - - 0 - 0 - - - - - 0 - 62 - - - - - - - Integral - - - - 12 - - - - - - 0 - 0 - + + + + + + 0 + 0 + + + + + 0 + 62 + + + + + + + Integral + + + + 12 - - - 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 + + + + + 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 + + + + + 0 + 60 + + + + Instant Update + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + Enabling this feature mean that any changes made to the sliders will be instantly sent and used by the Flight Controller, useful for two person tuning where one normally flies and ones changes the GCS. + + + + + + Update flight controller in real time + + + + + + + Qt::Vertical - - QSizePolicy::Expanding - 20 @@ -6937,8 +6978,8 @@ border-radius: 5; 0 0 - 540 - 663 + 1046 + 751 @@ -16860,8 +16901,8 @@ border-radius: 5; 0 0 - 802 - 607 + 1046 + 751 @@ -24815,7 +24856,7 @@ border-radius: 5; - Real Time Updates + Instant Update @@ -24833,14 +24874,13 @@ border-radius: 5; - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. + Enabling this feature mean that any changes made to the sliders will be instantly sent and used by the Flight Controller, useful for two person tuning where one normally flies and ones changes the GCS. - Update in real time + Update flight controller in real time @@ -25101,7 +25141,6 @@ Useful if you have accidentally changed some settings. RollRateKd PitchRateKd YawRateKd - scrollArea pushButton_2 AttitudeRollKp AttitudePitchKp_2 From 6d3407e4e47097e09a481ca269529b2ba3f91c18 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Wed, 1 May 2013 18:18:30 +0200 Subject: [PATCH 02/39] OP-935 Adds shadow to the image on Revolution hardware page. --- .../src/plugins/config/configgadgetwidget.cpp | 8 ++++---- .../plugins/config/images/revolution_top.png | Bin 182625 -> 187310 bytes 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 52a0ab875..9fc52d559 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -92,7 +92,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); @@ -174,7 +174,7 @@ void ConfigGadgetWidget::onAutopilotDisconnect() { icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new DefaultAttitudeWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); @@ -206,7 +206,7 @@ void ConfigGadgetWidget::onAutopilotConnect() { icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigCCAttitudeWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("CopterControl")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); @@ -223,7 +223,7 @@ void ConfigGadgetWidget::onAutopilotConnect() { icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigRevoWidget(this); ftw->removeTab(ConfigGadgetWidget::sensors); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revolution")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); diff --git a/ground/openpilotgcs/src/plugins/config/images/revolution_top.png b/ground/openpilotgcs/src/plugins/config/images/revolution_top.png index a98e7e3773a8dc02e91aec7f5eaf0439c9436ae6..3a6b8fbd692b8c0094a84f34c7733b12a7fdedee 100644 GIT binary patch literal 187310 zcmeEtWmgdfdqeRC2?+^LLH?^c5)!iY>oCN^c%3Qk54Cu` zp;<{OOCcfE#Ns@fpugJKPVzukBqaQv{|#i~Pl^GrlN4YXU9g6uCD`4>#RBQOiH!r8 zLq$fD&W)FYpM#r=>(V6;3F#$D;j5IUhvDH9CRkf386MFo$UAFhIQ~sX$6~QkB}dRP z9dYh8-sjC(E{Vm!DA|J@CkYdIi**u8r9yZPqulPefl*3gnct1W-o4qEPRU5q0(Mx! zE=g^VAf`G0ZEb#iG#wCkhTgqc2MhfF>;Lr!9-Hu}smCPtj~!O0rk6|QYAcGG?DZWT zGaTIAFB&V43+-1|*%>RATfNhPU~jKas;W5b!W`gL2g7;RIkj|o<_$i>d6tw!*odc> zzReKA959ds-T%O0E}Jtnj?jf)rSGegdVV!17>8C}YOi*R=S?@1UVfaDS-OE33aA;5 zfqzb4m3pYgj#dp@T6%LtevFspNGPfO<@|{u^Wwgu1iy#2-{HX$`%s;_UEqPRhEzQi(Ew=XTs_;!l`#(($ z^9iT5&Sg>a)3we@`ue@ebB$h~kEk3oCuK4VOnCPhqcilEGvsw0S7zp5qD)kdglE?= z$C~a^cx+@JFwE1bpP-?)f_XAt$TS zQ(RrBiiHv)s+@J92+E2z!2fS&v<72h%_vqb)@R-K0ma9cbL(u&8duC#=7%B~4Z1gj z&@H~H87&>l0f&0L^r>kxYDI;`e^JemwNsk71WgRQycA4*Lz;zIf0{P?B2~VrTu(kf zsA(pKq^3UX9hJO83=dDeC8hii2BWyVnxzBWi}OtN%4DyXY@OZxDGd7{CWhJ>&pj0klbuWs@r@ zyG--$-OudraZWNy7W=y+cUDrH`Posc@#zD{P2WBn75vC*YW8^>P-45Q^We=iH@2OV zd02GrIPeecL@qnW@;MFh>qckaC99RDQ=sI+jTfRsBX>~h5&)(g|)YQq` z{7;piNAtL;aka0$nlo&?q~#@+@ufG>y8G#6W@2{rI=^V#OQ79jky1vmHp^iT?XRGo zmSN0G95iV=wxF&Uqc2Ha+vW2U1wco(;6l75=xXckLK`_Wep9n_PmE$e{m#nqC1tNY zap1+|N!9*kU@8eZ;-B?=phf$mw64Y~mIfE^%EZ(z0QKR9j%nvzc}0v#IE;i!td`)| zVNS^N{H;nRmz1|R`6hOHnD^B?ip}VW??#8qO*lFnZDvlngjZLZf@G5q{E}Wt7V6kmVP@d+7bq2hGZRK*Noe@W*D2-6J=W+8aq0MF@PV3 zhrb!L?uD(kHBHyJO{)_)I0$@V`4$pA=A4>NBk8S=&0*m5?!m#HeYV-KQ+o{IpHO++ z#X>m-)_SHo$(YhwECUy~0vwA<##P|WyU%uN>K#r0i=_?xSDQVzrcsmk%CwQ|Z^;q@~sr-Z8%;Sm3C{?pIT znytHM9wlj&U`XfMyiv!&2YE~5d8mD}&rs4|Z-R#?w~bL7N-Eyf*x-*CpEwlh_IB6L zEd+n{=Uy=kQji@=4(3xXs5%Mc`Q+un%!LJwecDkW4U5g5Tewm}=<}7Wy@O87!z1yZ zD~QF#;m+%SX;3@}0|kk_@h+WVBkvmc$(#MgP(|GA`i}Ii)QoO)!MOdHxPvbEZxQV5 zvGILWig#Igs`sk_N?d{x|FLHXey8#G@LHPe#G9B>=YwP&=(UInLFcQ$90acm19Kc6 z{|$x~4I37)cG$8!7lC22`#v-*Su(s`Qx8L_d%0>d)yIyHNQGJxN#=2&%K8W%BicDAt#gF)*^IkO+&Ymd7}FSI5b{vSjOZur_1y6&w1EM%eA`CjQ`umOZO zPgyW{T$QGT4bL`vbdzTYB8-bVIpX6{hDvSo!89?p4&z<~3d|8dz7krew+@dlD^85> ztgGdwdM&m`xUq#NS~vmu=0tZ#aixl!qa#yKuP;`iNSth(5W+?^xs*O| zGxO8H_BP$YA&Z&;m8uil-$8j+8nM>sG981GcIqL3l_ax?PdU1Kdq*KsmVAIpzhP~9 z73hl2qiI9!RQa&b6`SCK3DG7)1^@fJYAz;XHj<2&=odNHM9;~I;bp$s)|&Yn>P9QD zSDx=G{)W<4qvj+zxu*n?yu&=Avu_YXXk9DX!uAKc&kKO>oX11tc6ZJ*CoS$={D9fD zK6idYt)~ZC;s1@V=zIFlcD%j;z*9Uu{mVz5YU-Pad%9s%l!BE+`B{W4ww?YzUd}xZ z9t$|;Z4P|KMB@`3@Mjyb$~BxFba?HRcg=2DKq!w_kA!>bI{UpbrR$;PiKW_Q;;gk>m!?K6_Jg^}P*3dAPQ>X=q zUv_S}&&8#ddPsr5M6&k|4`5qk(hJbl2zIa^%YVb~?M-auaq)U!nQaKcHSTX>1rx*{ zd=kY)vQm6R4Q~n`(_iC~%FjM_V^5#6E?7WE`O%eaNk~~gvqT_6L2mRo0Lf<3l~p$M zTQEd$bD;*+<93~8YMK^X7vt6_Ahhq@!U9!rR}N_mEw8M*`{y?}W}%TG>}SlXrSFK2 zVu=O_{*GNGA}IoaD3CC`9>DHXwIT2qBa-h`DJ60%d3U$qSF3k4ZsC$Ej7S}^(1FDv zD*Yyh_cx9%wZ!~0HixhV>SU5|8Rj19<7@kjP^~eJ^yK7r;CvZSn`)lTKgRZ;)b7r( z`qZmI>_oMIHEVjdv9#0rr{ez*QxNB23@G&M^;}bUMKS; z@ymLZ=A}YfM&``l+P-2wA6EMxE!7|;-$P+d`~Jt;QRqw6Y!dMpNze~-w$jNV#o^>Z zN&kXV8;7OlY!)Fcm(soECPxzOWip@zFG7_``P+tN~B4qOMA%!Eq{8y>C3A zi$`TBr$kJK`Q9X-0awyvs^i7pH)+trGj4XDdg}n@N=s0c2|o$~LwI zQ1|hFfBrr6z}cQgo3IOqiYvwf79)atepsYnv~f&L2V=*}O{@)c!Us<2tV7V&WQ~l3 z+dIZL_TJ?K0~|tbj_MX9a3z1|)gJ8?#0njariU&EO$2A{^LR2{}&PcD*u zSlnElm;9i1m7RVS;s80{@;<7P=0oXY9VE%$#l^b5t4nNg>}XgVXSop6Hz)j4x{ar+Rsc$S#h$Q zDyW1S@q+e;(R-pZF2=>PXDrNSzrl}^IPx?=NgQm}7}OGMVAqB(I#!?A*p)-CMji5o zhG;HtblzpMhh_v{$jRLQLf1hig=>8JtnlG))zhOV1L2-wZJ*CwJTGv+ zUq~ivsG}_f{U1|q5`o?-4u?dE(oKJqctYiH3IchJb_@(Oto5-%v}aA-`Bgt#k`9hO z#RF1aqM&E<)4oo?t)dOXUM0@Z5^tnjM@)Q9F>;3*8Zb^5@dW~#@3&Hm$zJF(dU4(@P)K(lhbN@C`;-cR`&QfZ_$o0jV7!&fIlWJD} z8Mzs9RY~)SM%?@>_0ML`7ldYOQrurRxz25jVXT0$0Dz7e~17vL#?Ljv6{32M>b zy8E>8SbEqZ>e+Glxc#(KtLfQ-f5xo~uT9=zk7Z(CO1qqgr0J~Ewuq%D0Bz#QhCT_| zzHyhwJ&C}Esbr6T18rYu&F9Nj+9B7yq|)w{G%_s5*T-lro8ChAhT)>z-8^4^FIAqa zT?n*u!c<)SeW(f~yk{pD$tXG26?kyK@fdm+u*Xx{wc ztdWgMN1D0eWwBMS2)N&3>LPRUdhRo5ZH_FoD_AZ4(00=9>FkJ)M*}?D(Nxn6>r%dq{Aij;r%ON z$-7j|Z9sbQV~$#y@OVg@hHeM0?KSW65*0Jf^@nWniZ2c-AptBB)<=itSd9@plypk1 zE&JR+Sc|pY=-cPRkdQVqPhj|er^}`i0&@fF#|})nzArH1OaKIH*AjCBvBgvfKRXp? zXD55*b7Fa=xy9$A!U-z7Bcb{E9p6O*%)1Z@7t&5(F1e38`v+`26&cy4{eu(V*@0J` zrvUhW$HzR*zUrDSr99s)K8+X`itg;)H_G&t^l;Qu)rm2>Q)>Pm~Lp!g9+$;bk3ZZFZn6x_OEylbkwRf`jfOgL(#- zvFKmEox3w0p5MkY>dC)&hxQjPz2p@YjYWC=QvjYGe6&VM@`hS%hKAm!Q;D|v;Np}lmfw|8-`XJu4ycCC*T-#SQjzBpg3{nIQL9Syk~mos#WOwl!WEWZ}?esP>? z2`V1`Oi8ZKo|N>t$7)#mi&nRmfyT;e1-i9mqYlYr6qMMoQX@KzGVsUycEkI3o&a*y z{oXRm_Vn_PC0X$l@ql=*&s7IDl#SVBe>IZH94|^ErYMWf`QiqJ3}@q=q!Z@>TNg8; zv^(M3SEauc*X1P&T4_oyTExlA^JM4bC5!2lmXsx1YDIsQ@A7bqm{}KRR~Av{&n$9( z%Mq(!V*R<%1Mhj*s@-(muyuS#fIWa!ohdGAze_N4&|YC3B$$(;t#Yr;{3E_$Thwv zz>E6t)bFJI*O;Jnz;T#!L@9}#HnQlwc#%q=?;W;ibo?9VkHX? z&)eUZGS!a!m}oW9AB`wU*u*alYuwr@*(!TtapK`(3MjZL2Rn$gJM8umEBarZ%fLM} zq@^5nCmjHjG7ppqGzyTAXloZTv$NsXW!BaU{jjlstjx{zLlNa|jz3(? z&l0+?ixLug&9g3^bv<6v2e!;=tZ8yUG#YUkwUXp)q=QRaCM_u3`ctB)0Yx@77Qg4} zXh_{-jsN1wAt$f`1XcD;Qzw&T$|wTuR#yJr-z&Z&-jO@~-2cy-#qhe>xOtj}v-OC3 zYKyL5{#|~D3Yotf2ni_gUK|7XXZ*yteT|$5Rq>ONgaR!m=+_2M5`;(4CQeAJI9WP_)UaQhun<3gf5jt9l}h=i5*!&&twv zkLAVre9w+L2=t;AHm$)TOKl)HUzNhOyU6kwAM?sP&eM%?#AP00O_~h(mTg`5wLDq3 zq85yp$m-aqY#p|Gh)=GqExo5ECObBEw5^$+u)avHSk|^%X!hJsZ$OY%GUeS8N=xTQ z;|t8iWOKv}!9i5_9G*fS*trt{PRG`o%iCt-x5WizTRY~iN}yAT=PilnAg6O9c|Q7z zD}@&(`YyVMmpz1I+snbMYY_9AIl6p|QkM5d?yY-};hON)B2t`qqD^0a}7@Lgg#cMBFAp5y3DSPv1dySADaKC$6V0_>1Hvkxx?{o=3RsCq$DPG!pc)ZWA&71 zErCxvn3k+n=rS@jn^IcZ+MoKf<#N0Fk$jVuxpX_IRc)_AM9UaT<_AVNC~KpJN=d|3 zVE(+a4+f{dJ(*?o+)V3bX!9$mirSSK*}b{WJ_Ma}f4gmdoG}6_`*7F=Ix{4}^Rb;E zF}(A=)f*5W_BSf$OWSv+S7(icia)&5DtObUS#jYL-0Fg^dkDzYyK&cX4SX1Dk?PI&5N9nVFht@HON?xwN8 zU{-3HWSo{Qsaagzb0wJJ22FjvAf7kdHJW#44Xg}uF#=XT6T>}P_ZqE@-6=_0GUO>7 zARz@~SiSv2%q$u_>6IDaSZlT!nSvk$*(~L&bX&Zh&xy-+*^O#kvN^h!VM|N9L2a%_ z=z`%9aSyP)gFlm-^#pp*jNQi4%ZP|PlkvJ^JDHcn5c-N&R7u!fq+a^$@sd2TqW&}# zNxG_;PxcR2R+%(7#MMZZ{m~H=P?SH0Q=2}0cyvUi3e=?$kboRa;N~)=Vo%5c2Y-t9 ze>pQtbXyr-I@q>9p-ce)eq7k(%#aU0DUHZd$FimX#0P-Q&chg76GrIXBD}(K$#kP< z^_qTpzrXMyW$Q1kBt~Q2RQ;S!n>APp2v9PA*AQnhLYzrCfryqrcti8!m?ikvDn<0* zcZj8t84jWyeY>~yj<_vOGI^3;FX>o<*uHMc@_Kw;rQqE zQo>m=zBer`8?V%G{DE$U)6R@$k-FT*=iS7M88yFV3hE=dxSgkB*L4;7hIhwcUCp)) zp(bVwI8kdQ%&Nt6|J^md8>ZXwQbm4~wEwDG2emD@X}@BrUB(?9*=x}&D_Uu;avJzA z&alO6ET~{adlXa)UUX;0USJ*@jT&!j+cpHdQ{i;@Q>tPtK>7wYpi+&Xl95IOBO{j^ zW{Ep)2`+Q_y0&0is?tSjQB^(4=Z3ttwn;BjQ{!(W=ijQ>wxs#kj=z4p1!Xoi`9S7o zx##ER<_?sNNl17D7kj39E)&tQyI&v9g|LIulS!E6N86z}S03koqJLDcyo{c0D?fK~ zgg+k^u9p~!cBQc1KY7njPO7mzh7u|g0&q#M1GROm)*n5Y&nhsp-E{O56l@H-wSqUp zhVc^Txt(BWdn7+Z@%Xm!Nb9HwiBP#Fd}$%VUd8hBQhq%E(Q^>qNo1Mxv@LOEjz0QH z**zBi`G*!oxW}(;DijCuzb^-Rw+4E_BBb+lqwdrcb%JKOilnMP+)W=nPiMHvp@+S@ zOoCu^yD)HMz}bkO5iX?pSF>61G%9DS7}u05217@7eGb+z^Z3K8IdV5!2BWQ|@N?>1 z%6EW~h;(#{#$UpnqTHUHzdPNnLD7Zc2^@L<5VMW7yua>*IL1M*X&#{I%q8l|+vLwO zO+KTU7(N*jIl^_IY?2M7NVG^NKP`37wa=q!D^bWe^IRF%@NHZ&{O?WN_0YUv^4IuJ zDO)!6wEUpx(DlA?43ss32*PuxFT4!SBntDx<$r&&8j+3h9cnEh8cqm%5j`MP3T&h#qZm6Rq3L zE0sjzqTZ1{600m~ilZa@Bh|5HZoUV@eVV`~oIBEZPc=>tuxxL4dA5A_(5}99ibho7~Zd0mp{VE!R zeZR+~O90p`ir{Xdv)Si0h`iWx*(zYO!hWMgQ;KTljzo~NGmvWTH>Z`x``&|Ezs$f5 zmzqPaaZk%?T9yRV;Y4(G!)Vrg^(mWw&*Zf!jSUWC>(4vN+yUqI1i#) zaq#wDuFcBK!arHEul9r=i)CD5Pl;T*|03>ieR8Y)v-tC)eAPlNWLf>yA03z4A;`d) z3oux~PcHY_ZKrhBh*Q6DQ>pe(mvemsciZkh%VKt#ivudoi2!=U%V2o-d?;vuBgUByj0D<>qe1u_A{Xb z!21VQHQl$YJNLK-U++!hre~D|b);3$sZ(~j zc=jUw-_f4G4sXvQCJDh>`uXDC45d8a?~){sTYJ&XC-woXR#zM5WjL6a&whP=Lb??L zS!Le8sGDemXGKoyweLp;FshW3kfoDGq>?aulVyT{UlfvXdQ)VQnl6#c+FeSf3WvWp zn;jHuY^cUh#c%IVn;LZN1_gbgok>2F(R#+v+}_Xqpo5uIU(OCwncD<`3Es!O&#&M| zg2=QMLzn6P6b2;MD?=s?!PktrwsZubC(pe-Wm(@O;iKSb$k*(2Q{Q^``)R+Q@+^NY z`|?V5KmCXl$nErCNFNr+tC&Mm4WBC6`cKl$?Q#aH<5?6^B3K0Ko0xG00yKRa$x#=zMO(~I6hSR93}ZwlAZnh=z3fUgM$v4w|Y*dv64n)QPM>)#u}Gl zhB@-qcX&fp3VyOZ&(=E!#;oaGVMTcUDtmjyYy8~YTpt{3QJ4k_V7f*jN<~?QS+FH4; z^h5hc2j(B9Cccw4*g-@qonCe8pZ)OPEcE^jDnK`bGoU$BGD%E5fRDAsvH&hBS`b-5 zZnIGWh7llEg^<2Z!+AaeAO(7)m*J6MvP^#mO1Laa!7-JT#T$ z4ImEbb9poOrEtz>dvYEWBEM$wNmWle4i?gl?-&)En2>1vXo3B4U}XPx7R6yJUkePw zJ^s<|lN~f8pc8b%`|^~$o<7f#$tOt2iwyIBp?>LNKG6Es@?>xX)~Dil>{ z00O5tNIAA}7+xC|AoBCX1HXKGBKjS+WAJfGJ@d2l@jr7pf#m@f2nVMj^D4Q4!&?g- zISZXIxO5-c#|;ZBxsNJK%<3@I1a&xDcqK0$pS*WyRJd!A^` zVA)1--zi4Gu%=IIq`Kzk(Q%>uMyAiOwPC&n&S0YmUv_}}13*ab=TM4n^@(7rmHhsL zUko~?Uts9RuKtF%u73*A=>(b84T{S34e;wT8{>h627JE{bYLO?C&s`#VK8obV$|Ag6@ zdzGV>t=fp#_y0O~6;3JOaJK;McY|xG-l(kE8txr^H2abtygr#avv?x*-QLv2n0q6X z{)v^)4f4nkG57O%KBPS;^QEMqg2Uu|mZ;XW#i@l^v-cx#Z;_n)6kJPw=H!M|W2_Ta zP@AnV9S7T-#%SmV5MqFDvn)Q*<219F zv3lt{m~4A;%ZA}_0}Q?<^8oJ?v|iH|LTS~J&}CDXa>8C!*9lFRHx?y`S57nK?}$CQ z3e{R9NaX4i*48z!?AR5$7U%PHm9o$^9#Fm~T`a#C(tn6&&AAekS2+R(J;p_wDCWOA z2=VyCwS}|eqDdFWE9TK*;Nm${t2L2q(@t$a?)rD=-m2?q&ze2^SKrEfN@RAn9k|}= zcdG!6gO19^kyh8g@svlhE`w{{_?*oYC55jB(xeE@%(-#HrmqZ8r8zAhuQtKG5e4nI z^54Fd_n)6F?j*Km`q-^)qWcoMQCgErYB$1DSJb8&ty?&O;TBm|SiEEf8z1sUowDbQLPOCF`4`&UA83L*mJ{Fp z!JhLLBuW*eI1;ILSVP`Q!i*x|5cb#`4CbfT!Rl&M-_+O@-H?f%|G&lAeJte1;{3Ya zh=u0U@PvdFsnfFpS|u9)#!4^S$|zht46Fh24{!dJyP{jhJ(hsygq5X0_Pt6D@^7?P zBq?mH^<<=H%=!3>@_&DLyFbLyeA0$#wK{Kd11+dR)dfyEzQ;ynEvL}mKhw;RwB|P4 zf4CRvJquzR{RI#G@=;c)#5v(gR95@K3H@XLV!9;`fVP78y4b57Rc2^8?$jE!y~^(2 z=i1!6NIzQtOL3U@Nt4G*$C?Rj#qnSGsjow7KH!0l!o@AO!dft_)loy*GzGgigk6LN zaB=k`Ir4z9rTu-q*4+gF9qU!4zhE%AjhmH_g}-WHO!t^SCntYJTe37Aq<`Js4*wg9 z^mMj#lh`$wHTWtxA& zI+RXK;C&dJeb-~rmm)v7iR*fXl4$%y1JIV)EJ~J2*jgKv2!+V*ziFmUtoq4-e_m}|I zl7OPZ_742Lvl?a(@ET=yOd~t~^)<)gk}(44+89>QFsnwXUz)^qN9)Q#>-tiXKV-cikURiIdLc z6|Vzht0<$c_d77w1c%wIPZnF=?MLWL!rq4;H=5&Ko5w>8zQ%FSat|n*re9d53J9*?UIBe`-ucZ> zXjYk5_ZiK%0@-8AlQw^xch8G#I6Yt&vBR@*zTvVF9*B#|LC|>E%;rg*@-C9aI|v7u zfih}G{3b`N+p{>44USUZV3nW8jhdttF*p({>7$NRu1ecCFaiq?+#sRiS!DXR9UvZs z+th7+BJfTJQE-?^IM!TPd?gX*Fv^nvr(*}|N?4c2dS-M6-KABS?=Y*~k(l}<4*UH^ z;e2@F`d*+~ORf6j@~qyCIczy*n*Thbp4hA0Mepibr$`~^KN`=AP|ebe>uX6bQ}*4P}O&b7Z2PT_%pdD(FtVP4+R zQH|tB%Uyj7+v{Pyaxs+xVt%HJLkT1}750anb?#30!+o<`8aLBc;^#uH*Ql}6R%@;o zr;i;O4{2*c!fhS)7G@9EHCvWlZR`7*_!Ty;`(buP(HuiY6(4<|fqoN{uto~}00DUN^ zvAR}tm;m+Y@CaW-2=F!&6ur8#f;CLjUo@U+DeQC~6^_0C5zU%N&|L@PlHQ%5N!sC< z!(3S;4FheZg-dir0dq!FTpz6tLV^(<^eHkVl)}Yt4Rg#U9iZbvQhBKkf076B(>dU} zEU-|LjAyUYJ5u)#lyQB1d$bRgw$;a195H>DvrgdZYF4h_7Gy3wSCuf*V4FO?_dezR zjokz=VvJH}YcMZsP~}G2+m)wPFJW>%DJ(CL3Rhx?;X52#a9~@P{Nuoo7Y%#wKV9Lz zGOm7JzOWJQ$97!KFr|H;H0inmS)|gk#?86cw= z?TfUkcMN)DBv`{{a}gRRp*JdG(EzFt@)*z<$PQyx824I?(AngAsY~ZqPyo6pC~Rho zt&6|>ZE4^~gMFF4KEM+^8BVo50c-sm-0K$&Ms&Oa>tocYSyH*s}dW=L+w}LXna!B=4Hx`9gzv0 zPU5GeR97OH2yxRKQ4EcLO33U&&63b=grl;4h;Z2=v0-LCoZLzvp%XM7Ibm_gc&7B3-I|maJdjM z%d84yV-n(Y0=uMb9Xs!qOhC{?=y8N*i@cB&ybRC5 zHs(n?p!*;f_XCv(oZr`UB9Uon3@(XE_vWUi|K5GUMNOA+mBs98{|#|{6gI(_FsR1; z%Kt4sAe)T#t4AEc%3+1Aon1M4?jrn~68FI3)bIh8{`ldNlZzXV8-!uxuKvLfg*UP$ zJfKcwMCxW5*K*#5UXs=s;wrpJ>jYo9fKz`pQl=Z(>Z;_;ZQ&`+W5O9Ae@~@D687=0 z6@qYqH$a<9Jz!U~eLIYiGR}@`1#3}NUv7?G)r56`H)tZE`vchBf`Q?P{?SKe3#!b# z(rFo9mSPvO%#RAS)(!uP6i(7rqJY0BlbiBXFkm5}WX{k>qu zo$$d;i0b_GQIaT8fouZT>N->sRjGO%E)Vq#aV#uUL0XsU{FLnoGl25ehVnIc2C@A(%M2y>4x7WMb<&>2LQ!{c5>}~ApX1a%L zIy2e^sA8wHjl46@9)sB6s@M~>S!bdz-Q=oOH(1cFD^d67BOFrB4#;)pd{w1EbM;+( zxT}?$7awGJ$|*iz*NsK^ORl9PEz`eGlD4hF9>diBXE9yW6;pN#PE-H3eO zr!L0+>$!i6ydgZ5@WBZ>+xd&lS`MYo=~b4!va_-9935V|FOJSSde@kp1Hk} zR=zu3wD^<6N!$1%;*Kk#IunGR35soPX`#Y-)9DW}{}YQpJTMQoDZZElJ3EE0D-I=T zYH3<%@kVKd`X)esBaIVhN%2wM{xHJ*gnmdKsV5+my*WU8X2U2nYZ{U}qeKGH@Z~8T zX80a=fz%Rv!oZ0TKd(FaMU0Rpso?y19`s#{A}qc3?M!m`TT!!#>0dF(C~#v={U%|w z@ee`F4|$PX;_8aMhl=eKRg8$VwRm%-reEvdm8G4gY(9?{sOeVQ0WVra_s6B($hvbxD6!Getvgj(-7t`mzb3y+iDe-o*2!IW*%IEo zdQDmsMMr%U9{jKCLy*)MWyxk6Y(9PZDJyIFmN5R9p09`0@21L!V8Tx9<+kXB4{y)^ z?o7h;>L64@(&8 z4ob}?H6Pwyd16ka*1e++&6w0^CH5s2;o>3tYSACCQ)?{5ijy8VZ1LLupaSzO3;;buw03=HZ)u!5v}JK#yFI4H{bd{l`T6;i0|ZPZPk8v2in`VoJRb6T z!<$lRL^=b@;j@iy*CW<5B5Sj&W*k!Y`azdEj5$Qb67)j;9{m?94~!>oUx`A$45X*I z*+|kTjvO~~w$JiK-s73;ZYBGh#yTSt=3l-f7NU;@>^jO`EQjhzT;@=w>tju*@*$6f zilSP_=p@0{du)nmUg^j>Q^nQ9t5ME8-DTa3^F%;)O?Rgi0Re%VP4y0&FSKZteDn=e zj%>8Y#SJ1p{3^V0*O)xd5XFvDy@Vr;C8@-)tH`h3$n&X7C(KnXL4G$ey;0REH>_3}#e9Y}+(bFA_HXjq1l})h7__RX) zO5`wNoAWa#%s!^FHTZ~9(jl~U$8g69qvAqYk(8Y*UoM1zM|Q$>I3_-Sg34!kkj?Lg z-7ApzM)s`vv#*(_JA36nOfDz=j0tPAu4oDCyp{vUw0JBLeM`=xl?{)#d0>eWj~&24 zf&Q}=KZ=xm5hcl2mEO}8_0Efk8LuQ!B;t67ZGrt3sA4Cj66Fm49s`$V+B+GMmXqV4 z$ly^kOp981{8XEb`i}A>c6~zsw8fje@EUEekCy|#!ya*Z?dT_NCe?LCWS7;LYt@~` zzP5i=)vL2Ji&kyGIbAsaSsq6+0li~GiA?W+j_;6)20dF!eggRKD@YD48thX=*?m&V zLF0wUW3<5p{A@HWzDWMWdMCy9LwuzhTL*LgT_vTRlxyZl#KkDaB?0n-a_h(H7V&ej zbuYGx`7{93c~M+e77$)u&K^riL2*PceQ6x7%}*yU>w+}8lzw%-|w1)eC7UqMx)b7jfEk^{GW6e-Afz z?G82%?7aG?pUkC9EO`ii8A@~(Lg9IA=#`nc7?s6rqL;}W`1`x-d>BXH00>@<#KcMi zicI&$$l!}%S^Ds#+FwH^g;ce}82xvjRRYo(<6=74x<~T9pqMvS8!|;DOspn{K(+Oz zs#}_PQGK&Y_KxJG{7LchA6)+hcf(aL{`E?kh!JHLQ2y4HOwW6AX*SR+?k(u4n3`73 z>XziDuA|E5RQfCd|4dZ*YnKN{Qvw#)ilPB-K>Pi1o@~d4a#GhcCb04?AL)^tMkmKT zMHUy&`^fBr-n~z&fy_r%-1ls_z773*l@kLO$7N)+F@1HrTOR8E0pS>My&vgRE`XuezjZ5%Q? zoArJ$EVs_!Hb>%d@1_USSMoNO*uY=1&{zy_r38|Wr2PS@BCiX>I*YUB>D0xb!|RRJ zIMslSyT-yIb;v$9!)dHD9^R#iX*;P2GNxKqp|pj2nyfJTOo9YUaoOI}=5@WmR{;OBj!3JOlQ2veIjtWQ-fge(ia_?-_qjxbh8I$G#rtlL zxp6O@ztJyq-YAbXPy{4PYIo!&!ohVpA5NTC%3gQsj<$9(3EJKk2?+@^+iPD(0=n-g zG!W_N&?B{IGJ>4aPRzUcUHMM1B(|j$O5KPWsZNm@nkAtjfad0`!_&(+plhgG@U>PH z+ZrNX&Z-oMTw!yj2trAhDnqKYv9E?YmyGzlc5%RB(+A4Vc~XJz%Ud>_%+v_%J*eSZ zvb}h}DE1lKJ`AH7=SZ->=LofW0+JmLN&343x`jxkRnM(g&1&m;x%uMQK@^c=+@ID=FMzimC=?4sZ<;h~` zQgm(NRk24qLB-XLwatH1+mPZRk)P1rhvJdd;MQ{Gz4FHHX&6`id&=L!{y1KgS!d-p z;(C$p`31(j79rIBzk!Lw}z?4{+pi8)#7x9s6z!`uRT(#fvq7??^E zt68zhyWp8gVJ*#nd2y?hvC?sImq_o_#G7wU-#FZ7_NpzT_5{Ir(XB03&x55%uxH5A z!cOYt5x|NZyw&~Y!e_BbQYGZQD zsgK*GKUX~JEUPn(x)E=x^WHt?t|bo(zcncL?}+Kp`KMc!FEk)&2Nf*C&h3*xE^Fd| zHQc>4a5A~1(qw&k3)IE?dq6U8DqkQ7n3mx>bNOFH-meWqhM>#Nrw4b+jMPIRpBeBn zw(CVS+Fk?N9e2}j^XZp7OJ}vMYj?Rt3%<9h@9qDBl2e3HS1F~IgtPgy)lB%L*w1?9$ne1fhpw5-eEFcZIXsNm@IvkP?z|p5`rw&dF zomUHf8!fH3K)B78sY*0uCp`Pc*2^?;mC$^Z5bP=2f6;A#!mi(o=2V+#B$`x*_6J>? zz1;E4bl8KK-9{vcPrv`sk{kML_w1 zaRJ8@`+hJ+FL(tFHIdYtf!U9=_JdA7-7K1xg?n61aroxHtKw09IkO{B;-90h3P14= zl{M}{iWpm2CZgYTNC*JE!X~Pfw z^}wEh?6za2y+aU^zDQ@~5tn#1@p4mD-#KyQX*cG{#(dW^vH0Vu?@F^>c}==2hZ>izB8w@U(A;o7m$QM-hK zq*;JBrX0qlIx}gCj0&_82W!So#vi_W{ERoGgSI!mqMCEJkVSX&n&~De!9}z3Y3`!M zXgBZ2?KN72nk!sHk}h)B);Ck}th0X<{SWp0sU~n0I4(_U@pJN8@@{97E{bple>Pf3 z>gxehfy=toO$~Lz{f?M`HULrXU0`mTE>CWOZSUQGA2YK+)Um>CLNpiGoqnxVRTT<; zPBPR+G>-l0+JKumgEO*X2{hx^y29)kf3iUy0>qno!U-2)oC%bk6(OM5+ zaC+tBU$>Xcs={SGjNQq!gF~dM3poa%XDR07UF(AAcl31d3gYkDu32}1>sSwYMsZi) zBxygCwUqJVyu$J1L~6v+()+}e0eYq# zgbT|Qn}7B{q|)9~Xj`(bTU%j`Y~dJt9_lY->!Dg$Vku2KnmD#(Uy4<8>m%7J zx>v){bgUQ_(i8lA@H3AZw-&gi4;N}8)(aTKZ^27j?*YrxlZ(k=bGw>+0*v{U0%_$< zXzxko=vfi(;x&#LIG#CrKD56(T_(0QjEAOLZr7jOi;$0YECYhT?)3s+^P6~yR54w!Cep0S z@nvl`d^Hnga$9-uXSJ|jJL5hoNa^Ts05cA2*YA6;{zJUMk=D_GH;0LfscRtV)B%JD z=0&t_TAoW=$F=Kc?(BPddM+=wm}97!zEH-a+Z)^2wIi^Q@6k|~rql=KpnggD2^Z=n zG9qnkjFRK-&X6p`?yh+Fwylo)4JYd~Qz>!vRmvwKp(a zt7n10`rJDynuqX39!tT#Px^zVtyKHHKr-)VvMtV9?BPcq#fF9d11Le)zJ@JnhB{l` zFWIf}yco}(7NWZ=3w3qLC@YUgVNndSbHWjqa1S?cpTo-4%kl2JzbEl{ zD1ADg#yZXQnt7+!^ZsWYgO-2z!+Wr^K8WgyNYqwE6PTh=RUU=1(g+k4MItXR4C!h2 zk&xhzs2E>73b_Fve=l6V;f{kAM)+`{0<^M<37Tp-1yarUG?X>hk?=G*2Cjteo6=tw zwT=PJ+ZrF(AppH**IZbfV#{~)G@utP`c{0~vt@#a$9U^fNV6Moprvu1e2#Xf8H zSF^5s)ui)tjmdg3g;9J!OUzZD0=KAZTqot!M_JFg4ohA0dCcf&`*31nNa(>s2aO5P zdyP$ucaa6X&%C_O zt$G-6E3v6Qe^O56Q&a1>jj|7#t#?fy^dJE`Tnp&GG)O@6JZOd>1CoKL0IhWH6=nMP z_!BhNmkituxE;!$9ksHyJZWQVZN}f#aCCBDOZl*RFeuy`t}aKX0qx>+oYGHRy>`i| zpdd4OVq#$G_3qinV^P57I3JtAtN^XzENt;gzp{j{)McfW`6aX!pj9PSfaWv>Yzb*@ zBom`K1kg0HbTi1}Wl0yyu@{dCv}E~C`35IP3otQ~Ny6!=1l}aPe42olLpj2w!S0E% zmt`0oPQ#0V`xxrFih%}O5^D@L+G42l0!E(&5vcQoB|Scpi=n=U80_*#U%M~b8@*9q z?Sqn%Fl1$iAtfysvGMotFz5!(csUWESKz((-kAaFzg9G1JWGG)4eK=ZkI15Quse*B z!Vr{|gp)*|v^X3^1&@%I`$$;NsVR368|Qrx^DpR zzf}ad$vS==%=!di>F4I@b((-)w`U$~X~c2#$aYHGf^E91uxd4b8g?<3EnAFr>sH~~ znJtL(UyQ;u2Q<~k$%nzU*HHI(3z~8^itn6sm+GOnVh8#v_0doAr2Y^lUM5m~VJn(} z%z&nmlX#FQb$*5+fz5#C86iB!o#)*1mjD^iEDF%P4Z~iw0j|ey0<^6A&!0E+goFn8 zA3uKVFadhcp~HvtO^=ywH9vW3qotMg8hZza6%LM$WJMF8ot?>wc9~D|9myO5^f#9- zU053z9Te2uQ1oJAT+O#;2rD4Z=(5c!AG8+Ge{q;{anSflO_5>u2LEeJfpWI~l6v-G z^z}A9Nll4K^EmD9Vryq}lD|&p;Aqd*F;Aa6qTzowB@x!MySuBopZ^`N>YCDm(b2(? znf)u5$`9!Z&@4QRV_~o|jHMrL<~3x_%cAmex^i3aHtI>xbO3`TNt0AgbAAS~iG9t2*&E$=fpf5jEX zCtnBjw52?I`GX?e6SHN;GM)nTw8#gLTQ;x4!i8UB+0yT@XZL0Sa0TcMh6~~9b_mv% zdvVHqH=V;a?AfykJN36>=Z>u~+`9v}&+8-n_5x(ZTcM^roUG_HwAcHhHftN|vo@eL ze-k>27}8tOTfP;2<+>QG-H(YE33Pv_ENFtS1T=$Ij=b1nmT+c>Gq_2gY^1iPW_++H zUo>ySE)Qvd$R&eW)oqTyR@Yw*4>$KGCPjqVJJ^~XK5}@^5mVFc$4{KtOjh)ITRYoT zj!urt9G#pN6QJ3Op6^6fw8v?W1^4dx>KEoGCk+lXz2wOP4B#0!OMf#PQ%YBcoYuwh z?-UvuYyWCsplcSO-vrFp0nRsLe0*@cy`!NlGAb<4>%6CngM*!!fV8ud>C_x&vGh3Y zYIfWEx<}^Y*PtDc)H$BZ9L>bwumKLcpF zt+KEspykUM(g!&HG6&t&$5EHP3FYYOb^&=bB&XZszv zb!i_;l6Q*lI#*|`M@8BuG*!5xhlam>Jvn05MQ_JFH0A4|g&J^s(PnfMZ$@_+0h&Lw zU%msweZFKdmElRpb;`Gu8vF+FwYt2xwaARzh@^NAvO>KHa@TP4mLpso*24VweC*r% z4L26t# zU;X;0_^1E!cla;=^7r`i%MY>FV5c*Q64R(BEEcCAwGb`(-V36q_VJ;%R~C2m8GqG(F*KrP;ecVE)H3j zXV>i+eQd1rWqW&hUP$QOoAwTNhX~NRX69xaEG;e9*xB1HCo6i16G7V5-EB$0JwJnj z!i;PE{SCF_UY0;TYPKz_rLp%_^Y_($%9A> z--DvK)hLKtgS^=FD9>|5T}>=WJnCu_P+fKd1&Ldc6T1OfQ6$j>;Iu6SVqGD<4QDa@ zEE}EG&Zx_hAL1{e<7Y>&L1OS~L_D&_!@$e9<8u~XUS_Z|`xZxyKZ1e&AMn{Huftea zyKe%lrl|BE0Qs9N=Giju+xKwWa}GjpFGOtcK4hl(;&J+2q^I~HEyW+nNdbtBxs9-} zYX}Uw3P1mI;zRvsyzF6gd>8&Oe-@zsm2jSRTL@Q$hCXF6D=;f7nJwpk`sW`_zYO!s zU;PBzbk|A?di|H!adbHX0vr+GmB*b$kT?z5_sQ6(6zX-!pJtYinhBdoG6u{Z2V1G2jnn!`kRi_DW zj&oh_qzX?}5 z9wiH$+AFswZd-D+%5mj~mh0r`Rkkx;$7uru=rApy|I$$3Q1w^+uL1gX0Kcv?>@;-- zDO;@KH#cs)EnH)z!Z6HeoN3g}#+IGy*S)+s>CN{v??1ZD~7iHTag97;oD(Gld5^%@_v0)e;5 zvbwOJ8oZJC3f*si^K0?F<=_4GZEW1I4kyh_5D}nfh~Oe&f)S^SGc&D(modB=)pPIyZdVb^t*2a=nuIj{v4UTo!Xb?KIf4I?Q>xj z!u>WP_R&!Svkx*-{gImNgOns+Bq#b2pl=~8^csSKt_VP1VL+d=!@lFYrva@A-9IG? z#NQK!w1BZ%GNfk!&9Z#iT>LXx&I-`{=Hd>$_0xdfW4@X|>51rYFT_S(L}JVpLiFwGE{qwS<9|#anG#KX zltj52Sm*o-%u469**Xiy`5YM5Tp3iaJ-ZiYogvP7*(b&iL|A46o%1RyTKVU=604U0 zra&#?Je+J07IbsT5tJmaM@GbIMBZJ7i)Zz*&qyCj7SF}+fBP0$&u^3U`5W=2I@7~@ z@bKmq#0D%vbiiUn-Cd64D05__-9>zyFG54F!^it1oNU(bVX+S2n@_+GYg$8Nk=qnc(aO_cQjeb27&%%Y8U*wg(4Hw&U~9 zKY9(O-xIc$|Aa+78_1fX(lp`BvT*(v2nw)9Qp{;2$6X-E_|r89koD|CkoF@;2Ouui z8<7z=5E61-xHxXybcg482eP220Bx}Ob@#@<%0<__&b#%U$=vuBKCH^|nl5Qb3!~%ggR>J?%V%$Er09W1T;jI04 zIPJUxPEMvce8doI*R8^$Mf1NWOBT48OLMeCxg>7MvTN(5QTJ9ln@t<4eK4e&x$ zMKlKba&YCcBi-Y(sHuv>$&)5dE+c zt&8I?4t4be=>9J1f*FnsMNL4nh0HpOCO~Dnd?+xZ&!o=)`_(Izu7Is{<;qaH+MbWa zdHJSGAajL~l|)qw>!cLnwP}jQo`SNQpGUt&7`m>c}FTGF=Z>$AdWSasXDx zSHkARQrx??0dWtvBI^EDMBdj!T%-dv_B#j;zJlA{r{Q_V1ZIa9WBdAfShMicX<57I zGaT5t5@%eDU`^09GStD2ZF8`H-yZDUyNf!7-Eeh24o^>WvYb!B(#8~KClA16-#i%Z z{uDcOKgOq@yrbc=m;vZ(>t?T?z3$&2^X9w{?{iBK;=KydLB<5;JHmoaBMUl>0G*l~ zfW(A5h>5<1@bH@mWEahyGq`xgWy*qnM*^CF`mYfNu!svFPg%%6w45dUy=k_ZckkRJ zz|7XO@qRr5^cOI)SdWDGD@aYeA>f>z?2Y93Ylw~TM0l_p9zAryT|Wn0zjBK1rx_d^ zkKyo9L#$iB`Ue4h$Z!GDLpPzZ(i`0!nP{j>M0DhB@q*EzLwjL*)Ck1|VYqPK4!3W4 z&}id2Y^;umylg=qJZON5vM4b>o-Jr00@m#EAXtlsi@cs8tz34>g68@!EoKF931-g6 zqNy{WRomfpoHk=Y&$LC=F1bx9mj<^n1#Hg44=1(L?EYOsU40b+x`O~MElgS93_aC5 zDsawrK`32;S5s%5s}sIW_j3BQc!u(ODvVR1&%Wjs#3inPS5NQ}LVn5Y}Va`yK>i_2G> z;Ocf1$Bt~qIyKZkoHCx4e9USKaZ<7+@QO6Bi{Y)x8DQw zYu2w21z}n$3z=a%3&3n8D@%E{s5BuAWd&vd=N&jO1!%)lYw_T|J3<0I1)$Ri&?yPG z5f{xPo687$bO{gdpCgbu!^_JGF0N)cc49x)>u3Oa;S8V`GobgcLPqpq)Rg+7wkj6a zt~%2`E}*JB1`*V08SL3kb;TR!&f4JC4Od}dpE_kiaE?K4RuEn1ZZUOne1tzY%X8)V zWhefUVTAxS7}mmXT_p_+F<+ks#A3z=gPGd_$JtjsTj%z{>r|R_kw}=Uw!@-~9o6n+ zT#i;*cpbM>j;nUqGZ~){q6PF{8fxn*|EjOQeG1TA&|JtIXE-Z>D&Vpx05eE6b+Yp$;ak%&;&G#0IA# z!FfCSDz~Ax$^auzqs2=kp6 zd+#5yb;YMJHdsTjT|y1~8_b{o4Lh)_nw5YOq1x*yOwG0C zrJTkm*Kr!JSNqfg`rjqg*3}T8*~P)IWH7S-h^Ovb-=Gma+u?2EcP9XY`2_E_$CQIrZ65?)= zHSLZ-pZ&OhYZnqj_ai;Z1hK(}2npDOhXJPWyJL>)*KOc=)*809M{txZ-}MXL7hsk` z7Bm5R%d$_fZ`UfUTRj)we)A!|{rV5$Ej@k^`OfcuiyhlmtLxdyu1SK-rH^Pqnav_E7y|G@g!_w)UkA`9k!f#AEANQrerTEcl`XWm6l<~?Mk z`y(rZ;#q;ne*6HBGwvZX;~~idA+fPO1jS|eFJJx>{^|37z(0LV@*&9|rsM;X_h**> z%<*aY`Qr+w0#H^QCM@WR zl5jipU2*^31(X&=kO7d7{Jb!-lq1LxNJfDFIRrkSQCj3J964-=%JOLO@K9RN z637C|{Pn!4w@}5*4*}>YH;8zi!k|KtdVN*}h2bDA`gWIk?7+#b0- z$#y0m402mk+bQFSA>XHcNcis&>Il&N{aw^$DnK*L7>X*+P}cMz&j5BdaA)+{09V^9 zT{FM(Kl8EFFbzC7>Sm*QPeX!LndvQ7J;xw)-EWC{bKEE>ivdaxmYV|Ns zy&YX;x@a!gjD|dYwAXv1JnInh;@2TJVHcu9?cnEai90t>;r8{DxPI9Tr`-<2-tG{b zoGftmoFiE{r{H970!O<8xZrsN*DoD||IGuqdvz&poSl!09?NjS>kwRB&0%I{M8oZE zSUd0CHv-y7e+4$InTxMJ`!&A!^cVP$0R5Y{e@!6#Ew*i%i~W0-!^mhW_8915=k86| zy7>!i()k0{ul)l){^-qb5;8<*!+Kh#psbnxT7Hf6*Vb#q=YRJB{4TCSWWWX_h8-n1 z`-z_v$on&*AoMH(a^u z3`b{kY}&kT8qS)sm@Mfdhj!s{sxON3gUE^wM@>Z}s>-4Wx^ZY}N)Emj^?c+YrZjsf-|ov4S+`;rz<#miuH2Iw2uc z3+TTzO!=UxRM}mipr|0nq8sc3VMO#ppy%80e+fh??6P@E*1nCktA0y>W}s^Lp*7=wu4r1(KV)gol6iC9!=1Bp5O#Y3;)9LI zQuHN2-y^sM2v8U1Jwj1_FfD_{TZa59cx5>OsxlTi*+EDnaOGs(AZztJLD7Y*Mq5ON zIUzCj45A~?lYSbHf;=hhJi;G2;jZ5)`1_b6_`Ve$J)pAov%;;Lb_nou#lw5<@V#*u z7f)}3_w@q^x@ST8Ea7we1n%6nB&+o-!b8sEetUD=NZKKl?CVT*_md$He;Ks&OS zZ=)dRp}YnXz6Q3U(^7nq81F409T84|zVC(G-X0RrE++}l>xFA$HlW$nVX|)n;zBHt zo$Q6uf`_Oq2_Zm7kTo5L*5(xPs(5F677ECME-4O2e@~Y1Ir9`neoeliE{WiskLS+{ z@p8CWe52*X^CFUBjPfT0Udqo2@YfId%ZCi^(HH#f7j}v8=Wna!|02ibn~D6(H1X;< zEhVVsI{6wogPLSI&d_C1ab6fL1yS zTe1w@9|H1hT>)BCSKBHpS<@nB;kY_J!WIg9^Mn$>~3X^qFoOc1Sk9NcN$^!U%8{_)*^RTishYf*wS_syEOq?8T2?V!s z&T$!BPkjPsi*I3XqmN_9_F(7sFR^XIyIA$juLPi_4_X3x`-*pP(s(}h?IsIv$p=`v z;9VFR?t+2APO_SJ!_s^gjEz=epRk~}V&|@n(B1MCHgEhG>(_n!gBJ9gWVR(dtk)Hb7s-*wk@whN{O*f?^Hq@hkcRJ}C@&5rFozMCW5f`@u`XU% zj_s}d1-uNjx1@n0Ucj9@r*ZAN3tZeRuxZPBEL^})o;w3*(%IEv zv~wOF-B^T_@WUw14WROPgzEBeG}gw_wI`#i{V~$h9^%LmL!9%pMsL?+4EE)qzc(A* zUAgG$$fbB5S=ad(9+F^YSaY1g%<^JtJ%gFQfXJU1;Qv$dUw*`QU|2@Ts-EBvdDRiH zYcVk)Kfa_1Z26nB*}$Id!{#M#%df(NX>aRwu^C*{{T)Wb2fLfy%IB7&2hhQn@S?h{vWx>Fn;{bcQoq;A&g7Ked03 zYwD^~VE2S{QOtA_oX+cbN&9`pFRSqIjQwpq{F1{osZ&029kiZ(&;vdgYO}>)qZQgJ z%u$tl429_gm#ixYzpsy*=jXxarUsxHz5>wS2eM3?i90z-KzrIRg_HTma4`QGHkR9Q z`0!3_-|{&&({Ov`x4*_*f-=i@B=bM`XY5?_KAcZ3ho|#?IMC8S_Z@6p^9l4eeGVi2 zuW`iaYnUEfgCn$`1I9bC*GLb$_N<5guC>AkExyGu3!XnD-vjT|x;M$2@@VP{=YNUt zhqlN_JcI1CD+JSrC?UX=I4cHvRQWpU<-4D zsACAGPJ-c1R(nARS@4f&{R8o5^AdtSf7q$G;E{ka?@M+DeBObmppK-RgwMUC@DWPr zc!jimR_1-OX8FxXKg7g%BRKdn{QS=1`b~E@yIGP2twTU2II|Fx7fi($5wH#QzeC{F zc}NN|q4T{fuA`+9x$6(HWuUZ(Z*NC?dU`b7SQnfZ;tGGi%P1{PAy6|I8H5Z*h9U!&L8}1EaTd-WOMi%3k4BvOSdqsm3#=1MtHO%;?sf}ex-wp3JAMI$%&9)kV#aP{n58X`{t+G+~W ze?n}hmJH~SKyP?CE{B`NCvdU&hAikEIC^v!wr~9$+c$p({jIC9RcD!oEQhHv4a+a= z!d-7$-0<9pv$mhZ<>bfku>6$v^C|34d;(jG&9Jc8k7LL8!Q`MmcJBC!p#KNqhyLW_ zDGU1F;HD7J6)utQr@cuuA)fG_$>eiqc3*C##-xwq`3zXuGMU*gpwFn)C4X z#f72B$$ltaI!a9mAS>DjAt6`cA8-ygZhFAU)e@Vx5TK{5W`^?{0Uc&4X8)8G(=jSy zgzKWbG=}QVQJgwyj2$~R!^PR00L$NR$r2XyV1J(Y5dy#9@^mmy{21Xmfth{PLnOmP z{HGoMn|q;H&+u+;Ou>m02gHv9`g(F{UFnqNP1g3ya*{IPCShpvKP_4KPwc#$V9T2S zZ7Bdw!vDXdC0pYBPfYO_c=4@s_HWlxdtzv_%m7+g@bkR}!@c^re8~;huAat;<0h~;bp%aKg;e1DE$Am08R;eI=U2Mv1`N_Lsha@K z59WAX4_V+HwB)Hb1GK(Vq|10WUcPJ<7P@@u+fQj-A`e^ZV`J=+P_7FFYUT3a{V|x? zb)j4w1nE~)VFsKq-f2Q|0HbZYFxsMz5te3sylC2i;ijD!ZZ^Vj>k&*6#CeD&tO0`c z_$dF=F9XfZaVV!onMK3sKwmvvIm3Y7Pk{FNvjMGyT^yl7cW~Kt11aK>#f z>}*Y7Z1^3FcF)6pqg~juXUDYgn}jD%7~9m=+CYY7X zpYtAk&wYnT9~#1k?H3lJgkd1TGmPLGM{tfu3;!&)HC;UH>g|#rkm~EnCP+UP($Shm z7Bm5xA>Epc7TSg(-9lh*Zb(8sfxfmf5_MHksH=`4So3$MBT+-pW^1&vj6u!THd)=` zA)M6t9I8q~1$>2GrqU#oD=AG1%}+_mGx)S47FzLe@KX8vOli76w1h7dJ89 z1!u<-R8Fbr?v#II7iH9&LuJHE26isNI#;}T$W}J{rdc>oHFaX_*N=_4gZ=w=LSKI? z?e`v?dob#26U6V=7~<1_=Pxai<;`DP93sH;lK*$fmN>giUQ$|PeIn9R?}-gjE5XFxNQJ3Gq-NE6~8 zh_~1>$g+O+ z`;w9*^!L{wmh#-X>51@gA9QzD3aA(4$08;=01qErM^a)Sty2&5lx3}ett@E;=qamu zvH}x*r!dyKlSCh*EVBXKxI@f&9%|f+iI`Z|6 z#X|w;?{G%}TKJ#|zCxrA+WOQ{SeqXrIS3mov)2Jl7IZ|254^qB;JW))xOH|B?)jME zuD=^DpIHz4li$JAWH}D+TPozB;SwA+S_(&t)d;_9g4Fmchz&l3Q17J(y14}Ymln}J z=Hrs{Db-ojCnabuDNc( z+>h|!=2j#IQ$2~ZL~;IoloydTS{y8_(I#r(ZOuu-&&*$N>*-{d21A*L?+h7&4oPcM zIt}?#(b<-co{lsD>5dlCX`2oLJG(yEXWLv))^%et8u%kr1Z#GMu%*p$c8Szi%XM{C z1aAUv9jy~-1VWyJETBlBXCE-jH1wzPu(jS$8z(w}8q)a(1Qi7J!u$|qKYobEnGeM0 zQzIj9Au#9?{QSM(dCneNbvFu&Sy|4~7cFJa_BjOT(FT=OZ+8}YXw<=RE;F9>A;Fz3zR|%}b_bQ))ho`}OdZ9B4QsJ# z)pD#{xeS{&u7fU}+a2mi80re>!XhWjoWab(>loS!;0$kG&(r;QAM4kzhK|k}I69mV z=OeA}GJ-VE7GcYq=VwoS+(|&2A^m3o`ahCr0sY4UyEuA!Iy(IPZotH3F9G)fGBcxa z;k+}B9Nv$zvK-{(B*WVJIBr}&gWI>faO{`~0r(N6J%+jYVU(4oAu=KWJN36AFU~>mtrbX) zaYa_T4-y{jMTGBS@#VLGi*$^0bI3}b17EK>2)aHW$zg|)m+6D-)XPYVcSTB!Gh)LW z5c<%XAa9Nv*Q{{TZs?!n3?au!9$y{+h8p|{q#*fXbIjo0ai2L^t#uq>ethz z^URWk3qD8qgOhli=#1R-3&Op@)@XHEC_yh;`kdPsIB5juEMYmb<@cnYMlbAF(w<-6E}IrMERF z3*mTkeS&~r3!MX7;Y|#8u}mPSv!6RwbRcS-aK&(b>Ht`8Ae~>!uC0j|FOM*!bFv>H zB_$AX@d0FX+(9&1tB*o%!qL$b`nvP5dHv_uqVqYnZTted8$QR5EnmX&$T#9u_{Yhf z!uMTP6hdW0okMjr9h4rbaiA1VLv^K1T?!n*m~v{r+D;1Wl3eo zpDAUxNa&+$G{QOo3yVVn)H*t=sZN^0+1Xsor{-;+3>Fg93xt3B2?3gY)cg}-jz1kF zC_iIsx@Zd6g=9e8p;7ckA~RoZl(S#Z{jYwEn@dC>Q+tU&yI9i+z` zBS1ey)fAxX2|%q)Y!wr5#DhTs41r}fpn0~z(?K4(XOmTzN9#C^e}+IXVvCXTGuZjT zB168Lz}4AG;BRG+JtjR%%m!iWyNfJto)y6mZzs@ov}T~4q^&tsoJ(5^!JR}vyDw67{5AQ>95%ub={FBlWjEr;$ zpYw(DZa90^p5R=I$;mDnPI-_;eFA-b4b-b%ptvcltxO3bJoDkG5QcGAXDNZ&grIzk zhD(>odOnBy_pT7wiwMwO@bIt^?hpxGWg#<^dCAaLQ0C<q-fcpa2vnUj_D0EyuS2=ZQxTNhU2_>oP}-LjHo z1-6msZf04IZCh7i$95g;(%%eyy>-~3OZv9e*r~S$`}XSKg8Obn`K?4s;1XmB2uSmfSD%PDTW-a| zG8FlQ-<5r=c>+j1?3?Y7!+!x|f|dk!nm7h`1biGheUAanmN#42Y*i-_s0mgiEo5=C zb4>r&UgKDTzdE`~Mxr8&;m-ATgd%pd!2rOt)Rpo4$fOY6I-d@IVLarCGm_U_da z*TjJ5G|t=F!g;0M$z@0RyLlcqTkN#dwAguWc4r6c(xt+dyKs^4LrdyNIj&&M*7rbP zA)Y;*`qA;rGK`JZPUh#w&Ia_`Bnr?!BKhA*{sV~?&_5I;pqtx$eXo+mXoBwU3Id=4 zWFG-}2%(_?FgH7dlw<-&UaZJ>=guXveEX4=6$?Ydoj7&s2x@9F$ci+@uASSFni_)P z;T8hB13cVqs4^#!rF{bt;dd}NSO;(K^YA=lM|t?oBTW|u!40r2=xNznW&UqYxtIaw%n0+bIT~B?1n;vrz?!5@< zk5&-)x1l`q5W(1=8di$HE|0otD>J7JuYHppw_}Ys7y@ zD9?g$jg8|KJpK*?0PMAXm6Jc*%|Y z`Lhx+%;pDS@*!9uo)WNmc;4H^4;a~pEv;#O;Mh&D7Qm)sbhZ+V+R0KRkTbmbhpt`J zISBViOETJ#d0CwJ zT3t%Ap8z%c*oCWw&V&8YZ2iiPgsy|EYJS+-MAm;zHCeWGX=Lp1I%#n;tea?io@v5g z%wuRwr5OZiM;gAF!^PPW85vP{G2DgF5Fg=(e)*E2%hT|bE8~ZJ&l#aRwWk2?u3 zw~a8|`4x6<{R}%ce+pflkFkB@$1pKifIBy=5E3aWclzs;3l@(2n5xMqVe;?De)6l zl6-1V!!bweD>Lg0-DOoRREoiYlvnZWeJPCQ~A}p z+4*K~!@}Q#j(B(qS;;QQ%eX)z0QqpRwjvx&wQ-`+vxVC$W+brxnLsS8F9I(Or^QTy zXL5?z^Py52O_hmhV?2e7{i8$A%7j(Mu;%&F41)f?0)jnRlWhs;X-_0TCs8~eoh`8x zPnPZwI$l>>3hC^}Wy_nbZL+=z-u#Djh8CY2Tai33TUw}Ob+=~|tTF`<+10>cV*v7t zHSF$aZc3v#S=$6iwoX}R;5F2z(0z*+)93h}6$v-hLlou(qNpHPyiHkJ941^PY>o5G z6P`L)RhdANNT6k_J(0l7ZkJR6XFfgymPN#Ay@WAa{HX-o6f`%}In!u?&r`hkLx5%I za$Xh*V3{t?o1ojuE+27Sv`t&)_qG@N5YVRet<>3duw;s|<7WcgSxSqVf6>Jc7}K4O`U&>EWu$oSZiT`j;gCmE`Y87|{PSi5Ad56l!ZL|3hD2d&je9t?2Eo z#DsWQr`!w-!xseNVZ3^YEyuGc6;GYW1M%T_ehR;A>3l3-I**p~2uR;x@xpI$<$@)$GyKI%5(QcQD9rXn zNvIvi~cF#-?+RFTCKa~i%s>3fW!!5qAJMwa3eUY8|6{iKg7dkXrKvTn(Kh@>Ayk)|A zX6s8%`zjV-X5oAc1mT13$tPHlC0Oi&%Iu@4BH?Al<0CX$IgHw3SF(`VQYPS%#mv@w zYvUs{)p*lL<_=oxeQ4=}=Gr@GuD?s?NBQU+TN?R+VT9-;8CT{@ZhIPy;c`u`x&0{V}I z+S)P#bW6t!1R2Z{&^-TGd>u}_rPoTrZ{~3xe))t&y_CYjU}aIdN@tL>u0X3E0&-jd zm_;3z*Q;}pZWbBWe3hHlzpBLevs)PLKZDUek^xVQkxV=}OL9)g_~1E8_rys5c}$Kb zQ>Rglu@S079n@H>oX}KikNOgOG}ic{wl)%_Wnm~N3`bbl4d`uOiB&7U!G5E4Fy6Nw z`}eNFW}SJMJLf|jJg^1lP9H;R{6!RHdZH-9jl>mY*{4xkbRJC=*U;4xCcyi&pJygK zo(A;r(>wxnE}jkK2pJ+7Bv7+|l^0v987_X^gQ$BO5%XXJbs`&4 z5WfM12^&!Q_%K14AJoOueRDv5(ry%{7@<7ZmO9!qs4nqDP1yxXe>4p>VO=+cqrT!I z>dMZcmZYZiEGi36qdfmKUAw=qq9ve%X~}OR5}>DEn&J7|Jatb>4C>fzLc+ji*9qTu z7P*c9E*{P$k}h2<^_0dU{&PvvKu~9xa~=jfgO)Wrly8y0sWVT2Z0ZM z(%08afF?M;swR*nVR9q^lP}{iKJ`kF z<*TtYU_4#QL?-3oS3&vDDua0byoD@rhP?u`0yYDh;XE7AEWD1F>g#k0)U9;BJRzQ^ z^zd6xWh50C8>^(@RS6x7hgqehSBv!Vv2rmHf3P@0&d>0g}dWASeY-ze#1HPuigT(Z+KWZ<+}Kj@}_My zL=)0V=70AG@hy(TKwYGTA3$-=9r1vWT^x;dv1G}n2_La^HAvWsxz7aXCj&g+wp6$_ z#KS?J(IKqpa^ZItaPE~>T6cW&KJt?Ptj;30_1Dk?ruWB7-j3HPo%fZRO#7Qk zbzkutD_G1`s zIe_QQ`|+%C51!O+M^D8zbd+pGXQ@73_C#WWKs))o852A-ZFR?Br4gP~8{uig0Svbu z#Aw$cyy`nl+%=P+CJTCWv=2c+x2R$Si};Kst*minNwa(7O)d_$oE4ng!N01X80Bvb z@LNxL)S%O;M^8d&X*3=@;0J0KaPRIFRFucz`BR?M|Cqp#gU)6jl&9-b16zx{SpF&N zD%`!c6qimffxFXs@$Keq+g9QevPysUv!CFnKl$if6r%819c2GSnAI5``B})A3@6eX{bw z7(akvNV6Z3trxaxxY1{3K15WsxA;4@uisf*x@-d{XH#s`TZa!nR1XQ?4Cpt(b$Xo! zzJtj^D^P;V7JDLVeVY3ru@!wsNCOINY+^b zMcJN64PA>=>SR+xRv`kupxG5b7Gg&Z0oor$Nm~fc{KsypLout7 z9mP=JfU^7xsHut<)-t~$9v*fRhYlKG|Gph!p7TMI-7|70@EeS`Zn~2}5kn)=w8_}G2U|q~)MjtO{aZS?d}b~DPOn3oa5XGbqbBeW+=)yjHJl@@V#{eM~@m~pAlEEeR$|=fr2CxR28_

hC&mDi9L zw~;KRRY;>@a;VQ@7#q&Ry0r_%7sWi!x?|y@`FQWW-{Yr0B|r-yFi*vQM)K>oehGu! zy6`$u;pzo@>@!%88)sIdIBo{ePx=VZJZvXG_qX|>t>ggOOZTBeN!bAmwq6w$ zHCvJFpJj;ggDrl_&cj9qLv>}mn0p%)?Sqieo4Ehr5^i~)7GF|Zw0OZZU=>I;^?!|M zZaaHFO4nTe;e+>Z^7tNPrQSwS&Ry{aAzRP&Q-J2#6f=O9*T#UBFG$cRhdOxqEeQs6 z(G;Mo1)#-j0RnVyZy^oc(@;`OaL#^&q$F>6U)>BBn{Q!y_zi$2F!NHvnd38nwzu4l zpc@Mb(uVSI2Ysv!{6^5wr}5vt5+QH;NE!zJ-meApesTi z1z#0E(hUva9|2s$BNEm_NPiT34Z)Po>o_0(nI|yt5-qQYzoWCx!udox?~~#oA-C{| zB>2${lAAIf%>RPCN=C~iJh*=e_wQdM!^Ml_y!c@N%RM@``}Z&4p~!Pltb0hyz=!fU z4yMBK;66Sr@l#Cz=m%U3M7U%7IH&B~Q4tyivEX}xOoD(ej! zH=NjGV89^f>35p)-(T?c_aQ*n5%oGSF%pl#Is@^o3ICte;Ti4^9BMqHn zR-q(uE$Z@*qpvGTJOpI_b9dtnH05nUOWr257O-qaYvEQ5G@m6v%OSq7qRGnV*Lv0b zSDs!~U6p{0%twfe_ZL=l2>co^g{umHh z)lbO6<_Cj3rLMa>Pq;S<3&N0*@epxwH*o9HMmSsl0H8HQ0Q&a?=*1Gywx_n?{+0O% zzPSJ~fjf}%*bjL*L3o^U25}G8Am;88LTedGDCMu>@r)dvH_g*1 zOG|=j86>2%BydVN9wgj2rNtox`zVx`$D*Vp62(QlO(cyFBgJ>4d0*Tal$XWQx;T{b zbiIl=l=1gNsG}??4y3ej(y7BJjz(c&GztnL1w8qi9W1#ykA!54crfzwLWJby28-{H z5Uw!qZT+Y%t{o8N9nIu@3Y}&M$t!|!% z$1k(6{EsC6eSum6x|RUlhVd7%=&Rm?uClFY%HM?2l=XOcdohd*=3(Q;6*#(S1)2!Z z0|e%N5(afQ!MUBJ;+F*I-K$}2v>BJ(SJ6;^75Xc-V64Xxn5?0OR|f}sGhDysIR$98 zn%PoTE)Iq?Lz{(NAZ%q%JrESWXZc-P@hQW}TJ*PEMqTz6l&7snb~HhlVC!>vKI~2{ zCOChL-~8s+WZ}IFn`4U*e0`pH)jBWBk1Crx;vTN02DlUfPYGlH zXK6_kHL75wrQb(Ff}eo&m8&jTxoYXO|5$)ixhyo-P062%^HOvDo7O3v<$VJ5-0!}` z(j{|YV`+?>%)8a`K_`e8MtVC*s0{e&zIer0yrsr~E)=7Nfxdincd&n&=S1^E z!?I~W_wtlE0(3(|im-HZ2qG!T-tZ$py4%emKyP>>prz$ZOLlW;0NUo{Hr%5+5_o++ zBJXZSX4)-eXFWuEk_V#itwx03VuaC%D&)>01l?Ll9sUZkBrS2r*9(UZ?Gwk+-?0UH zdOG4|B}0P^xahi+_BRiqca|eD+7an#?6dVnN}>;L-EhGUy^RP9y($1$Sn!CTcN1Aj z7RZb*I1ejN|V%I0Sy zM@@~ejYbUoin*P=*(=jyCN)c!E-w3a&Nq|aeDgJ4m#;LIDn27~=6pM`e!WiE=bwN1 z_k<~a#2zW%=J6rjh3W6)i(8|}rL(U7|lCCTe>pRCgT246r&XEBZt zpj!ygPYBEm=}rQ3F9|Pe$bxp?y$Xj9Y@iCe3}uO{&{MhzBVCRHsLzM$1)#59vcT|@ zM1nT|GQOFFANH|z%&rRp_NyLDj-=z&iwGf;{JGHKaEuQHW9(TlS@{{$fUeEjg0hr# z1n5=N;Fbt$*v5RZ@QpH{*}}6qPL1u_Jj6Vtp?C&=wEaAiB99_2)C7@12XN>5PJ%0c zA6Kk)3c9 zMd@a!$ahC`LyVZoz#nFBsVHSX&>#iWLj!{J+71`CnlXE%`H`bHDjL=FNFu%vGNI z?R)r+^tq%jnD;rQy(`nd`vav@=k)EAKIadV{;7ukAr{P?(HG49n2z%`?dJ>8`F;NR zN8;hz$`uO?^ zU%&eg`1bvOq4bVp>s zDuS#8^FvC%dv!i;dQk^{^@td$@XJ^0*R6sM2`|^LTZ!#kSHs0(0d9MKi-60E5fN;K zgt$A1kGX~T*ju=E)sc>?gGWJ^2!QvIk$eG(p*zXiCaXJW1(Jhb7hac0lJIaj;vXz0 zLt-_OBKFfc-XoRW zL7mmL1@OHzAGf{cl2J1s*UxW&_bm(RygYHs`wXt#aKpa+J28L3JP?$zV8ML0h$p}P z=BroVe)~09#cUb#@=fyQw6$y3=6vwMhy3l1zajZ+682g17x36`{oeO%~G~WMu~6ak?)J)x41qe-ojhm*DPUhQmj9Ve9sFSiN>B zz9j&$b;vMQVAhnke)UV}lV#+6%?^=dNyJB8Rz$eZ8G0Z2p@vFBy7nSF}*3~5n zSn=?;tTal@6o?AH3g6pKxOna)&U>DKv*lvgnSKPj<8$CX#X3m3Z` zwEj!j9s3CGWbu2s?}e+yw{SN91Ri!Pan5ZgLFX&DoMe3sygc^6-Rf(2Sbm0!9=f=5 z(~gc~j^#_|lJ)!*wr*KX7W8}=@7EKrrnB$4y@{>oG~w3Z2cL5OGg-`RA@dj1p7CEl z_&dcVWHA?$HO-?3IVYMQ5^_4fR5U>A2l`9U(VhkV7DP==0xI~^u&J&{h&X{87x%&3 zbR&)&ScxP17vuP$wFGTFoH(Kf(?hyAVxkL^eL67NzY&%vcjNkHbHs$&B0BI8VuB8m z<$Q&##s^4G_CieX9)#c1L$KdAJh-zJ{x>$^`i0H7c;P5)?M$(C-F$rW!B6q^`#;9l z@BJ8Gz4sHWp7&eW9sLZKT<7D?B^?CbwIFNx3c^Vu!mi@Nc^homyjJ*p6XI?l^5Fr5 z`z}EYjrQUnNMCnS5D6_go)cVCyI>Cw zPaEjzZxOBv2JV+%evVH*`50e+&H8Nk&IU5;--k2-I``MVew*DK|4i}^B>eUvgPJYs z|2`n??Q?s5Z(n&Qe`tGTC=wk6=oYf>8uK=xDsux8gI7~UUquaZ8IEpRg38~$h4x?k z1nocnF!@~p$PGxOnnfvg%oT~udmK~LEh z^i^)haL+}&nkW~5ZphtApwl5sf30}>9(a2Z&bX`>-?i4$)5V_MJ8|a8aYy%c8{)#L_c5z6ThNgRiMFIMu zzdMp+`0I1m@Hpi*a>Xy7?u*|(iJzyEJkH>0Pd;>gr{L*0mq4M1mmHLI6m_s>^w0|p)lmY@ z9WDHJUpiUO{CP}iLGuTY#8=W-$a;SIgkS3}6@X?qGralD!RJF2a+)2_;vfrppuZR$ z9a+N7!}EOQOCj;%MIQc@R(gsrqQfsE_~AK(1fECG15Z4>>w$ZIu6Ph|8iDuEl6WG5 zI^y`4o0Old$P_;kAL^(BsKe%AK2K4*jiiJdh>5yFoi;x-JA+%doN)f4op|uIjR5_{ zZ~p%O`yglh)5qqM%||6O)-5lB=|i1Z|)=zQ)fdkCLq7MeSX2%W%mUm&KC2=?M{66%E^Mj zZ2L7_tiFW9sn20&PGYeHj?TwmYkwRYH?75c@4bWf-}^m&``fqi*00|h`{IkwCTD~9 z&GIHdugUxQ&wud&Vd`fjKPF*Nv&-W@lQ5+J-~XDpx6dsCbXg}`uOrVB(BEW-p88Yh ztT9Jhl^N=ajv*>&A8uUOMnjvOh&_7(X&0@LaM}#fE(Z~Ay8)55D-h$l77woI;^A$5 zWJVuAU#%HlblQtQp0FQzVxmtB(aJIpPJK5+56|khp@Kku+G!JZ@7j)!KKejBfcy1Z zKPUMamMr=Xrib;(%GiYV!cFKc--h9C0`w#`;*Kk5E!0J0?nVOmdgRBgK}zTfJh;6T z=ErxF)wB&q59#C9`5lPxS%8E`dyq*(%(y^3@!8K1ZyvfWfX{`waI^UeW`{q8vC%g$ zr0te0`3fI=@EZ*{vuk5U-ul%q1fYZNo)&PsFS*d)P$=@ ziN8Wa?wbT#A7mt5M|$ElWTknFfAwXhUPV^QB^2fapg8XV@-wd^FZ~L|@1de36cu!= z5?UW0eH{@Ymykh_Y^aVzTT?t;3x5+MRdg(D1@q@amET!FShzU&Z9#suyMip{3Nf35 zVa+-V&+ri2im$7cpu3y@e8Vq5@T<-8#Rz`ejXxF2ztrLvL$Wd-AS2Zusfh$y8W|2{M65_#J;$57u7lrBeyA?Ji^iH@Jnc)wQ@shy{sd@h_yp*TR9^vw z=*a7MaNi5puAIV&V>;qtD^E}R@DK07VAlqu#(9a4CGiJ+nf3fQ*C-1l}8> z17VQ!->VCA15v>L@uPTAUeNSw$>RTf#lfhfdoBK0LQt+M2@xN%Zy>3!ilAi#S{wNr z7)etfeUhCFe_LdrCsVjK#P>89$RzS56#iQWe@v&0gnz$Oh0&23ynIn9^cTbBc=@tg z09#nq{L1&U3bLXLAiuPhgO2uWw6=05B|9n!Y3iU#qePwLAIoNEvOJ*p0~%QbATyPJ z9_uGuFnKwTgj*;#`yuk_+Vk_m#7u_FboRyiAtu@zp#EeEG`E z=u@1r{1|5}K8B~&SGeS%k82lb`wJ&=&FciNoHd1)(>k0!^$Fa}KYHbCKDYL;(R$wl zyLB#+TsW|M{l&d{Yai+?`?hVx+z+sK>pM8Q=N%l`{d<_`{|+X5zQLh=8?k=n9IRUU z6%2Q;!`@vwul5;iDP6pHe&6fheKU;TB&%00tJ=DL*>TaEu^*}ZX#>Ar0`#}DYuA&jZn9slo}j>i^sPfuy*_;@46$Lk?LJ=ut{@j8r+k6gF!8GiN4p9)z-z3~yUf@AOL2tfB&Y{QG* z%LM3JyzIM){wh6!_7)-R0%7SW+Jwd&9h4=lMt<}P)+hfh zq#+Lc_mNJ5H2ZJ)AsbtXO%4351+o|$6Hr~?gt80+l%?-Md4`nI)ZHjZ&_{l<8Ckgg z;^(OB?#M_yjf_|`q=xN9!o!V73fzd)@ZHExv_x_4E%D*_ijr`W2!e5#h*y_Kp@u)` zGxawTh965qO|)=dv@|5j-%!=ZP^S<_orScPyLs7`BH%pOE59-Flq_HY<=!I}Zh4- z!m8%C<#;+B&l~2s!3^kgUbb*>JPy4L3k9G*B`_;l@zpP2Z@vRwp60l8-U^p#WO?E*_iwO!9_RTR7?ALC&w?M(c7G>ij}qDkr|lL(+s*sY z*tE?3(b!Is9drI>a{D*`8QZ@3Yi$4auc1rJtzZ8qZ2tPMvH7e2j16D>HP(OjpGf{1 zYd`%@SoPVDUd{dH<5xcn^u6chqvYTc8-;L}c;iZae%I^7pKeA`R9~Xl+=$f*3(Lap%pWiS<82umn`tP1< zYzkP#aT0dB{QGniw{Blq-_jJ@IrJojES)4gf0|4UE1BYnLY~vQXM+hCpoZ1k87ZWv zJ&cC3;bi6U=N$R7j$}QxC858I8sNZVj8fxcKQX{x#^dR6JVT?K0NsFBFMROoi3cVI z+%VGXf{t2y8hTsflGkw@G1&%_{Tpy(-#i@M_Z2Knm*CRr?I=nwKf4jurui*dpv9NEsx{6=( zju*2xswxO1DaXXC$Z6qg#a!<6ur){tUXEBA5yS=VMoQczB*$JyO!y^4JUoUlpOpyr zS&sO7%aIzi6lwhOMfhfv=3Sw(AgjAP618L@i+}r(u*KX^6Gt$PrjZbTaGyWZnL<#G zLvx*+nZX|+YHx}c7IP2X|K3ir`a4od(uCzK=6z3ne4qWx{Ixpq#k!}t=xL*b#>GRvPJ=qm?2zm;uf0tjf!m5S-^>_39FFQ=Lw5 zosgRVZ<&Ku1hl2bPsmR6K+)s`6i-XT%;I#+o|%a`1nar8$0IX60+tp=C?p47G9wNJ z*#?-Hu8Qa|tDQ04`uob_zVBWi^(mUmO!4|v7Cm83!pbF981&u$#80393x59cUtl`= z-{7zR9|)8wKw*^hzi6K&zec|QzYw5DBS}8Wx8+|awq^VLGyG}WUr#;-{GSp z$y@v1;YDEf(EJPBHU0uOl8f5E!I|W!@^5fZ{-3Z@`k$~?`d`r3QtB7Je?%raqu{Rf zSNd6hkxBa5EFYPC>GjCvNAjoFDXI5&@Ykb#h2N?7_ojXEUdY}Lp}zb4UdrEd>3tQV zuMeUd-@4fjAdGUTMJ}GaWN|tmhhP44uwF2~(DB5+r0W-3V{nl^JeN-N>Y{w4<6Xxh z(Rm~S=MIOX<4_p7TC;KU8oOq$wZNqv_u}5oMgsZ)k=NV(>LfwAgT!svIn2Si%nWHx zt>Y9ssec)F4u1ah6uHD*^ccDlhnkn;Xj3sx9V$la{+T#`Y9*e~2l(}iBY5-jm}sZN zOTD{apTO(qjd=Zx)j-5^{$P$*s+Bk&FPVLcbHhlyLYRV z$emtPtOp-=C0LoOiu~5_h#+Was9?+(0<_FAOJMFD2M&}2dWHpGnWwuWH_HR#lP!=IG6G2fLy;7yjFfOIB!}4`Db$)CL3NQ5X@sm4 z7c8IShWag5XxeIl{o7n{>d1U@$yM}zY^R$-o#?~IBfDkMK8k?MP-ggvBJrX}AcruT zL|qN8Z7u3s-)Iz2zIRg!YcQC9yDt@j;;;t0Voo3Au*Q?$2(F!z(RIjOEZDhlm~-tt zap_n99^c$xSn;c`-`ML5A~I@m_M#eFpXMqZK%QjNjV|kq^y_FRH6}IejVJR7+4gzW`H< zvXC=A9$t!o9{4GgN#<%lB0bI(g_Ghib#fA>O-;cJ0(J59baKrZNJ$PAi>7i3@RJK8 zk&~i}%y^~l&>*WC2K46G@4HuqeS)SQK`Ya4A83m0eT$4_K$}(6eS0=C;cq`d4B}Z z{5l1k<&yml^54B@TmCzf{QG$?v=!LG3o1hTLI9VS;G2v63525j4DrJGO&3f z^Uu5L`SbD|TXy+C*B9X#%r)K1%Hnw@aE(NQc6Ia%+3j+PkQy1o-!q3jNQ zK>5RZ|8_Hd5L-luHh1zA6E_XQd#o5adND9RA?O09Wwhc?ZF|jevXzFX*xN z^~)|g&R@q4oI9`ZDE}I%CWj8bNQw=g=MgDRhUCc$97HjranNmb&7) znN$3*bG;=R$VKn3a>beBi^wT&$Hh+W<5y4b3x}(?>fF9w0CULVCTC$B#@(B|T)T+? zEHxaxe|w(*@1b&^LGy%K_ZHaX`eQFJF|( zes*$E{dRKGXXyX>bS*jRYEit1Va?EPJ6TJkR3VU8E=iIsJYjT=x`w~}16 zv{IA1*YI-steklGxLQDa%+Jsq{UbC-NwUL4{{9Nn0W4icdEZy^W0CgKyBgU&>EcQ2rSQ~8(R&;;!zqfq5SMR=uitn`~2J~79&|k>(If*AQIUSI5w;9%)x6P22 zyXlYnH*ap9)4?4+*H1M#;Z&m&&NMj*P&1HuTY#CyQv~M|dmYe9IlUceCSWATxk_mw8M3GB++Hhd0An5zwav7&s$CxzI6=f76It4!)^l3myYn{F6o#A=w~uO z_r{>Pg%bU&N2l=MJ}+E3j(hi7ap(4N(Y@o^wS%MsxOAymtf=FhV2&rBJyT2nw-sn> z-9k4veh(SObneh996h`S$B&bHrW;<%!PP>%gq-t>n;Pivb>~9VR4*b2Js%4eO~u6g zG^A$4A}upstRl3vwt$V5IjpVBU~OpzCwoi8MR_7SGaPvnVhF-<VH(pfEob32`Avhz&tJDIq?TTwb_PN>T)}(xZ@_5skFu2(h1<9Er4) zC}gC?(7707rbW|sG*&E~hI@C85n$zokr=k@z*%wt%lBD)4VN#yNa`eU%)67sB}h*R z7tRw+90UE0Aam!|K3wTqjg$N1ad>w)8frpNy~z)Aiye`ZZbHyhLqLEzEUk2)tTf^+ z*Q_X!2kmW(m8HR`SmlB0bspHU-jQ6Y6?Sd32Co#`v&9K5O|!|lZKcQTEjUzPNXKkY zO`u#}Vt_?OdZ=FOiqprIh>!+5T27ba5XZT*Qb!eTRLYOy+@Q3kdLdRU^uyF#Ed@Xu z3lR6Z=l%gbqri^&Pw=7L62zd+8xW=Zat^&7cXQ9PeqGKVgtkOjF~ z0yDp#9A|#QMfYWZe*WYbJw2VI_x+T365{v&#WVVvCw!yak4tUiacGB&sQh+pw;SE? z-Ozc^o8Vt9;?>-ZgDc$eO;x^YP9No})(M4orAiTX@ z!QH3#k|EexQ-m$60nGD@KY+MnDHH$sTNEBdu^&Hv{!s>;d*t)3zl@%pe zv&0XjB~F-Mnu>Yzryw>iRMa`qH`Jq>wi~>>Jz#5V1sfYn5`mgVCr4XEhI!K8atLy= zqmVm38j~i*qp%XQumarh( z%@Lv2b&)}OXM?;(yb1Ief?%(q2=yL@2*2To4b!5}jW5ztL+P^j9uXEhr+iG)wkHg9UANw^v?k07%X2b3}5_sKge}%gp$$k)gJhTuP;E2FL zHv|Q^(6%%D{hi?JYXc9Lv2e8;2zQ4O4}3jMtAhNTX9oGZP4V@1m~COE(V#r~`^PF{ zzJjL8*U(b^20H5BLSOr5n3`z9%uE-`%A*e?+#nHpjmG z_FGlLlww6Z)?gA>#^dz6{xsmfQC#GSS3feS*-^_E*2qI09|!1JvvQs4ws>4`+GdMg z70IY6Ux4beg?~Vc=-MTu#i-i42-~(SB*{m)7GY=AQXFqwgCl!apk~WlY}+&s)ms-} zN5x{)ZCi?+l?zcBP9G`3 z@m)@$kWx#HjmRuHy2}?`XI4rX8|UkAxr^KIbAfbr&@}?mt;Z@weFS!PD;N2rC{G(P zQT)O3g^S!l%b={N{s3Js8rizy?1{x9BZE6(-zMmBDB~_YT`-_;-#9?WxWNE9q3GquXyCp$L*Uuk#`i&9!X+2zkbP05l%}X4sz2kpGz_2u8u9(vDsh5 z#3RGq5gqA4H$_(*sBx#8Lj@kPW9G~ay7vA(uEoL4O6jJ0`zSf)gWygdT-A=-M2Y3@ zhsv>M?(f2+jt&LKc=LbOUgLjkOUh2t?MFdi3>1qKR;H zq^E#pR%Qgo=R}iJjz@leA^|xG(b4__(3x2=1ndOlW?3RPRTX(@k|w06zDSSLxSbHD zdNVR$^wV&HahR`6v>on00ucct5ffpIWV#8YrbQwpHG;NTkw~JS8x^WW*NsGw*YIv{ zml2PA+{Rw@b{T!k#dgq3N2_1pWc@3gZGNS{m4R?0=k4un4nKc4_yxGbpX3+d24C9u z^>?NB&J-^8BVb1k+tT#cSC*#3ZWtR3@6=HJ<@UHyU%eSO`YR}p{R(PI-#}gETWG5N z06i`jV5$dW6Mc+R8iR4;#=^iz4|)cA-Nq)y*Y)-Fp7cWZ}*@U`|kVx04*1T z`kztqoNZoM!`;i}t-U@T(8V*xJ8fR!e7$nDg;+Vp;H@U$R+lY)TU-0=|3U30=(aYk z!J%EtP`0iZW$S07YRi0VFJB~7wt5=M)=Wp$=6R^CTttAXC&)6Gd4iFE%$XkyU7j3# zO~(ktlCzeEvlQSXjJ+sWk;NH;7tCfMr0 zz)+uDg)ef(XFx|+2O~!)=0U$Lo+JznCh$$0gt9HGFmLu0c)B~Fc%n7-RdC^cE|}zu zuG7oF4O4m1$<_1gaP~kDPB*%tt=<(U_mY#{A4acd6M=3Y!E!ITS-zILRMd-Ag52qX zGdcK?yngR0Y*`zQIYmZ@jdmgM`jFExh9Nl`{ZU_#zJ$T(uW9@WdLw!J8@SjQAUN0$ zGpB~5z9IlEb%8kE5QnbzwF1supok~n#4>Dl#P?eWilm#|^@SYq)024h;;iI^pR@}2 za!Y-lV|e^fDjCYxynasCJ#WLC*Bn~v#OoLQe)AjxPXc#}P(|yJ6<9ROkw8fwUR`Y= zPd8)iDGwkgzeOxe5!LOu4hOv+(Ovr1VcfcX3|Frm0JnQO)4m4>4pw2;?)9juS&mg} z=OQ6FM!=MdT}je|fxfh@udmZ1Jv|ovTpD%hXZM0YfxS;ODQ1_8ddhzN5dCmV$Hv~XmTgU-v1LqS0@3JO!i>O-!PY-Fq_>ZNct$dtkm zk1hYLXWh@L#t zGGdXKKsUQk4H=||!Pj*#JRJv;6CNPoECG4|0eT2LTy@~K;HL){;st??byl)r%rfmxaU))>$#;~3C%PJ1LhVQ9h7SXXGA(pYF{ zYQWIYfZk_aQFM&o&))aCuRa`${sVyiXB9hX2K1LCML>Ui40`(X9H$lY?XRyYHO9u3 zaRk+V;H;pUvL*c=CpX>SaR&6U#?{zYyBKSi6p{-p#M)&9<@Iw>zHuHF&(6mDk_@a~ zT!_j|b3}?+cQ;Qia(D65VxqD8)fv2@4}CYmL2}UyXNEA3?6&3cX>QBK`|PCYT9Jz_ zbzFJ%`~;ppI)Yo5SK?G77hLCJ{Z?4N&i>hf7QeQYHzoZX1a=gUP#hH%MurCj63LgbdY zSd(mV32(Feef_e7VB02u`{q>#=`6jM9L8vsp#17I-n=Be;?6bnzSE8L^~+NP_R|FC z4!nAKR%B$HIJOCk7bHSgN2%w@#MDFs&3os9i%M~31~2ax?)f(N9;BPr^#izey+y>C zxl70C)4R~rT!!+>rC7ag4(2bKhJ>Ujn3@_%V3vyjt=}X1za=QM7|;yow*f6l5zq{0 z3DDYfLouV9p)=hSy%7=WhR`4*Ua+vbrJINae=$1100>W59cTt8~h4AtskJNN{}Yk%wSd- zN82jDKudEJboJE9DQgj=>BeWEjWJ_Kk%Jxsb#+y!swzWSd7P{^2fxQ3hH-x)Kp*+; zyYJo?;$U%@&UKUs#Cp4YTRddk1~cTM5L+ z39zlSeG+d7t}n^Ky&|{9uofW(b+?1)gi*Q59FZZq^!TcWpdc3{CPvYRQyn9Q4-qhadxB6}QOJPig8jusS=hLy z1hc27A|lup3#M^BXgjp-a=_U`@wj!ZPQaHdy2<5#7QvbSTBM3I_DJcz-_wz z&h?$Rd9{{YWeqNORnrqiE#%!*1h6}I;bdziS`MzqzP-!Qw0kLbZ7;>n>Ur3)Z4P$U zEI@SyZ_me}<~2BRWDCxnuE8ZP|9QEAZUmev*B~YVdE$?q@RQ%9!bQ&>AII}2Qf0ko zG`@OqhTL$wfHMR6HNp0caM1MsLGS157xaI_fF?MzTNa=uI12~;oF@oR3x|D=-0_JM zJFtrW&-L`Q@Wc1t();D2+ju}nxS57#KnvIaPC|K&YamP zY9lu^Zo1tP;- z5EJEzs0eogvm1>bh>P__N>VT~(!xaic_PQ23zG@XsVJJ7j-sLr`dbR2n};Ft$W70l zGYNC&O~RbnX_z@90wu+9bc2s3R~=5yI}q7fen?OCLUNLaaK(uUUPwyvCoqQ*pu>fO zP9s346QI*Gq6yA%$jXiv;ghuV2)Z_aZX$H^2r_}cH@$9mHF&ye(o>2)Jn47v^sx^Ws07KiI7SQ~`ix-xiVG+G8QIualY@Q-&~i942sxC% zF#KoH&m?*LnZq0MNkT4@%2^yA|8L5aY^Rx1t*_6WrvLkZ?nm!)&WhqVHIE#tmaFeR zYkS2Ka?rH|)MFB$d1OexCOAAlP9J_w-6K~m;LPHX24{G1<_GVSTNWV@5~uhHK%Wt@ zXby2aeS8!TZkOXqdjZa$n1J>p*=T7M-=c!ZEFl}0f(DWHu1lBORc^D8x<1l4v zCLPbB<2jf%JqJb8vN5$N6Zr)x7(bp1-A5snAe@*Oin#b-a^FFcV!8cP0AgYT=y(v~ z6M{)0NK7Uui#T+cIL6mRM*1Km#2tQqPVn-wg{P-2-0APs#nlSVE><-1wk@1p?PMc~ zVC>{izt0hVjyxGt^aOu_6FAqk!NslUbNgje|&g@|4k{H=rm_m#Pvn< zgUJo%5;#8&(0@;DuVg@zgMM{H0(3V48NA?yM4$$Ebs~dUo~^-dnE}m{g&eD97fs@@ z2m_lJ!*F)T8+Ly5m`;!6&&l~cddR*1xXuN4E!l$;t>tLgy8`Ri&A_5Xh2&!V$Te`i zjA0l%cDOW-87jtcBsG;$^yq7X^{WbTsA(CFA6|pAZJP;()wp?WH@V}z1mXq(KrR#{ z95bh`k!u!}>aKBJje6X;vKw6|3URv88E2bix#ygNzTXAs4!F?hipy;|c=UiL>^R5x zsBpNPMRA|p_uU(fB47E+`C75K|60u|sWpuyhumz9&o=Ow2(mqeX5}f&F$Qd;J{=OnO%W8b{ zwH)RU&YHgGqu<(a>QptBE{+v7sek$TCn00~k*HYZN;j2N;11Co=HLSTSFdvQx_Vr= z(17z@%>?Lr3D75YVo$?XtlzYl06h!EbEXoYqh%ou3Chx_;GX*d^oQK@+kjSqtL;#P z_-czz?(uQH0?f%tK}byrCf6HD&RK#pJLhTBGBIODHf9uOp=9QGq^3oSpJQQR3|oSp zoxLUO?XARUYi9u)TXR@ho5I}OP~=PVgrb3gHoayo=#j*zrzw-Pug~WVc+Nx@h9n;O z7+=qhmVwEDR8<`ZWtFi|Qs#-fQ5ee_%NmU_q_N|893?b*Os__b9*L2oMqtFqVHh@i zC;@j61`Zm40pyH-9q==L`ISTlMU0C25f`=4V`=U0Q(6o96cm&VQ7)S1y%894`(60@4g;cEL1q z*rS^P&EXA>J+tJXmbqryfAzc>kFOQu>FtH0!2ip~m3Z-6Ii5ePq{s3D1nD!P=EKAL zymWXU0f8%|@dAfx9NNEvK)nQITV^6G#1)nn214d$dN4E55u>xCIi}>tW9^E`IJ|Ey zI!;xg>+E)dGZ!)9#T^{V;D)E%J%kr_aEOBoAaU^{Zfr{c6(I|*0Q*1$ziF`pXIduW z_%27Z)jJZXognhjNoSfE)ULR3HWx3SwBQA&u+h!s)w2_LO0ecOS`X;;v+i80$1N^Y zBz`tQ?rH6s`l&PGW|4rb2ELt1(aL01o9;XdSeIZP3S6oNKqU?e7yTTTiiR~$ml*B`+l zUI+;E5SbMmANKKek>uknGDujw@9W3n*fD2ec!-HU=~`!adO5wtVGC^q;HwDW6YP~3?js58WMByT z668k`*hdJ63qaG?(G8>9-odsxC@3(^#>T2*^yrb#_}tK;gD{k!FV~PE14TGw7#$x* z4xB@aswztNH8nMp2v3S|mIIn6;5dxHaOM~<1CgC77xVvT5U12Jm=#wM{y8}Fzlj9} zPOctq*Hbg%u#x`o`_16^2Wba8=yO$g^SFW3i0)^Hf!7RX1~iLdErl}B&D#uY0!jC2 z+Ga<0mSDCEch3alcAF>eobt!*(}B3z7Jysr33&RTnjX1NkrO3oUR#N4oilK$eHuDX zOhS808d@8|aPnXQP8{8gimmgoVBSPh9!lp-z?_*`m_KJc)~+nVkpmmhexd^BPFLaL zIfnCgTqa$+w3FOwy@)M~P9k?Cx5{mwt`WRNjg1ao;l?R++t7M!3-;~Iz|KwfSU%5{ z z06Fw#+`PIEzsXnoaZ}buoX31ztn_2Okj0T-zdTKnxny>~FE};vByDrZh@MOYXyq9- z9Ovg_9OtM12N|5@U(5S%$X#=oLkfR%ifVON$?4ZsWgQT~w4<{%>>b(Vo5IqH%!#QwjE&XkW}{Ayo!mUf zob?&PlGrh8>8O$8CIB;_b=2v+0Q5c=XXllwsw%gJj~Gty9!BSfV#v@T7(93o1`Qhc zmiX9EIyYj(@NRW=_4DJDlwAo?eF4qxnL`>JM&Q+Y48?yT$!lQzcZ;F?_o>6d|MK$l zogADTuO}o&VZ*w)|2RPRGvTGn$zjJUmeDSu2kGS;f9;7pT zz!hhk*|9p{42xYwD z81u6>a>@LDaVUaA780PPtQn3a)5s2)o=mvKST|q8=jbLV!W**Z;qBa7hLYzh#S|X>U6vyr3cU*+(m@|eX>@x zd}?aiii&M3v2yinlrAj7bOLlwh~qtQR&>yB1G*Q|{R5gO3Dx20qK?Qgd&I@~A~D`y zxaV{NVPZl6!ooZe5#fz2g5zWYG{>Gf#8EOc7c*y0AV5cudo@Pk-8RGE- z^8~S9+yx?jdc9 zNkV4}*xG2o(rg$^4S$8P{!cK_{So@wKSEFYSLo@CATX;!&p-xi0<<4>dH@#iXCQx?HM4YBEXtis!{7VYjWV?ZG~2cAO=_?wRAf98O?3 z%U9_!4F6fgQ2x(>S^h6KKi|0*(7cG`U2y&>_4j>#=X>)anIpAPIJ?INXLehooyLv^ zJ6t~Kgc}6e+b6sT)C(j)zh=q89;EI!CkPTWzCMbFmnY%Iad%ul=7Ot7U2y5JGp@IV z;n{;Kk(u!9@c~?G&mllNmACaL+xCtzPQdEgHWzH*ZBl{YKR9 zU4zPs`ItXD2outc5a>$|$IVWXt2Cy@d7!Z>1vf6%;NFb}f^@TR&rjrfcv!&rnQ+7{ zB43$973_XF9P)(&umxq1Ly=l7zsvmPCtjW~6R9ds2A9H_vy>NVt`r4+jvVv?{o#32WC53C8wy@2iw zZ@d$Seh1JJr1kYw;o&qIQQ@{oi1R1+%sJ1Yh>G-rE&+*)YH4Yy!O&0#Nl76h23=Az zUW7Mhk%LZ4iI7oWgVxvABT!4}i@opl$B6)a^xJQHvN+`7 z4URo?h6KB34ka+0|2{DMXZ)9&Kgr47(V-X6{ebiDrr(4A)&;2Dl!Tq@J+OU^8_Jfs zlH9Pb(t{xFNRW2N;~S*}=3~H15<{9CG^gTqlbe3?lCwPy!qhkj|jg1q>x1qUdv#6R@SGycr zHqXJ_;s9hOYQWKC1PsT155sY!vER}71LAx&uy;!YE}q$f8<%#HlddO7?)%VL-^U>UTeo&`R#(Rt8=-fPl+4|E<5p!d2O z4<8&Om)(Nfw~yi~0s6v)dYnJc%ek9y>hvzOw$_k~-iF$`wIT<4!Qvv6%#i?XV$wIn z!R}cCwA?)_=0Lv#Xdd5zwB(?@-L()C<&30+Kru1MfOd7Yh9HlfN6zpD9j-^=cuDl2Ixr{s+d54&Pr55I@jrlRseLk z1Zj5C9QMf0Vb{!|4Jo|A&`ydqMNH@zLgf@@ zeo7AV5kLMnpsRHPHZ3;8#0*Pvr%uSta6-uxKO8%_6x=fE<~4F;jfvQ}*cdD3nq$va zCp45hqrSoySI%#g8l4iHAKZ~zHr>0~jN1g_J2yCN!7*NjHphLX8pt=UG?RO7!u2b> z$b_NJv0%=Ups&4iL`;5hy^RycE3kjxM(p0T64h0Uv2I;4W|u@EC(RlThC`)V8nTLX zyo5W^UmJ~;={R?C6E1h|Ah*sXUAgA+L9z0W-L!~Hvx|Pr85x}V#vu%ugO)Aq;c$eM zvn+%3YYtB^l-cESJfA_z+w7!euoe!PCuAAg3~YAWd=0~x&oR&?w=6&`LL!{*$Z)2o zlqcLFg>Do)0r~P2IsTov*^z^rXR~nk@@&#V+$P<*vIM_9XjB075nQGBkr(K6p4%gf zLGQw`<2%rDqzbh=$w9AW2VI2XS(6aQ3so4<1mt((&~E`+A;du+ewG9RhJyr%UN}pD zHZ;&dpr0+`TK#Esu*$2bpm7A`K7b}A#Tt=Q4iiA` ziA!h3A}!SqF=46%=aGmE97%v4{W92l%wtdIQBNJMhrMyKA?HkRcCi}>CjzvSE$zGL z5~SHNvwN1spWW@?>PCNqcFM4|90(ipUtw)Npxee`@DnSup$`po2R_qO`w?1d5}YMK ze+O;#?_^GzAWVQBK4PfI#^8?noSE^bgqM#F;?W(R7^}sx<}4IXGJ?B{5p1o^VQXU!e_u!J*j9qGr?=zG ziM6QN=uICKO@sv6B0R)ZtP)F4_QUDpYXpGVMgPV{=gFx)yt`k3k>kLRdBW|%5#f%1 zySHCJl3n)otDHW^85=EhyoIje^W0ZY3UPFG?(6~dE>XyTA=a)f!Tk9XF=cWxoJ__- zuMeP8LM(B3?|cGu87`fx#kC8&$l*88>*Ko1T%_ojaLz(cc;(*-f-#3P+C;X8sGUvl z1Am z#iZkJ4^EIcwUH+vIS-v{a~u}==%TvaQ?7W&BR7g|?E&=NJ4Z!ZtFErSJ%HvEyJM}j zXgRtab-Ol@gPxDlMbj~T<|M=?h7q6*1(16I{cimE?GT3|2nfyuWgg!Kv?dJ6LHl`X zAwJdxsmVdeNDD!>sJRg(CJ3{$qTo(&V+S1*nuN0Wm#7TQ-Ft;cnT`;S39fjK^GG~!4J zQM%;D>E~zi3c_fyk}x$b90@U&hzuG{a31|CDp>P;u)q0ke;?a2Hy5jIb~eWKT52O7 z8R`szy%oXPW&j+m2f)dG48ho3IA(^ktAMjDoSY0`XEg-27Qe#5dgx*|aV6NMuP(1V8zgo@fY&id#!F*V|z zgbFRM`a0#l`)?n!5yg^vLL3a}|L27`CJ>Oc+Rm`a*+(^2e%t><-&Gy%Cj(Y zdLZ<4#)`TboLi}PIW8vX7@%DIheIWoF6>6z ziETKzf3qmVT1kNBqVNkA6k=LYCY%Y-l7p7SfKCsy!qLWM=xnRN#f}#7BJF?m3) zoij6@Jtn98oMGH5z$YgC*x?d{MVg#|E>GBj*jdenLY6!B(#R@o& zk0vJ_E{ZPkF-YCx6lBi zqcNVEhq3}R_D!B(+q`&j(1Ce#1I~s9=)N@4{t0$wKf=NMNBG+Rj7ZPni19Z-T#%Wh zKy$$Kf982Lqin>q&b99JTiPIcPRH7>>MPtnx#*gTZ%jH~S85 zrr*MizOSdvD0teb!pl|-p0+BquL3vAp>Q?*4lbtOcKg^4yAj)-4Ki)h~$jG@2OWWjsF4 z*EBo9&nz?1pJkqr7+{f+L`n{@NKX#5OiPiJni6CsS4v8-P;zRpb&t}5t&`G1tP|5h zY=mOn)U`v*e;C+T;g&xRU`1H{JYYqM=db6^t@^I*)H=@K`1}78fOfEdH^lMZkZ#8- z3A@ge;n|(-cywbMsR~bT@4$Oeq5HWk)bZ#5?%m+t zeRVi~WHV-!WI{t@T+gaC4Ye_%9si;I8_--&PJMMevNAm|X7o_m67KKlL#u=%2Udv` zIZ=<|HwN%=a>7Rm+7hhAsydMc!3_bpP|yh)$rTc~Up;Nb8_p}HW6ycHG*^OqbV7to zxVFYg0`vhHpergCVD;*mBK2z8^lSq3I0Zm|3Vi}}W`qrn?^}V+Qv~R<+sH+4$Ca+# zBE0hG-a-2QC&(=mbm`|wF=qy}Y{HJi7y`mPvB!{PI5SvfAqo*+X7KWPhA}&3zMhXu z3xA}2E=DB-^s93OR0g!%UGsG^K#Q33c>!Q~K_!vG$Ke&8xTLQYa3;9(vhf#mW8-Uh z;n3rUbaUe;6}stgEsmQv=!SNY0o~98=;N)`INVZ+9kpw)dM(GGrwc%Hh=XI$!a)l_ zzsEt#V$biuS*EuDO_D+!8VK~(L2`lzx#v((_jv-rnU{8RNJCwnz(#P+%S-6V;3zI; zKu^GQ`aexf3Wc$W0kX$)b-M^;B#{%2Q$j+t@nLs+-9ve9-@I5I@x{x=E#@zuKFNIf z^l9F!CG#yY_=kVPuV4Qw27dFeFdO^t+#|53cVJ*o4?)^C;9i7(MS$U7y8{hBc^PQ< zDTzmt=q32K*M6b^zf_E0w6hXL=l=$O`dWV;<=Z4bI>(~z*8zr~ivE872A>G|>3{OV zTj#H@J+%H8JV`vdYyLajH2xhf>i-UBHSR_D7dWW=1$N4RfvwVCV5R)GH+moJNyvKt zITM}HZ#;BAf9|dO$ul3JPoMef^~z7bSN;Z)=runJF#POUpn`&oXjBmGKMgYa{ArN! z2P8Wm`~iiSeDQSkEEn!c`2W6pZ_UE^!wq~Z`mZf+vRj2S`ar6t@t+R8Yx ze~kd3sC6s@G`H~LObH%&0**65cnLGFz>~rWbj@SQO$#?m0OHg(uAj`H=jGi}7DuIM zt;8V??i{^hMKR{g&B3JHKsXwWgzgAgh+~)p==3mC9Ns$zXIr=6{OJmGo~}mcnOa=G zR4;O%*`dE6r^>I9#ji!clAy>dCq>#ELzdkwFOl!bA!jjw8OD5#EY2*T%#vkch;s~K z-sg}Ahd0;>b2=S=4=D!y`c=DlKez$xZ}+Nj`^pkrJei5hZRxnyQG{!k*5S&<&A4-$ z3nCrB<@RE99Z$i9)>OJC4HsKe&~+>coyRh8wQC)&UEPlh@({<_dYm}9L!{X?Hf=?D z$ z16)K)G|u4g^mIUApgR&0f~7p@;%rQxF&;(JGR2Z?V`F_}WX54aZWvPIwUHP#4nh8w zb*{EL2PV3F(Y-$6Q|vD{qxUe2-d}~DgkSvM?{rj=j~^0u3JL7nIphyZ265Vcx1);G zO@+Idc#94vQcpteN9fw8kK| z_ajv3sPg+=RajEDl-})r-rGLc1sVK@yrT-|Vavs7e_VTm9kskjzZ}*d|8M+60<&4*zA!sQhBHI* z6**aU)(lQw6!PF!9jjk{-HN7WRRZz;ygmBlD2PC{mq5gZH#L5~3~ ztLH2L9ioRryQkw^TRFPgx8Y((H75n4J}Ytc-9tI+#O4U0DE{mtk|&J1;LsF-fQh=!Cw2j?+dG0Xop% zqRz!e`#`q+XWi=}KEZ+VewxO9q0p1C4=8$p(a&*$ju1mc1|j*ex4^_wfRQ4U-x32_ z*6vC`ngOW*XzoeKfOhQx^#6RP(49nz98rP#uZWJFRiD&I)a{oC|G>a}DuC?izS?ZurSHS3Y+M6bTD-xol*0z>9!b2o;{{L1@oGi}B0-vq2g#0c z_5{0Yj#uC6nuoLdeMOUirfp8BS#OKY%WbfET`E?tDyB!{c%&s5!p%wr7TUvLp*2(z zZKp?C@u&4p;^*1DQh_ z9G>9J3l>9}#n^jfwB0%pJbvRD8 z)#2#TZ8&tOLS%8Qp}*7lyilcNBH|Ll`T)8Y()|Ov4+#1IT2Y4js_=IohopEHv2u_L z^5;&7BUncwEj1h&8Bxg2jv>Wj;>1MoDnicQ;21O)MdGF09OB5zNu={qh$A&t36Y_O z$K7mo4yD+9_GWe1r``L@%(`E_%p#KwHy$R6nT7T=NpV#fB{lB`s738DSD_?$XBz}$jTHku@{64&+zxLTC(fjw7 z=$Lpf`F%CuQNAq`oewhn+ncqs9p4Z}xgH2h-j|STgYXh`1~!BG&qG>-I1~U~r3h!) zc9pz<(%%!@{d_Nx#j!jMYv=o7;9ss{&_7Q`p;C z2?hGvU|-#M+`CyX7J_hGS*)5P0Ej z0DXQA+MC@(AIJSwHrTP=9GjP#Ve9%7tluyPv*)BDE8Pa6A>Q=p?DLi~(<0Hddk#Gn z)Zj|jF0nv{bFeu}lJ#d_vVa#BaPxkRP=Pfg6zVzQ6xeB8U+gpOlbXsoow))i)0P;7>jqyYH) zdt=<#(HJ=JS0Sz$?BnBssguG{xxxZXUFOSftW%whm{{?i3DMTIx+M z`bd>%akY9~DdsPpf$1{~5Gz6)e;&}iaP9}t9E0}JM@piXaL(g%Vvw5~k4XgM!opNh zjc)q%EK!4lM=8Z_0%p$46S3%|aj-3z;d}uT@8V2IUc-Ky~D&u+jb;zUJQ}z-B0dY)2rF6u`0>0Y9ss z;bZm{{LH_75o|N0Bh+rhu@JivM}%yLA9vCF;kJ$1r`--(pTbf5Q#k2-3TNFf;bQP3 zT#bH(o6s+CGyDavhCjkt?+ZHrdAFCz4|l^HMjwc99Mc%#IJSYtrXZUUN32x8`psm_ zUtzASAeFztT=h%RH!v9U8T3bg3KQk8VN9~p9(dbOPve>5`~9~1bI`rV%#Aef1>39C z2iT0+7icqje}FBGq#)Zd%|W(fSxo^}BdVP>KcC{P`Nb3$tv=HHVls`BUFFjLlJrF( ziANzfoi8QPIZ`2Qi}O9lX$xfAD(X3+=V6mtsnuwbeomKPgi>oOO#9-N1+ zj_qhaUP{i*5sRkl(TBwf(P37I3A08)wmptD=HcP(Mgi#OkB+?}E z)e$j~t_TToMsOgBZYW{FE|`!RjOIPF3DDKJe7+9XFYgh#*z!DRuFoMRC+X+%Ymws4 zocm0m=F~R^-mbynmTGd)QktDSiz7CXCkYh*O)wUK zmVsFsxsytNfbMnA{W)lkLG%Afa#Enk;t-RBVP82 z&3*tpU6tr2XNRC5R|E#SARxdE0fDaY^EHEq(=fO@41VqHrgGlP&7{uT!)mjKt3|n! zz1}W0rJo+Djr#^#YTrOx{afg2d`C|OBVcNxEs7_Znd|k+ObbSOgJ7WjJq&e!dE#iN zyVKp(W|fzx<3eXgi?uphV-F4d<;&-T2YiYVLqEsJVV`5v@GmfCZi!0szBgE-`?-S>0b6se8M-@&7l)GqoeU3l=Z+vc^vn>NU@pk~tj`yQ8 zJAS`bw4&HSZ(R|C@}&+~Uuugb)2*<)#2P!-IijP{30IGX5umq_b3RBwZW2&_{-B9q z-GnE18}R53LwYx^oEnd|Jp|hw*4STRj)u*qIJ(mlmpfMA*0p+EZeN17dJi0_wZYyk zR#-Vp536VEWA7#_bhQ@X@qGgRZ->RCpyZTK3OK)h!I=^SXxf(pnw>QRT3*DSLCx`J zP8qv%s~HzgO-Jiq7aXax$AKC<@#w#EvkjVeO%yrN4SVLGe6z>>S5+Y z>Bh2gkpqtJFBUaFu6EVZ)4^_0V)Vi7W&-p9*=v+0CWVV8XWs*8a{kgp9|M;mEQLFy zv^dF0OYWF~%Z{7R%a0MP1(11Lai4)MyIu}x64y83wpRDm00TCa%7uu&}-J0VgUnsRv}^%`T$zyp5LA%WI)T(?B0UF`{B$h;0z3O;OTCS z$Z+mE7=(=UFp>K_VZ02`q)OXZ#Ker*>UQUC=>OXe}Zr)0A94s|@4RS$nhzEj# z-D%qcfx(^xX%~1Ayxkncf|PDYn;}nZEr#ATHyZT7K>Np+TB_d?oFxfBYyLzx9Tizs zI|BkUL7KN|WEmSNLr?n`XsL6Xt8ZUvsQ!FUUFDY>V@G}eV93DF-wgWoQw$mSDTWRH z48s}H!@t6qF#|A8X%xni1`Qs7k)uY6<=!f)D$vx{x=Zi-2OP9qicY$B+s4NF_;=rZ zr$(5P*W&0aUcmCtCYb(|akpuewMf&6aBtYBshB)M~Q~>Au#Q=UEgg*|>teWyg z*z$B**_lb2Xb+)WfHEQnu6Qsrs4j@d3b)mR&vnfo&}&E?h|gB0sVv?u^->t zi>s$65YQdbUT=rfdu-9R+lE}MA8uY;3!YrNeQ_1e?e|7UlLOit$hGaXL2I22PVKeF z)%K}){)pqxM!J#+8eE(RO$; z>MINot ze} zz7;i9^RRYh0oJc6B2C5G{#p zuAX4M3#Zy@1f-7>r1$LIfQ_5yW9jmlD49D2G4YWwHa2)S#jY=;g?pAH2f>HjGXq+W z+_s*sI_zvskV1gw-h)}0G02_3-BVITdSnSNN+B?_X3d_6*>eiSD6eK`W^Rm01?ea$ zPR8U3=9rYJ#tT(2fdHKmuY}~NF^CNr1#TD{=s8sM6!dZ)1Wy7r%gbdX0{kry66%T2 zFfTC%hmb{W zmtK>hBnuu5L}7lGi7B@W8$*Ep5vodGgPX*T9`OZ+5BW@hncee{fuCWh0Q8p_J?a-x zdQ>VwI!crcOi$_U+8ax%L`@*fyLywFDg}=A*rJ9!?*fgOi7*6&r*>jxqB924RI6UtPN>}pj0zk%6aaEvgC#(7t8?WV>f7<#ZFib zU^%cQK=XMypu4*zKuhuMUO;nZ%kyV#c=qfpo;__RH+_uUbPFEbZx!{OyUy*ziDP9r z-m)2o_pigjrqyWKzZS<1Z^Y@76*zmU3Z3oSMFqi&UAx7qOP(Y=-&rrUyE;e#b$}0NoSf=mE4G0E&QC1hWKZ7B65@p~rPg3w;sd z$jOctF=%$r+;?z#@p$2uxj28xtO=MsH(%21JW-D$JtG$87A7btOcSL=OJ>AiN}dJs zGd0LXt0N~_18K49h>uV~RIn04{l+4|YZUxEM#9H^G&yG#&iEiGdk~zx5f<((gET43 zhvZ9;_JE(SCET4=K@J)==D)z)=qH%y|3Hu?C~Fg_bq2uDU@T1KaAq*~h~dnRT3^(M zHZtb-YaBGx20(f2w-__>OA*o-I*8yrh~fM>!TB4E8ucs2j2$7sEF3h4um%sr=+Psg zrm74jrLp9$`_|(4BVq?Fx#$l7TG6e_!yErBVmNb%L$N0z*NFaeT~%^&^IUB0?PO_o z3RxU~bVBeCLHv&bdMPe-Y{RRE1n1j3@Z{DGSw8eGJh?->};KgIo0k;_bL|ZJW@&>(#Vhjl0)t@ZffX$j-QTZ4)k^NW!IKQMhtET8x)@ z`$R16U0y`a^stCOzZ7}T(j*+mc^TO3nt8uBt*%X0A&-0dNgYpknK)-4?Ax~)8&;u3p$FI)mT3 z)(CEO#obgyDbe4Kl2hj!f;2fPZWgZz((-t-04PIOKH(>YFXSPLUI)y;<OB2U(XYx972&o9Gqq++FLzmP`BgpZ^uNV*hjye#C-zw6?y{bI9)}* zZzWE(R^a5Zt!O>E1#RT6`B(?%cXK&c0y7ttVxY5&?mV{}=LpgQ&?gAcEma~HdiU;i zsI6OxEoBQaWokBDUF`^>hOo9WhNHb19PEtXV5>``A#81o=(s*?EH#C!Ec9SWKw{`x zTN%*4J}hY8!c32(P0|wkrY5=sDh&d<8hpI%k&_i6V$THy3}>l(im3ZMbAnXCZe}jI z=SifA0?xe6fVQxd0L}df=glLBJ)6KjH4sw^{ZW`7jNI|uI?IP{;2wyLaiJTy1HwY= z5E4uZaTdjx7|Nkxo;}+F(4i8b*-dji+Q-KZ?ruhKa?pT{)mT`Vj)J+#82UYwNty&; zU6_+gHmCQ=+`^~_&OLx8v4b`wKy!sU9bFY@XpDr?xB(b7@&}9<{ymAt5x-#M$iWyj zdYD*4AUS9T^hgXC_>1VaGIYp53>@?;x4?R&rl#_g8_50%bz53m9Qo#(Z{3o{Q^kIk;0JvL;)D4^4S}{;|?pll0t0yBnJAghUdZL5G@Zm!d z6X}hHx|uk2d<)KYYZvMFqSt-<+IBp+vxmMv z7v86z^RR(l(?N2tr}6S}10LU6MNb&zG8fG;=)(k14tX#{ISg}*MxG43LcdcpUAtb2 zSrf2dJ)tL+`?SwJ9|^**p6sIi4Rnq{eUZL@9bLbLzBhxplb&Fz@$B9vu`f!A-rYj) zUm0G$IECkQjIo_r>BMXYMeQ_p0pWfPuCEbx8pq5 z*d{phYD*3aaf4iLj@#9_8|TkA;B5PDFkgq%oZqy{0CZh%SgUPz4h5q$)s!d(#=>WJuYXWDj0M3|cpcjjh=hq{qmNiL#6 zY;>fD=slPa&m~5Kg>#;i7mvb%WYG+kGd6fake&0)SvdsfY=Uwwx#WD(M9d*b&zV;s z@}Iey-S`O!V$x6)Q6k4ZZAOmhQOMw)KA}GjRRLcttlqLiN z0!TcP{ArszuSgwLT;c7*^_}hE=4JzDXD+mF3`@HCSkTSKjBY#})-a(P4g*-;Ma5Wj zP|+1KGSLxWHZYZ5=hJYbZlmWi+|sVFJn{MzFY`K567oj2y-FpNC^Kftp9D z{nbz8tO?r6V|bEqzk$B~-k*Q|@#**9eT(mez5#FdtM4W8+JylFe)&yPQ?uw_{^egr z5T^QrGXt4{$dhsGRu#p7l#BZW{-eY(X9lyp(+lTA^Wv31UoRw^0qsD5?#YAhAD;gR zaUOI-SvZbWS)gT`Ihwba;c%rnPVcft$6i}>9q_~bD{Ba(O$26w?==SWZUN|9mv`X$ z1)fafBKkGBaCRHcpQ%LWnQdsN$7pt|XHU_wvo+{AQ$@~o2RTy?8%Ps^TosPNEHWYp z#tdiPmfWc{NyzS59`2CpUogD69>ytA#*|(3)5phg=hgwV9^+-ntFU7AER4@frN>J{ z3?4i{T8@h+ z(s83>A~|$=y$@<|t0NN+u1qKQdKkZ5orxPK{cz`OG`-FP1kg=*cqx;{4Fuc{ym+`8 zkFJg<@Ky*&KfOI0_dCJ}yyXPg(|CMsGVY!YqU#yLr|?MZhmt#QqVp%{`%lEZ&KUZ= z8|mjA!u<=GxYH3u`v>UvZ^rG8c)EF}()+;gCv9PAO3*YFacR!(;6*H4OIlZt!z>(D z;R5!`P*EKVW#uuVpP-V`2gLmbIsPm93XT-@m`9ErMkYXNEyab41`Qg}BknCIG*CWD zX^-5hO6ocI3x55TTrffQXL7gGx#k*^_y?LCVeIJ_1DrU9s3&Je#_%G`0A^# zMBhSgjisut)NN^HvESc6V7#HB{$6s^FXVM`xbwHj=;5)?vBC7ZMvfTvNJB$o4&h1B zIm-bphqK(Na-3J5d)&7-A;*9Jkzy!w)&{56$veHsLmPh*&>Z66NkVxH`eWnHe-EI` zz6Yn-tyz+dC9}g(Iz1S(rUYU(Jr1s2;ENNrRybSlh#T!Q@Y}6=+$BeR_u3xZyDp8_ zFYG`U0r|`cdVFr#h-Hf=(W9a}J@(na)x{cat~O%Z-OX0W)59KqzRn0Hr?O#Pu?Qb< ztqsmC<^?Lx3AFOnf?SP_vol0E;UzB);gx~}aiJ69Yq;Rg6Ry4S_ylg>+>aB-D^Xj! z97`9cA}hm5JTi0tHU99##rPAT7vcmx=AS-UiPNnsacGAZ4)1V9=c$Fbcy29D?DfRK z+5j9sycpNIR-k>KFOKX9BL~WEbu}&@^+nshc!FFd?q8Zh`(8NF7>4VYtMKT?Ok6$g zi}s_FaF=8A*Ya_-H2`OhPQmRPb-3G^hD*o%aQ4I;JbKuS2bU(Gt0e#(rxw!33_woz5h*?+?Mn^Bd?r+JT$xF=%ZF!j%hK>4~EXS5AiESbYS6b}QXH zH=^rE5Dx8%r2R_VzDQ3Bjc(Xm8HlrOD{%4bLhP^c#O}%%T%?=n{d-4o{@iXHKU#@P z7YNLknnj_c%Uold9CcSGxoi&kaMqV zK{~nVjLcY}^o$s!q;g-vFwwa?GSZJ+GxsEPhp(@TSU%1b=3HFJ5!2tUld~0^oGeK+ ziftab8@CM{94%pI&pimuU}IwnOG_gWPv%%MhbnYsZdej;ljvrkrLEQ@sWZ2#=*%q| z&WdVu(oJG4x#8i%2V=<4fs*KNm^*j(6=!h#Krm+)&1rUA&CbHgd|yC7z<6_W^V%_^ zN4}7H5)PIvSQ;WmzLAK2gk)UgJqeYS#{QJQKy)?nw%aF%z^W+1X#Wic4# z;`Fu;iDScmZ*k5ugZa-dPEq`qJzgH-;554rIOu-d3%B5%01stB`-otQgeS&BKv{8wk={ zapK5Qf|dsk)VPR=!t-ZV;rJdetXt%V>C>|5SSi|?e6eCd7-r8R=w4ll&O?4!S{jKJ z%ckS{*@-yaSFn4PrBHb!MY(YcPsuOdu$3BOs@tVr?j9&o02-o7-{ibRyO)4#%>kGjQwL7F=wN zM(NB*tX@@uD_yJT#u0?+Q=+h~auIG`UO})9CdU~=KYJyvbWB5ir58EZI5g~CiOc5} zqkK&O@+Zcl_4qd2yL$xNYgW?Fo=A|UC!Ed(a?9kLxnTd<4QOqOqwg1qW6fzeerPI= zADo7krtvtmHx;c%mgD5f?I_z?3_CkhF(IX|r-AHLSInJ8t~TEsbEf%Y-fVW&S)zc} z%;F48CkH$+O%oH6#vzxKm#l5KcY!G2Urev5h+KYtVWOxlos|`d)U*&JBnBWR)(=t9eu#|n6Jd|=2yc=PB1k-j zMflO^FD4H;4jmZe27iA?czavX-16Wxbl8i(HSu1N3ShB1*3_^d8 z1au2aLzt5|E^Q)%yP*+x4`-MYtW}0#+}Obc>!Bp6(>+fRDoTVn$aVipfaVE9&V#nH zwrsSvv8fuTH14+%q9@_d9&v9%?mswW2*IDk;O2eS@ZrO{Ra8}OX>02w{$Kys|22#- zr3h%no`mu+f_zCeF9wl|o$G&>`W8(3^Z&BsfEEi?J`jWc2LPHw9Q&%`(7e?iJ62g^ z&w3lNeWcnEr*_)l%pM1Nd@jK4OVzk`ejBcIZXIwMfM)&uPXuJcC|rF1;*@%Ml$*m2F}D9aC^*mp2L~#-MszDQzIi(KRQhAtJQrkUCS(7;6*zx96=kdaF=0X)&YaqaOD7q~L6|ft8&@xuX(RVVFC&kR1M8>?-%B?;Vb{YiHv^$6_3;3qoc(-z?_i^wE4& zu5m?bYK*vHb+s?T=9K}+%!n10{cheoK-VqC#EF?Wa=46KHN%-5bUivxuRzOAH+s6T z6FKDjtL^FU!=BzJTQqKS#*zKAaN-Gu4rwMj%dCp=}jRCKY5zD$G>Hv`IGf-lh}OlQA{dOh8!z zvKpr3sAKAQMQLK@bYB85J7|J41A6{s(b(0}N&+-5O<%BR3g(q&lcNvDv_e;M^7fcG z-Uj0{t&o{wj+A&4#77w-I$R$SA%+MKwIn!ukbEUL6Q~8C!x`2D=tu%|xDWkZxx(Mq z9A0i}aB~_7XS*S=w;BW+^TDt*9R>?CCAv}Q!dd{DJAF&tzFBfeGoX0_QF7l}bfX&s z9j!soQ2hbQW52{vsOnjC`jvOKS3@WQAlOxx-r>&#) zg!>Wpik-URet!~KG~L$L)<(9|2mH z#S!^oK+E*jQt-dCwwEu)*<*`vuWJEroSjR~Z8omA&%^D`Qe15-pvUqYg3V&wxlFE( z0e!9#S3Btuo5q$sIoPz&7>lQAW5xtEBu9>hlMUUW2TKr^t3OEV0AxX%zH1G^*2Ts+ zy2BPH_qgK9*-|l?_~<@&Ea9*RFRMN-ob;;~?c}6S3im8IXm-s<2+jw|MKhp};LfeX zqMsf+#J$_Iv2lqx3Uf@58l#V_L_^HXw?@t84D4%Ig+u$-qMTIYZX*+G~! zYa(`6C1A^Pd$Bxu?V9P>R~LhorH)8R4ktimV9`uFw4E7H;v zuzP1I8fthaLnqoyjv7f-Xxex+%*a*m(R9+RsSa4Q zFc%BwXQQ~l5=9f#6{LZjWOc-ct05_x+g8zyV1_?A%K5bUo_Kz0$3mMc7h zL~xE^K!>`(-$xr>F2mvBBy~{X?kNsdzlxMQ3*(<)X81GAjEBI|LKD_DrX(}rq^(I3 zq$N-@q)kmVVW2kzx|%;gOZ{7@t9(O%{t9D9eTmT{z7(qmM-8WO1c7?Y;I{zHnH$^y z*3eKNIyyQ8Vs-Em`gc?5G1kAm^m z$VfKF)Tucr%#THUq&DJX%rT?55Q`U2A~)wiPRa(cQdbHahf60y3lwmJ`sN{s1sSRpLL9xjgbc&M57Vc35S;1eA$k(3Nq{B? zpOY*Bnj6N(DF8aydpH8UMj|-SgrMwAK<2Q96yjh99Y$k-ua4Bc+j+16w3~y}e^3r+ zOA`h(FJ7UMAZ=wuPFg^kB?mOQXa=;oHjMO#(t9WM9^@5;8U$z+0yHmL;hbm*&|hHW zFw%%`$xRO?P!I2M(4$6;fU1fTxHsX*k;8=}?hD>ODr*}8w3G)echB<4L7o_7Kyzq= z!wLWA{u2(GvpD22=zhT2uh>Zo{e2d*u*5=@j!G#H`qp+lx> z{@gB{ZQqI3BTG51*@%&>K-5!TPw$GU}<*tTUNYPT=O&e}z&+z^HJ3ytWw1-5R= z!TNO*=@HuqdD$MAkei0YIA=rzDIp`xUxXb}66_HjqKeG)P~_5isd1>fX#by;m57)K zV?>8)Vth^_Qd7bZ;;)Iw5Ci1qrO{)v2i>?vAw0ww6DQ>$I@$+8ej4;M?CE?K?R(O` zDv}c1kw^Op30?>f(m+~@Ke^l##6~+KDntX>S<&KWMTXfREJ%|898dcR1bzoZh3a8E zK{qQa4)M_zhzZj}MrN`ozZn%_gP2Hbq^Bn$F+NZ%htAASMt*({)~zlf$G#CKPt@Sd z={lTgU4cWjZa7eFBjCJ`;M`PcgL(q=?yZh!+C2^X_HRK|`FOf18zCpd4&L4#Ffh;) z|F6INEX72Pj11uA;oJ%G$n92PXXky-EEzF;)jrm2|D4nW<#dF-S zX7v=TqQ9ro8Mc^Rs7=zMrynixUR#){ATo$U3M$akRYKkbIiMNNQ$);J?w|`NXJO{7 zbWF~(q#La?smPj`q5d)_Me|`wjK+hgAe9#p0b{$PgGNb!_GLg16AfSkeKipp<}Sc2 zEmrXnp^cCbC-}IJ5zS#q-JUMPpL#fty6b2&{DFn>pqFNbyl90Rze=kMO=;i4LY2TL z3w02n**%L8hlM^&j7Gvh_eTL}eeEA#8R`yrV4yqrhMMwEzl|FH^_!9GoaKP-f%NwT zXim2qCSuS({q%z{KtKQdBWH{JrlG0+qSqb2&rSDtoZbHaAJ8&D+uwMnqss5;gQ1R( zU*^pcdC&(7arJmIx(+4a(vd`5IhKUWqzf%14smp?$Bhfyap6oEI!|rE`BPhQj&yYY zDpZ%x!fJ9o^XFv4+tZdFwKT;f;O_xiPkR_PF0v*NxX~lEFFH@o6NQOxUvCufeZ-T0 zLIi0Nj~r`$cwd4vyXV_Cxfv~|i8bQVg*`ZXh70}F;`q@O*t^XiHS4Ufb-6j#Eil2l z#g3>bn~th&^m|t=#@6*|ST@_3T%ZY7EKR|J1?d={u8XuJCjwX;q9Yy1QH>*rdLk_~ z0YUzz2=?JJn7&9#ih{ql7JS{weZ>YKJ}wLa^vE0Ft%BsFaKuFW!{1AlAgwLpzybcw za3?^A2Ivzcli=^?NRSza&>%A;CGvR(c)E-wfZGyKqu}dn4G-sWhzxf{OiUQOz0All zjza>$H99&3uFiV!bRCDdxL|q|_lLWyKHQyE=zB#WDk=cJUOMpeRHxS&L)Qe+_pv5` zn;|hF5~)c+m@+vDlP0DjGb0J}W{*c@*<3U?u0zY=avVRh0f%vxxVp>fv?G!f7%$_i03&5OQ=&s%_II1l*s7XfH*Z+A?al14ux6Qwgl3Cwz! zO|E$^x#oFO2+joNh0}Dfa5_sD%St`4Vf}QhT~mlfGwm^tpv{^ySsO*UT9}xwN$ytz zUaqR-qLooF$sbFWPQ~IS(qtezXzs#oX=Q?f$y~D|5&1br1Z6e)S~cXP=-!MBHQ(pw zV_V_nVO#F(XtvkdLi@a}`KUJmo+Cte?jRYU1H9?~j~A^FoaKP#CEo#lbmMUuN*eak z-%In9kC$bIkC($*4>#Kl)|Q5QRh5R_(@^~xCi)VfxjVO+$uM%!dcr|VfR-i+&CJxv zJ@b6b4+Qdo51s4{c6)m{FZA_spXuh}xI|A^bML@kzkf1lfCOi`iylE5HEIBf0sSL> z{PBB{^)YM}r9GQ}XzL7v5^!416upe;t ztG{ratrbq!d*W*QBHXxGi;L|Q1n8|e ze_8_du>-3J@UyXYWg+Iz&4!1&HGNPy#PJ6Jtu+Me=INuU%mN3i?a^_(m;k-22hhJU zlpm6d{;gGHcL+e=J1i=={r0d`7S?FOjcbj#dZiH;yY`@+0L}Tj$B%EuzQ&o@U0Z;f z%3PFh$sw0K0cBffVJjDhBCT6H33I2Jp}4>Rb7sY0+VnVNC2NyYb|BD26L`r%2P%;} zbrTTv^)^C)*BHb_d(pWt0;W2BNJoo_NRI9LdTJ7|>H4@3F{$M3rc57lEdq8Ff&yLX zQFt_he07nW9EX4aC%8I}C6{K5*w_g8`q;wNVH83Ft!Y1!fNTXf$1w;aw-y;03=cPB z+NYltvDo}SJyHqxcX>meAy>0v_#Kwn=A?(UA5J~fTL{{$?U z>5Dn!hy|F*H7{T|6POpz(3MoIhm{LFv3c`MY}_ynOXoOZ0i7=`k{~^IiZ+TTX(Px- z4f=Y@^!uq{R&fxPt(cBw%V!Xzr(xmZ=>%vg#F1af)$S57G0OlG(o~V1taUHk*XVGP zr}E(pzj24=OtwB*UKZZAc~eAJT$J8REv0W@p#BvMHNJwA@i*|d`58gD7V45ljW zM&mw#iPGO-OfnkxR~RXM0YiGt+9N)P2KUn(`weu*e$#ECJ>>_VO4Hp=GfiI&v+I_3Y7-IF^^LP=w>?xM&yU%pl{hY=exy778}`iX(t!oXqcY8mBEx_eQtanGguBV%*DOUjJtb`3Qi`?fW{F9q z@dT&jlmJA9=pfi%1EHagV&ccoOPye71Xnjlf{PiP?Ul%_n!?r9309U`u(22oXD4$w zIorY9Oqu?eM~nPe2L~INn<|TCzRu3Ju(LCVnekXy(W9-0hcoS)(YevEwN|I^>jGO_ zQ@VaEtSvR^>+Q*18Nk$N6l`tu;X*&l#>M~^rek1lXADP2J6M?Oh_82Yw1hqVEMsGJ zx_&gBvxbeW1&j<;VPr6dzLy<6Mw`+8IC5>{=yf{4&fXH%R@x-~S#%?Cv4W3}1HCS~ zNzl*o_j5%AJ-R0*1dEDs1qHmMIvcZQ=3w2L88~{RO!RdWjeoiE!oH0H;(O@5-A?aq z+164_FG@pJdMM&!z3B$#jgTNG(XpMoanGAG0juZJvloFf;n8`ISnn7?b*2R(% zJuD?HDbdHOMP79CoQ2IB3A*!~u#mvLV4ALg^xP>rm_>lkP1U5Q12wuKs30dhfB-#% zR7_5KdJmv^aY}w+2BsFpVM4k-vXfL06=u{L;-+^f$MMV8Q$0U<)3n9x&5P%m-7jBG z>R!Ic3WLA@H~jqN|G=+b{STOp{)^O6#o(`RDS#y_xX+?vZ~7`g|F3WSWkvXV3-xp1 zep#V@p}+P@D%8*0-K5t-dVhWGCleRS?=9B<@3NkRQb!eMwZFho_21y2@^7$H{x{et z{Tr;5{-e9MV80y7JoX3ZcaNFqjP7>V{^Yfn_J7dNCh7dgYaa#q%B4%MPbPl7Ec)I1 z(cfMNaKA-TpiGL}z53*>?Vz{LN#bL{MxVY~Gu!DUVU%6`|L5k-RjXv%^0K1xOp-tU zFC%*b0owM)@5Z3}1NZNSIesV9(dX+K(5n|^WB!aV%qCJqe|jR~%}Q>t9InzJ&6e=syqYbOC6) z8?g!D|SSuBUScjtFt2q?SS(~ zCgDm4hc!0i+{w-8Y}+En13M>R!vZUMWHrFF@!Cj@-*xh1 zeMiOf{T=JOFF)3I?0e07L{BFD9p@#)Vw=wQY|F$;i&;JA6~2f39LJKs|Ka=TQ|?Zic%LWnQ4Hz6568 zR)m_=FqWYw1GEf^y@2lRNhknKdZ%fuW?w+}H})sZK7f`Wtq5m1pyhoD{dxc`gLI$Y zhb8|V-~RpkY%A>dzK1esD_o}lXkOkem%J|_uVmyjK!&v1KO4V{n2T59|7n; zs_hkv(SBqxZk=0ztEcAT>gjp7es(@?(*BjUX}EA~60Wu{#r3XjVv_LusV(R_%_BM0 zx-6_OHO72;bmctgwCFK#w3g*T(}!HqH7klipr*g7uVXHOvZ*#zzmgxlOow#we z33qNCA~2IvCI`*oj{EnH5};cIxNizTAC`5Yu1815Zk%b~jT0wo(b7^$kKkKSU%vqr zl}icEC73n008^%oM^0`ET;1(3YUE&gZ9n1XpMH2pJR7b!{@(Ha&helf zii_ispKXZTG=h1&$*~A8!9C43BRt#%MqaTlS z&X3R2*U|TX>Ce*t8|jmmzIuOq$$bGm1en=5_l7rI)c&2|%ps1y5S;%)aF#+G*2;f< zqpz*htq9$>A^c%+h{HqYGy1uIed(?9*Oxvzf0Lvu$yY9VZGJKZ=zsD;$Ur9AruRc^ z^B8FODM_|%z}vF@cg9a%1oh}sNk+0!reNdGp0AnZ^o%gdla^n#waw=chrBN#*8<^E zqw>Wx4C#+w_T3BUKUvLA-mg&T4`gqA0PIqlT@7A6Y!tPiAK&6KqkBb3(fikSiWIv$ zSL(zv?@Jw31nEj#I4h;u9c`Y2ZR;bjdZ7>I7rSA6nkC$v)iHF)fF4IC2XbFP8|aQj z#o8zwX~@R$<}7raSd7bEbt1%Zn;bHSF(gPI!2P>N#Xe_j+_<)nAbpq|^nOvh_{^C) zw6*QPv18Su!D&H!H+gQ?pFkCRJ50 zqw}O{-d-*i)07j~%gI2Ll`q1k&81>7%G9D9Oq(%5#GKcxn}fCM=VA>(dgbbwShiv& za`RGPZEcRJbW@%)Cka#Xj8K@Zj!Bu?kK)6OPfiHdY?&3O(mJQmx^>gW(6$ZhL(j)W zXui=^`3gG9UqDagOE?&QjR4zU5aO(aFjqB%l7d}G&MFA78w5YgZ{cV4!}B1AQKv(l zR2oB_R2x{q4$AxNw12*3uJU=eo%ZK&&>`u54oCfO;A}Ji&O9+_JOoaLgW+g62oCx` z!CvP}(6!yJ#y{N&a8NlIk+eZJu4jb_=}2;s$ysNe zkc-Z`a7k;0Ty<$Ax$3M+4mb3lIWyWtTYL0K!YOB%$gAsdbvp*NV#_OzPk)??PR|}M z3vqA^`oEwj;YT>_?G;OKv3)C^->t@@>*aWOtsK8ytH1-&ol9l7b&+(bMifR8`Ojyz z5uB@V{&Xcy9$An2oeNM^R!onylf{AzR~N3uF&Klna+au+)jJO1S{y?LiWoK52(GP~ zi_<5_jkj0hVrMNbb?uZonOtqe?HdQkDIXN$o!jJ|X}orsSG+Zndp>|m7n^Xly-sS) zbhHA84sJnn^G592y^cQ6OR;Flbo!8HlXFfcILCu42Xc{{Q6mP)0R7`TFjbV|amDj} zkN4f~Pkqn#{a*iNlEb&}F$E~Ut+xUF`DdTfd-Vfm7pGy%hGKHOvqijlNA*H%XH_jk zZOtOuC&NGh-&S5qkS?Wb*h!ZPRaGuPH9=agn(8G&)zt)SPI(mDOGHhP$_f&JSq|qi za^GcT3$T^MfZn)qE@>V%kk+l6O<bSFM?iu;{Q7);T!?4NI&AiIZ*|gTqO5>2a^3PAT)xHyb z1`V{n6J1tJj7Gr1LWg7sb8{|7%B4tkU~Hr=3j6D6(zQB2J-4&g*ze+GvDw|tc7?s2 zNtuS)sI~#WeED+VuTp1~!2_lCS3?JVfnmc3kOtBJ(|7pchwm_S*dW^HG&_SPB^4o8}{ZPSv&W-*@N#2j}_r$4yTrY%S&5&j%EpHqvchP_RUwW1VXlasA z2I!9oU%Y3b%3E>gKd2h|AROPDjf)4v(AgY31m{SdhZ1r9+-eEXY{ZzFm7JsR04=!KWOMu>k8|0$dEpq{+TQ@l0`HbzvJ@#zGGi09)I68LNY*pP``Ig-}3^#Z|lcCqqHppv}{`f^!J!CH392ZO~K|3 zGf=*T{$2^jLfaM)s0q+D^mjzCW*Ap(TS&)wTiR!5EkT+7-h_i*itXf_tE-pNKEYYG zy=~hP0cQDFPOiDEj2yH8^+IgkG9Q~Zl}ezdas7t5SW6Ci9XaTA>r1hkK1VB7m0;o| z0<^6KW)$aP(c(PJp6-Mhle92>q9&$JQ0IK;H(3d)&y%B+p2Y-@e$9(hg1m+zz+(sk z+=sxQ6yPxwp@Dh?XK%#B_|xc1kme=degtZFk?&4`hPTV$ZV#s+ubgd%Jhd|)_}tR? z=QkqvS^ozZ>wOO+-S27q1?FaIu(ULUrIjH;T2?b!G>z3INGlPfe}=B+chFYXtP*Ucq zcxq1ww6A)htLUT^iYfKGc0&>xv* z_kn9`em8@oKd>*ruFbKi-{^qa)wZZyW{v9QHfY#ni`MN{IJMgqS5D2r&5PT`D#ETa z6(Ze^%Z#2nwi){y=n;22IiIa_P&#KkQV7ugzV`5P=Vjj}aCR^vFq^>L#SDJlHUwuk zWTpnAY-2Hw9^8PAGxUAW@5YsjoHExaCJAp|YZeoN3~2%ATP>m(64#61Yp#-mzIdSt z?Websd#)rvm!Y9yBX;jzP40OKR;-?jlGz2w%TFUfCm<`fI=;wEj$zj)b zzwa^mw&JnA`lIK2j>#dac&xAbo>%-D8X3fjFz!#%H4>x+pg;c5{$IDy-|rUso83&GfsLCMkdvN| z4VxB{77(mC7CjUBbW^sqv%<{T`B=VUIu@2jW9Aei6cePUk&EVXrQ?&8ksdo13E`s< z6*vN6zQYjWGfb=^4E7@VjwAPMhq$-^q1e~}L<>;UNaDP5f6p-l=pmxnEO!F8xBLaR zWp~g*$?^CD*HFSnI*Wcq}>SpG6--E!A(J zq5L&e$9;uyqj(kJ=c1c8x4;@P^b7j?{SjkE4;3p3xu`$amR40$fxf;Tw6(Pu(4vi4 zfAD=Dloe(5zaOCG&i=mw(C^8EejkM8#}&`N?^;FmcRi1!sx6DKVo^Tk(qnAN)MU&o zN)h9tk}w>qw7`iSwzzPt05`fA%A8`il>l8XCJNh*tVPrA#q_94?q+?lC=_I3tb>sw zxP0MY3>S502a58etdYZqVDzYAP#QN9LHD< zj$M-h`pRXVAS4HUx)vu|x8d-iaw)vAYZbQA2YJ!b5=@zvhY1tYkd`ThH^QQVL|Mm? z^jO$82CWE0#eMm)4;}AM{ax4hSl?0cy8gERlo-4{+r93%=lDDO-}eFZXY?ArMS8M7 zW)-Jm@%#zcxNe46dB~v-cF;S>8Sh|MOk)kX>FqU3#H1mQtlAyR2-4C-B14;j&0>%X zH!Z-;aON2FlAc&}W#tl7aL9ukbp>s2B^SMA>wFTqX%f3=4s~qY#E|A3_c>aE{`>U0!XJO^4BFvu`L6A1b^hvsyGF}sTX==!fS4MK=SWze`DsUvi{aK?C9;kxo z2pa;kAL8SKWC|3WSGbOJY+SH#)S!8ubmvju{}bkd%~0 z3XP-B(cr{eXr+KbBs>g!kc331Gsb>rH8(FNr4g*~`*VK2d%>lg3EsZ(`mJzj+)E#>5*H;Kum z=`-?>mJyHitQ2JDW)P&a;TPx&cQ1G7>1om9;lOtQ-2*WN@$tT}RMdyAk?;QzeeCsr zT5o~)1N$<`0sY-~U%}7E4)HO*D9lg6qWJ|_zLcStj~UZ4uxMd{ETpkO7H=kZ%`s_m z*euCaFOfnWB!)Cggg0nkggQisgJaK&#K@9D8w=hJacnN_88>X4i}f4kV8e#FQcQY1 zhdkz?aB?Q>?5#wPLe78Z43Cwoim_<%M9iC)irF*cFslO_fsC(9RUsh&tmbVWj( z3*zJ4k&xhr#Kd64Coq@;1e{sINy`AuVUH-T7ait~zyK@wc%3uxZwG`sbsrf4X)$Np+JoN6h?h0a=nFhQAM z%ubqP&Mb!Y6&e}h=g*eoJY9E|oOj!aZ3O5_w6v6wgWf=HYAynUyy*jKjj-@AWMrjb z+VrWgwYP`4rG=>S#en`*VUn;fAm#gt$KSo??XQ(@EAA_faw%TZ_juo9e>e4oZ{OqZ zT=#Z}^5$^8#|t^F^p* z0JKyF?lGBcw^;i!ZJ z8FZukNE~nG`p;en3-gpl5;u?y4dt2~-Utct5WNcn0$kwd=LBzWd$_w>!`0OSF3tpH zCkC+@xn~A3xn|*^L7q+!{0iLYr19c5*-~#Q#L;zzAbGk1 zElsnqVWB{hB622t8ynmmx!K)?2;MC z!Zphr^mW?qI=cp~jZrw>6pxdKCgIrri8$PphXeI_XxudcySHa!>xKkO&i5dq61Rn?U0dZk7@Ki&z$0kr3+F7 zn8l=^EK5Vgp~)3<2;=RL28TO%pX1LQZ>D1mYZ8YwwpA?^PeBam%54nj#S*AVTgw)S z@Wxj9yJbjkB0z84%x;>V07(q$^&3hFz~c#gX5?6H2$=RlF0OXuVr}8zXbpP@D*~nk zfzbqJ=7uma(Gxuixps)2o~CF(z|s+Is?=nXx2%%2t>Si7nyS#yR3TU@OYN#u#z;L4 zl}2OSxKZG?Ra~=q^k}(;W7H_tupV(QLrFu)`AT8IVZ#PtD7U#H@UlB*S3GDCeQvm1 z@4%nwvm=QY5=lnm2l`pVMJ$^fdAEm$Qv)Gp$e1ysbJf(8PpGJjJ3VgPnA79Njy|nK zBe`bUmiGBLA0zjCT2)2)h^mUpc>dZxQiL-*RR$viv2QQJ{|@!-Nyz!n9Cuc1ef9AR zRo(`)yjW6y6MVlj>DN~u0(B3d$>k_q$7yz#I=AEXqh>t2vj{4upt*DR zPTVFjpu5g&6-APGkxJ*OG91~z1Qi?7v1D!-N~ZWBDb|Lds6l^RyaMjsCEju|pbhkt zP)T2Vbl(iLwag_)zL@|mrP@gjnzJ@It&RXqZu;D*QcvECA!mYQO2kuLHw)Cnk~;N~<07N!GXWupsQ`e1U$DaRCXMes|31lJ+XG(3XgUux61DwpGj%>2)kIdC2i-F^Sk4la`M4hB!p3okEC% zQ|{zh94wAMm-C_*F)qSZjz4cHB{(k-+O%n&NV}6VJES-?J8F(Q7Zhe7Cnp}+IdP)8 z9hYEDPiMCrfuv-1%pr)5_9utzjo@Gpa>8!#^<^jQ08dYQx~bcVZr!e~Ha(*xTY|l< z)U(jZ3XV=v=z?7`yJIUWjwf>}odLOFSt^~eBqJlawCRSRMJ`#hNBa7FQ&1;y9cPv* z-2~VJbS&g0ZSP|ObW%$aGp*UxY@N4H!p0%)$>&Z=FK>JVxw5*-Em?wTK27?*FF=gmQBK};xv)H z!H;Ns_m?|ox#VE(0krN|l&y)w;rfXp4te%Y!Df0jM!*y0K^o9*QNhnPgu3JA_#GyH}gPk;Ib*x!4 z6KmGe-{0s1a?+jTp(g%{0Q<=NQA>69QFtfc0*vGYfsq2%gc^{&$5R*L*Lz&fX|^2E4a8= z!r7TeD=ALxWKOUracIPzLn6kowK0N?2!$BH%2HoUCbCmDH`nb6hnSn`(RGIObtZ6i zAwYY%{8s>)-7|+Ybf?;cV+hv^3MB zX;}$YE}4i~Gg9deZZ2E^16mGZ#Ubf;B7WAUiV_0lp5%%!m}rxy7nMUP&kxpD=XU zAv2t1D+f7+j=(IfAe2(-IIK}!&D$#o%*#YrgX7SgV#jgkvhu|!6XOyQcjg%M<}Exf z5+MzS@kUvAg8?m|OyauGv*+Yv)@=H_oSlb~nG-N=T9$}Q7Z#>r(xhaJA0Lm5%qRkK zgaC3pLzjWe?X5WG9O@~c8%mPk>n<9_1_#TU#Rj;*-=Aa9&hYVZlsRt(u#JGOlM_!0 znn|%}&fu^&6B!%~Ug5TTV$o6@nkyQL)H@4(0x;Jd(Sa#BaCYGgVq+sMa^ITdzBR~o zt3yvu4SMuhGc?ekuhSC_+S$px+w1*+mdBD={hjYmd@YAJ*gebZK{K2=zAJaB{|sUv z|L35r_)iY#ers|3kub#v^*fHc@Asg`#j3UOs9ffZvL%i*I-zQX6Lzn6lvT5{$N8g$ zqTLneK65oYsjA%;a?mRUpjR!+$DElNa3fd1fadPqJ%EA14i@*Ze(mAVuT#xPz1ChAU_04`L&8)qjhD|+h<{(~puZ3yj!$7{F#>^}s)!FaLRO+BCTH7Wa*h>> za;>pwZWJoSszJ#?i`9Yz=H9FgDKDDi(d?c@j z&69*uCWkZH*Pez zv-X%VBSp+v9&eV%nMaHmDm0uW;>~Ys*f5SibC+$7K@SouZlyRhXJ<$m8Z3G1IC&hJ ze* zHI_^9=iQsR>8mAnY_P=kbr#sX)C3D==woWGCgLK-!o_|t4E27Y52G3ZT2JJSDgyeC zN)A&+^>@C%V||bJJulzxd;T3UIQu)!`p`L<}FFyYaUw`#i*qQ!> zFs~tq2^@~(u#w1$8I7VWRm?5W!t!~ZVhMPq2y@H>*X*dSl2#M4Fxm3iRH;aiuDa~%f#!}&+8PXdzl8fFjPc#tV zrQSK@kc*14P&6$EQ%QwWvM{M29TO*|VnS{*GP7clnih#<&f-W6MNDiUBBT7l&0#}B zy@X@tOpTx*cLWA<#)c~b0^P|uyOV2nfse0~aLz0*FMAQbaG|FRXL8RRm$oOzEag2* z;$DP33spp{T5`-Bv*s)gX$d%Ia>$o~lVdjI7_|o7KqSYktE<`*pVrV&67gt;`RGwY zh2thC-tFpY-$-yaFfldRr>Uj+SVKeonOy1`YR}Zv)t;%d#6F3(H8eDy>FQ`dAfWFV zHEOgTA&PU0609g6k`krTV*jxC-Yh#g-?1+d^ z3(?;%IoStEi6O#08Jijlw<8a6^aZ5iet+uk+7DgNdfzp__jUg;^}x9|w9y0WALM}k z4A$l<@O3vpPP#uP=Y=9a#~(Rq?nsEVKw(}8%C^i!`PNbq>ewdB=8z<3|i)x6&9ulv3sVG-LsUnA&nyLOhDcwQtL{knDe^X;F7Wo=e6rgv1T2o*>N7U zC1%ae75UFASCwGpiXtrLn&+jdD4mxXW6)A+9><-vVP&BP3o~Vyo2iqu2;MqU+}VVl z1_|CgvB(pOBSs7n;(a3{?QRDL+e0QMCJm~pD$mC$DPf$_xE{&thmTbnOZzN7E+5Ac z@YS9e7#Pg@|NejfZw_zBdlAarGfxW2LmU6+x@Z3P4xkl*`A77hb?M}&NKv}qd5d;n}X4?FAA4W&Bv82G-3r#N2!hOwLe2 zLg+|1SSjW~_ev4YEM3hZSUp=GyEa;oD|SI!ODQ_f*5Z6e9l7W_ThW68&aJp?HPPVScv7>8ov}HAp9A1q>2UcS9rs)U|^M_bV+zk;R~ULK-B6JZKTx;JCD6 z9`rU&wc`{!DF)3cbt1e$qdb+49W#eB#LB_7vjn7ha**M?nm$Y1i%}20C}Pto1nCq3 zX$3%&c;QM+v=CtsPzDQxVX|Idaq|C0kcAvp>g zKBgz3T)zisK2PGw$EtT6vrMx69rQuCc(xqR@9n^&8{6>UY9$_CufoF{)wp-15_c|b z!|lsEq@ILlrPYMz&y=H+#zVXFv1zdb7EL$7j68j$M61Ekh701$9dz$PmA=x`9**@3 z?NMLhfyQ!2oIE%UT^;l@y7uAR_Sc1> zX?rLdYC=$79fCdEf>6HB2McC8pC^uKvE3)Gbzo^d?>+Z3?c(GkRGdt{0w7E&o#rW z0!u6_jUe|tS7dT>^MUj4vJG0iTog)Ku76F=95>CYOWrZl6=|y1H5w$pG zOw`1*JT97~fx;{`&4v+}eu%i7wiO$KPWgJwXpgJwW;8XHf_{h$3WDNVsa|7RDf{3o@ea;Yp2 zx=GZ7esY`ZLGQt%+k0^DYMrPB&3VuaXi*QkeH)3Z+HFJYp_SNKH5HrIjK_+_Y2>iD z!KrCa3|cM*a^Gzu12wvVOu_L(OVE0-1ZPjICO~st4ubOKW&(4AShT{BzIc8+TAPz` zaJv)sS39D)$^i`(_SjQqhh3X(QMb_s+t*uT;}Ubso~(~aSz1VnA!p+~23F?7L=0Nb zKpSJm4DX3S%R#9KOhs@i9#`D&EBSfF>-z4$?^?M&bnc_XaP4nj2Hk%5-*a3ZgZ}2L zzyANo`wQqevTWTST=SoKYi9oQ?(Hr#GqY@2%*@Qp%#y{-%#v+MmSvJrCYhO;smxfe zD!Z_|s_AxB`J25@WJoDlcDbtizT5Xbt@W*Q;zUF$mCF3(7dy_`8;+J!5J>Qe2~Kon%LFj_LKH8>k9;H*Dh zWVkcbB`|A`g|5~Z=xDMg5}4_G4;XR(vp z!HJWkZF^2PI&PdMVT$KI%QpyldL6IOZu_v$_q#Kci`5w?YMt? zFCO0Ahlls}i5rFe^Pr`Iu+Iq8_iwGjCzq;m^I`?Aoh!%X)1^3nq8Mk67U9Ifd>q=7 zgAHpE>4W8h@DOXHB>9pH3K8){C%WVnF=)CJ94ZE_EO}gcpYqsXDW9u+{7~b{l8+hu zIPY@quaXjUh2Atyl5Y^oeO~I#F=!_{9Rzrrp&&aPbrrFwEsI29wm*`hZBSMiE@IF- zwzrAd9CH3=X+AX1gC^IkNR%Wy=mWw*OJNUQRk)9~rDRDw?T%Lxa)^VSbAJq)-7}ZA zN=ytFATcp9M14aM)~;KOZc$OC0V`M4k+bG}(6*?nFGOo2J>L>Tkq?@|Tvx3Bb7g_y z55-v~&vO=;e7Y!B@4LiE&7acZ)adGOA=2Uq&@lw)sQE~aGeKHfC;(?cn7-08$Tf3r zj+6)_Cx;_3!3&YWY6vGdhxyO@F)Tps%g_Mr$NpX#&s-hm{orUb{S||m0qtr(6)yG! zYd1Y$mZ9bVZ-@URnpZ{Er|2b3S;+Td73sk!46gytECs!)@-}@$^1Zd~JWJ$j?5Blv3S^hEYBZqSBNE+@R_rdi89=LJ9 z6Sod~;?7Yok~i+1j_S|Faa+1k`0&;i5r@8UaUD(`UPh2_#nz3rSkjV%OnOrX2ROjT z(+ch`W^i*hg@>z|NIe?pYm4Y`S7fCIV*AD#oIkaS08NicaORxQ9O7U=KYPq`pUFYX zHwj5kA9MY|UfjRC1$RH`!L1t`aPk^tOHfDPrKtt=w1M z9zqP~en1b0vx7PO$oUl)W}>0C5Y-h~$jOXDXpjrCv!VyYpgAXpSg5jd33lyhptg~K z-6Uyuiv(zqZgeFYTm3HC@sh zp|-9NYu2)RUaTk_TZ_V?MdGG#bxj@`>%vi4U?3{0R2AsHD#|i@79DPLBG})tH^9$n zyPuE!K`%G6J6tr`gZfz0=m(bg#BA+uMCIZrnIdmc-NS7}D}g4$gHUyJ%h*^1rW( z79kD-bc*skXgM}K*fkH+&X?Jko`|I~HRTIq1x^FfqAaQ(Z+!ec@c;oVjK9 ztffJhW;zRDW}<__+$fwqu^M-7(qr8}BtjccA0HKPe*To>(0qfC7p$<0=6TR{xOyTM zmybo^!r@4q*&mJ*dqQz^S11l_3&O6A{#dot4e1F62n*DrF9~h9IxV0#@(ieJs6gLP zSHz&_a)@Kf>md$V3@_!r^0xARdEemugQa|&vfj4uoy9;^ZU^s^^_FdEYMs12&_RzL z`7tJp`4FzQv*77C2R^O~kPxnoqI6@_7Mi0f&kRc&La=>Hi-<$>R69AN-L?(s*s$D{ z=vf_vO>4rib#swe=DmH# z3UbiP(Yd@19v;q!is7V2VK6l_LQQQRR(H1$q!(l5>Lx7jB0v`|f*k>zZx+_o#-k+H zNYo_EOE-EE9cXsBz<<`$p1e6vw{|%^y?G<`+4bw0FDi;Hf7VnP1}&A3piSaZRpEAH z5$QM`QBE_3A{|-N5oS9EVb&uMW;6P4;r3HLjj*5gD8jB^{$}I9an~F6%FkpN0?bIJ z!{Bc=9Dx?&5NJ73D1c=#0siKr;Y-K)ntY5P%W;2*beMG~(s9-&LJqS&3A3AV&rN^S z5B3@#z(q%rGs#K&eK=}=3$o8YYd0I-h}T>jkNzh6nqDY9rWui z+S*k6Pr-I`KMA*=b0geg&W#8qMY0^{T#s^`b1lkou28g-q!{OUvaZI;a+!BE#zo~y zY`-qWx{_Q}E{m2F*QfaxNpky|;@u=AxG%W4tS;#Ey}Qf8&!1mr)6>()?p}Gp%0K>- znyGNmsd2A|IDQpe-=JUdIJ@ccabhz~S!Xr!3X)-CXNl7CEL2q|B0tj@Ig2#t%FW_ZgqP99YTuDRpDrKs>ikaY zS3mwe@6}H~m0|UAd(0UBZy{5RlW5FSM~lKJhb|&dOItsdK>Gj zzXo1OgMqBPE%l|U-XFg5)BpV|`kk)=4BqQgAd8+8KQCFqMl5>X)C!5e;XQsGNK(sV zVw+y0H;G?Asr{g@|N6f7Uxk}}_-cKt+s}kizF{d#UNZjMveym%VL&@L@ltONar}mo zSIT|O1OT`OJCUS*AC)z;YG?SyN4?L@-;p=qjXuu-LEYzb1K~I7j(7uIR0RwL%0v zp&){@4Cnv`G^r2JBv0*sR{;9o6oCGp0?;Pme^!n`AHl(|z!o1nXTRV~(b zH_&^!32RoQp}pP`Z8gT|s58dW8bj0+>7%?P4Ecpgh>r1t8>jztv4^WdoC-9=-x9?c zI%uk}#`4Z0tXx@x_V#jQWhWpxh36wj!Q0yfdipx_zYay~;u0)hQAh5%7E9YJke#Cd zba93NbZ)v4GLzL27HoAq(ADTdxiLjl@bIOu!q4%$SI0sS_&{3a;_`ggAZ zx)0LIaAx%ZS|MYW(%(cH@LKTepxjrI{2GOc*GZDx=T-o^RREf&{>kDSm~zTdUhOF7 zg8prgUX+>ZW$)zp%egq-1mw5Cc<&HnZ`1yrU3hwbC;sERL-^svZv64{-T3~+Ui|Tk zz4-cBFJ3&_j2Dl0NVzy}?*QlG;N{-;sl9N#9^1O3(b43O+ERBcO0a^Hy`~6pNKoc^ z(ETo28PK+t>e#h07Uz#-;_9g)+`Gxs?06O7K?1WJd**r29O^iP+m|YF`A8Tp916kN z1Hm}8Hwedf1>(q#036urM~~%=O)K5eT5F4fEK~YGYQolP7W8zcLq}H?I(k|nH-Z%6 z=y$=dYv4W^Uh)k>d2HxoULRB5H+by7M9N@(gCrMCfEF?6_u*tU1)<)v5f`k2MUe|o zK)|cc)j>yI@*fS+LDjv=6qCCW+E*u3_*cT2=I46NRT5Eqs$NyI3F?5 zu852dfUlo3935<6XKOh?z8)q>i%}z2ZGk1N*#u{!p;Qrzt0{|GZ1 z_P2h0{I_6}4}T0ad>=tZ0~Kuip-|8OeSkpP#|k$2=%-M#VSgq4MaXp6UxH0O{;R*i z`#<@RoAuU}@`08$;3e8)tdl3biZGg zhN?gN8IAaBfbqwF2~;SEWy0d;Bq@ZRpDcd9VP?ar9nS5a!_4~?-mgDN8bN)Mg=l&E zPZ1W>S`7bF1o!1_MLSrLR-^vZ-R$u_VRZc6drQ{r+*MsdeV(h$v1o=h-^f&6lK$HO zEvFmpn+Gk2BnAUop#dR_w*dOh8al+Wj{yDb;a>do!%6)0>%;irC4u_O!}$K?5q$gE z0kKHs%V!7h`Qv@!=HUIC+X>F(WU1v`9J{tPU{zN!ni|p(9pwcZYa;@*lx|cR$b)5P zt&9D=g}8dQNvtA#z=Z%F9KsW^%$vZ>Hwl$v&}Xu6exC=<>~_V;oh~@m>x{!&op5lo zBlfJf$M!Y0*s#o6%!4k-&_!IN1_FImVQW24#Gnm~^u#>qxwEAhvyu0N#H!_`Xlc$vRb?7VN>W5wC@&uu*x6YNIXT)2@On6_z~A2qzW#3Ho~>b~HxD{0 z6QHd!QM9`AC&JxE1<4U=C@XM7Lwy!KZUKS07%eSDSWIr2(}lJWsH#fA`1i%ssfI!86;jQx7<%^e5zc@th)8mZkkH#7RKAG+`2ocm>KZT8eyZDNG}++p4ZLLYk@ z%%hfMs4~pUSY^0}$$ZiR)`&it_RHN&Rcb|FS*jx?El{+-q=gDm-<(>Oh1w|hP;VXA zfB-8)LaAJSi%VbebU=Ag%|DjZX;B6N+R5?d00%9@SQ()5_JHwU$X54Oy?!pwgMM^# z6~6zp3tv6#z{~sX`0@d@q|fiRxwc8@!l{+mv84ek zmKC9?E(6|PQZ_rDk2!6suAi^Km9u4vYAQSrx)3K172xpRTx?jAjHGxs`1@KTHr5XrnUN?e z$|SeN^PnxErKK_8CLxPKC#w%q3MubX*5Ko0DFgkNj(r#L;|(?btECL$H)+6eifMMk zKE^0=(T=wI@bj`laee|SiW5;;5|7-BU_^%4ASWXTT^%K;tIb3~L4wGs92p%5dq*pg z)ou3dnWE({WEUqbxN*)2H#?E**jQs4)TVu`&___8J`64vbCDRKkD`2kR9B@FWOLBe zn2)BWd;#gDOUnt;)ubBXm>Jj|%c`kgE%xQ)Ccu^e%?nl<8`Du)WQFoPZItF{qcB6~ zZ)pj}_rrtD&-;6up7nIqyJ2fF_j?Dcsc>_c3U|k;@F4LVW-qse^kw4MmlP==z#aYp zZt(Rnhr81(xY|#9<>ol|J8yS`GahbcN1PpvPMI1nxUDj0%#W(`Mv98uT<}$0bu_f- z@6^>@2wgo+!mmNCx+J=?(^8)ZjfJB~V}3F=oOjpW*65J4vsJH!x!$okvnM|vH|E2i zCye_5lO{--JmEunUwlmO;R%>JZ4$4#B zq-l0T)FhNskN&G_@SJT_70rin}i$tU2tW$ zBTjF%$MGIJT-xP`8wZ^5$;v@5&SEsyri)r^oF72k zBou&t9n!Km2ED1x6h}7M;N*5!+&teba&bIiKr7}zKYJp_p-&RH58(c7`hvK*2Dh%S z!u2aFaOJ{sTs*f-=0N%WP#<{TuD%%^bWT5@hr!X#5W)WT1kD5# zl7BRm6p?Hvf;~jFmB2uE1O$4BMEstvs$!L(i``V%TTON64G=Ohxj2nVeIv2ut**+Fv*ddK=G zoIRL^%O{JZg#98>(jkJfA_gszC9#t}gikKj;PSB;TsRbla|c3kdS5V3><+@wog9Y_ z#G&2*Y+d7p#dUTl&M`wwxHeoIRbXl|2l|HeLD1EdYQN2%Iv~U$OWx*oDDcT4kAY(Y zkNGtkc&_BUhu-&3kP>)b>no25_0QrEfFAJy9Ia*`I#3l!;hIPc*Fbu#HY#&Xu(;X@ zE0<-Wv!e`E6=}jfXJkYpEZi41wq}?)b9x`3ZLAF7V5gp_V(z)b_Iowf#B}*$5fUXcR>Gowc!cp@!rx9g9b9&JwwB6Vc zi>e|s0qK%#E##%Di&cY3k@FE9G#8=1vk;)jq2c4gpq?(09R&v1AVj1Xm6G!dPzQSn z`T1Cga1FU=IN3~rodqw`<|W$WVWdlt=4II$yr^U>!FeW`77Y@o3FSN)1Zh#uO5vt; z)uE+13u>xku|NUnd2@zi&a7dWIsIcypF%*M{GkB#l*#OzN7LtL5^1u4G-n;u&`^i5 zu^~OS9yB%ov0NPQ0O+9{?7xEKrRjqK{p+*u2|&9rpyQQl5)Pr?6l?x)@S#WXu|&vKYUk#baqG`D=oyRWwhSI#!$=H+(W`(z6_=)DjnuS6A{&DEi*YWj%@@*D(==F^sf(1ER-}Orx*yPqvEIne2uFTy3`&ZVP)YEwsU{~~mxJc! zLXnhzNn0hUT)1csc?bus0JI$ex~e8$fO~0sDViFhP*q}!vOFVke5#N_)S#&`8w(dqz=C40O~JaKw=0B)Rb!u{L3$wl*0Z!UFp z98XEya@x@cw>bvggqxRYas2|h>9f_iaH;}lkC)@ju`--ET!KyA>4=VW7qRg8givH< z$D^{c2u{w9u(q-3OE>zq5C^LdZt|F78r)FJxRuXS*5Lhv`^p-8j2I_KD);4M->5eo zqX2H7h8h#DS*k)F@W0iGUaaCOqA*GLsMmh)k0J|E_03t?)iC9Wooh4f%#Osl*hdd8@05k_}57xUlYvp6!bUcmk>+Qsi zQz6xm`Fsa1oN2?ElS^>ya5J{_l+lMegg#WRh$a^o8yAek#AsMq zTfofROp&l(kcHTu^6mx8kaTHn2-eN*Fqel zI0kJXZW88YMWeDf9#v)WD98yzT8b~qOOvr?RSnvf7Nem)8}+qW1i@4!CAbl|jNxc+ zMCTj9)j_nuc zaTS$Naj$}_rbx8~x!5aLNZ};=E~3t$EFaG0EK-KLih1^2*_*3+bG<>XHOSRbtgVe; zVIfuRW-v=Y)+Qjcv_#yQGtjYP7C;tdvs9t3u>fl7^RZA(1*!|@Vg3RJCYQqEGFV&! zYdU7l;__FDvRC~1A_pzsBxFc)vZUE_X1=npG(YC#?6h+B>{-tzOc?iy9rl|vfi+2(_>}>xt#5qDZ+a80NowGa_`nNAw zNnr;qV$dAoU_igaO}=-5@^6qxH~L@~{{Dx<`18ws_~FG~{6OvZFZSW41f%GyknKQl2gp!bC?xCS9#S!rphi7#-j zTdA(jTF@somRi3SE|h8y&R5hPoToBJ)D`4V!^~N1P^OW)<vr`>Sl3~b;LwMftf2A16ERH!dnAthYaQ(@s_PUydUa|}Oxc@*D$eh6Pb=ef`a@x_z<1n6CgL`k~{ z(mQeE;szW&(2nh!8?bg&1XtM+MZ?cziajdq% zx(-WJ7aAfXNehWFT8IqQfU|=tIT|f751M1p!a*y=p!I?PJR_BS0Yiq=6LS99< zeqAH=>(JQ}Oc2*WNrpNK7A-`2EZ>xyhtMEv_>ntxr}v3HLDSC061FxL3R%L#)e<2- z^97)@GlNl7m`IL1U2&sOjzM#1qe4i&QMi;K&2i|w{8U(4njs;9tD?k_u+b4c_F6-95OTpyZ0V3b!Qglbp#Z3)vFzt?0Sa^R+XB zjg2WRt&9o!Tzpnf#GCnsppGsVo0Z)%!Jpi+fWPfhCIBnO#Z)`_n13Ry_wDG!oePWc@@@mZxLu1EtUGno zufy|OwfOW_6TTo9{n^9aijr4cmvFNPb6h*W7RLzCyS6o9)4FQZRxUzpv=4pAEX33- zdmDY&S?j~W)&Nd)sq5}+CQ^>ZM!93-nsS^!xf-{wZN>dNd-3r8Aw1%gqYn-ekPnHa z-CSKojzK@Xy9IZyFU74Z&A5KC5tq)^(fKtvbG#ZS4p-vPzEX6r$`qHVb`DmEjf+G< zVJ7MuYT)SPNFO3Aa7E^MbNe0i0DzH{p{cCF#|=JasQoM%w>s zQ@%+k#h~SMqg<141pWWa;OFCvs)_M-7FCqpo-)u zE#zf~p|m6!m6hqJsNnj6IcO9Pnq$yqBpK4>Si(0B$x-JLjP2~KMDbX5)*Z{Lu&k5k zOP8Z{Nf8SMwcjKzshV(ZX(%)hv6@Vo%yd{7e!OYwMre^vuF_mM|eDhE# z{6R416rvg$bFol$Cb{$JBx)DTqINa`SRuL+0?`Ey^Hnwi`r(B4o} zQ~Oy}bpbhjRg$7zs7hZ53&^OElD|>U^ z3pu{~uOekA|28noKYbyN!3$Le!Sgi@6$<%>q1}OlJ&D-g?SO;p9C2y48?Nqk$CbTq zxW3;Rw~qzk(>u!v(0lOk);0lV5re+ogR2DSqx;*jV{0QebXTFYC?0|SPH=HFB_JCM zFiU_o6x(hDXn$`4bfgEm+VgSl#43DpeYw@cFxZ@{w#D-#GxNQ*p2(2 zti#=#D{JS(L+tx$}#Bd5c&}DJZL{eMf)K%)E~ws-Oqi;#Vkq??%N(bt|b28OGRUc z)0eG2yge+CN)Rh6ibhR&9LkF#k&_XCy6QA++0=y11ZCFN&8;F~(%Pa#2 zYKXcbeN^Qe(3g0GSkzLO=a29}P1sq?7V>bK2Oqcj2=-b)PJJFS;&o9{7%k>kb7-Tw zI)}iTi>79t3tdbqA>i^2LJn_m{Fwnw|Nq=X1)%f9&B3Kh^U+ing!*bP)K++)ve*eF z`SvKtwn28971EN-kQi%B?@2>Mg&83t%o0&i9sG;pwUd zSI0SGHiv`tbl6%>hn4v(Seh>&C$CG8HW~nEGjn~I5}>7tuiejP;`OF(7_&*%rViUjB>WH!{*IroMExprM>XleeaudnxWf1N>Hg_LU# z4mBoe&@2u)ydh6ti-TuDe1~F=-*J2P+9+=o91+*YnK;dNnI>jYogKF z6och0u~^#{j7vLhas7a+xJf7gt;oT_@#hD(dU5T-dK}re6x%n~WA%zsq$CB3^6;}~ zO%ri0Io2ijIsPTZyk^43%NEBElY8f-M2b_U|`_5keL;)k6ZI2VTpT5Ii*n_-HW2pzb)s6a=1GPx5~ z=o#qrhd7iRv@%EskM%iV#kO)QOFmY4>`ju79V~g@;N#@&f0`J+%6(CN<;e4e=OQy+3l-UhXf8EJXM+R1cjB>a%VLE%<>+E;-?o%sU5&LX7Gc%0IIQT1 z#qy=mShhF@ogD>O(N%>udXH7+=^`m&9%6%e3ZJBuNP=_heB`AXkYi6oeSMCIJM+y! zzPXp1n;_aeQe9o16xtBe>Eu})3}|T{G>K8eHtB!pU|D z0eT8-EhfRrbRsOc=&Q+0SXyYolAN@Kr37gXg$Ng|0JM>@4gq>0v^A$fQ*8{?RYzgr z{E=8NZzL~Rq4(=>G39RV>=BqtpjJ_t&Y=vBH)HO+nIgWesVU8aX25D{@to_y^Pt}} z#qM=U^PmR+nr{yBYzYo;aNL>Q^KV;1{omz>04?%CGoXJ{(b!+ouYfiKdVLptXji&zbDS` z^TerL?l|7-io;u7uz#~N_H1xM?-~cJUTTA)EMp|a=prG89gzXNJq=-P!w%YrF5y%L z0Q${(eL)H@xKKVudEel^@-b3hdc48M4&ENB|DPr$825|A8&Y2iaeR!?BN@>2g-Ty` zF~NGsNisoswmGWv%utzQgvGT!*tWSzl)dUDFmvL576W^8PYbCPJ)2s{h%|{TcN;e} zW8=nFtXY{)hQJ9`1*Ry;GD7YmJ!B{8A#agB3epTvl52zdx-_(K%$eMBWmP83%!~*^ z3?Fi!#sTs~OIrQVPQxt|(1~jiKw6&NlDx~nr zLNhM@YBGZyv>q(TMN5!oKpTiKhvc9&psPIp&Fw3yEHl2;l9TqsY#U7`6opJMgy<#OH&)i@z zAIB4N)9k2u!OEk%TXFZsGTgql6gMul;?mhBoIBZo)5q&@;&2TP?XN`ls%!)Wxrv)N zF|pzFVO@mUx(c|uyTZ!GT8cp{r5lwcLu;rp^Nb6Lt_TY3vE!6 zt&LJvj?Pc{=>}hCB%9q$O)&i=DO&G~n2?2kj}28pbg(j@N&Y$r5BDHA`-%8-7=bx7 z%oo8SPVjc0NA7tBY1ZGo-PNA>cep803$NPRXrDATQn{%*fBX+~W{!9z19~n2 zT7vXga?mryG`vZZ#*0}TeB*G+)Jd;YRTn%XH~qs<@a>npIOTO`Jp`ctPjt{Z17~pz z0nT66Kaw;_R+qR*_{rHiJik_eM;CMP;Cv3Xd3bU;kNWAjb21(euQcGvooyoS{K=J# z1m{iEZorA%nOM_eg~nn7lxFH6Axst4<}(KZn!eFxD2wTK3h_dfEz2EnV!Id4?T;Yv zt|UMo63LP{_RQ5)IJ2Fovhwt#=-3JVZrrBf13SDO2;5ve_w12G~&BgU98*^4KpOKlm7BDeqI3 z^1innC&XYKYFw5K-=W47QeLPcg*ZOOn9;-F>d3h`Y><^2jM740l^2bw(kK+<1f#Jo z16zAI{@)}*91Q3k+uDSq-YUW#+%6$dw+ctSW%FVYqwb+T&-hriq6*8}OR%K104+^9 zXllr&HV=zi3klA}Xm2YM`8JZ0!Udp%Lwu+oi82B(16kzZXlFPRq#4jTNp!`;=|(eA zQ=5X~Tr(7AXrUlO>!*w))BBM@md7H4YGP4y>#_n8RroC$xA z83-f=d8;BU*d7s~t_TltB}eUwkRWFSdh5a4c{+TYXZ|(F+u*#vm-P-mFT2fto_1S2 zUCa*}>&^YlP;2}vE2HtSG8zX9Lz3|{Sea|W%0d^GW;!r8)q$0zuij!p108=L5FHa5xMoLY0yvXTQVBn7f8$0i5$ zD@9f?%WCYRV5>2&%eqggqO}rjTByyKri$3n>sFU?4E#UmCwVZSf3q|GHIN?S*xoK_ zn%%wK_>b?7;7>31;}4(j!ymsmfbTxvk1wC@#utyax8nTq zHf&v=jb)4DQCks;qWxp#ZqsvScL%1P?iC$fVG{q9`^4j#kKQG@X6H`c))Y4 z*+G+I7P052$Hh#JPoJF-;f@ElSL4dDIGjHah%BzAG@_bll)^MCgdf1!dKv=U=OD~?9#W&#QI@HP`XWxk?|`){bENq5<`&_aw{Kg5 z9lags-QG@puJpYOJIDlZ+e=q#J9jJ>{cRkl-qeD1YwNMHt5QI^Z3#h{K;5>aNGyD5 zZ!1OTvI>!~KQz<_Tt$V8#d5hTp5t6uohw!fb}W-J+bwOYA_vXMu`Ezrnkn)@7i5_r zFHHj($%fA(e9bPG2h4b}qj1K{-D~V$K6;e?^5MgrZ|f>8e^#CO0p?G84-2Nh2Yc-g z5n?$KVbYWB!Ow(bJQBVvqv7x|{E+o3&}`HX5w?>*jj)^iEZml4Gx=Gl)x_tX z`osV1toc4%wcmpa$yrO1ljetTAlazB4{O!;sQnPuY9GK(YxJK@4Yht82;SF0{3cl$ zYy36PYU=l+$t2svY$qp`heO2ik9WT zntoqdF>jE(FV<K)}A}REPB=ITApFTu>QxU)+zr;4w_@oGN6^F(ETHN zr^iqNwG8Nod-3DljINQJZ6-Mg`c+;b1PU23mw z#)VUBuw!d8R&q$&wU+ z7P&Zh(aNW%aQ~AP;s)WFJsvo@(;Y{*yW-Fm7wq5UjNR*;uzd}|qQed~C6>rcF+^gF z38KP{5foqwOA8H{m>G#h1{{NC2hCto2Ad4S!LU;vd((d9R(V``-{Ad2>0OTbr->n~ z+#fHzLBNnGZ41 z0q9y@B|yE695uH)cM_m?bYaWZc5=~6uyNyJbayujr<|M=3O_%dy2i_>T@e)IiMslH zQFpMkEJIXPX>2M%MrHzi;p);=QlOaoyli>BBJW1E0?_6tQk1;niYi&j>g0kg&W3uJ zT&VFKB`T^6EO{kYRQbO#nQIchp`yyb>K_9uen?VO15vIXLJ}2Lp) z)nD@Jy}puH{-ifmRN{X6|UwYBv({Xs;a^j zRr)Ha2+`lb8dOz9`nwfUyl(xkrLv@b@@qL*N)=Uj?z1d;4m8&#;Vq? z7t@LUQ#H^@b3W)>=Uef`?HWA0UWvz7EAZ?_B|g1bg(uf4@c3Fip5EPn$G3ZN`^rY# zytE#-E^iR+*<)SUwy6%w+Y3=wohs6e8X9T|2Q7s)6fSxYoLN%3Q4?^w(G%MoaqUbs z?%&xXRuhUm9ORzaO>>`t{rJ%V-20>(pIqy}jmvGgLeBfb=@y(l*^HA%8*u1A4c4v6 z7jW?Ka6(*M6kYD7(q(QX92^~BX=M#d=9?)RzRMN1{GhQryx903H)#+nTDu1-UDOEhv)gGF3Ag`mn|iq_@= zxVqZH!rTz{cIL3RH;0?6jhM&WP@jXE>I~G?W}&$$AN2%Xo;FuglY{!YT#-^VKR*!x z{%&-hg?Jo>G_UsKd@9SA*NEDKRaH46_cKqSGcz|qK%l3X58cs84w^vC%e}Ki$t!ad z7Nw!QoB*9>gv=!MSHS^xhXP%VFO+!^pevPY5|$}y68=w28u4a8Gd%kH5Bn59-0!ArnR0cZhf35X0z8PMKC09v`^mGO`zuUN`sZw9m|c}2g=Uj{V& z{=tAASn^8oy!$i|&a44{JHLjauLNN+-rt7NKIPY2R=DZ=*dPH~UP1VKl5$-_1~!BG zw@(99IOzXnfZj_^`Sqf)^7b<9+n9)>n_O{VtrK>vu*be`N1WO2f~$KSas7}#9^Pmd zOT2Gi=^-$0Pyl)Z&K_SO0NvSMfcly=czN2wz(CFitrUA6LVXGQx4GlgE+5=D--rkI zcts&EP&tBUkNF0n6pv;=KY4Tz_ik^*?Hem`^J*8aUhKrhv+X!{dMQpFUyP%Nn(0!z z0_A1V$jl5xLV};j-RtM)1`|^Q=+m2T@GK4nlrr!J_6LGj?hn+^GdubpW9a^y^e)G| zCWh%y{kKU0U|9pF*Y)?uDvHLsIO-!R)D9(iL0DWJgqF%6)RcvyBtIB+^ndT_tUz&5 zvIrwtTN=UH$pTIeW^i@3fTz2)kh`mukf)n9JY215pC#N}Ea5@h?k-kho8{tUiQqt2 zloauFIScw<#`c9cxJYbvPJ&2;WoV=?Y81A&OI1~PCWi=dC}Pk>#p$T5OhA5yF>+Eg z5D{W^CeYpVSgy+mMbTI*3DB=(Kr3nz%79kDp&t?hw`wGX>^H=`+2LH`{+w{8i zL0N3~x8e&=S&DHb2hBM+l=E=#9Bp3V$gt+sg})ur1ZXjfV^O-&JZKJ2{MInXKM)?- zy>%H@b(El`CK>e=38*fOLuFAkmNkaq%r+Zb+U<;c7s*ZE-HE$5w&C`*tx_DC+6$*v zW5GrUE*(e1^!a<-LV-;VpDn{zKzXJP8j1|jR%?f@jx;Q5FGFrloXBNiZmJ7Q zb6wb&Er5%S8a$n}gghKI;qIV8(uAA6I-F^rlg&c7+Ns0UUPH*)P78K6M)38vM{agB zY;4TLRJyLNI+T>8!^YN3<_x=9j$v+&~Wc$OHUuKaC{=B%s`qk`7zZa06IsV^Ztwyjh z{TQL>K(cc7{4^#-t zV$3(83Wc#O$9xmcvKsp}E8-1`v>qp^zyH;n6s08E{!-D3?P%KxU#)8N{(>+%;l#=M zh7~LGW2rxm#0zN{*gVsO-84ICIo$Ew3>B~ved!o^T=}@c`lbD>w;l7g^ZwH$gIVs&+XB$iEDoLr?O-(@0iIgONVG?B zrV}dj>2=PsMcyI{RM8a+-^|O;OMs4!22720U}m%sUN#dD>@;S8f*ku5D9fQ=Ubeir zLxY^PIWp73$U&QnxO3Oa26Qg3LtT9#3dtFlmSv)KaVdehPV5s^y_eUD8-{uLixd@A zxa3tTDhkcT;*`=H-5=8v&2LBeo1IDwwLFj*<9Hx7)$>?Pl>IGhvpGMR=#GPp$#~eB zj)$xD1o+UGd!UyIf_<$?R-z5^v4Ee;e0bSUg15uezXf^fUJCHE*c;$swZq@tYNv;z z$x$8EXnpa|LGwK5(W8dL+0g=l{;sI1$VW{@4k}ACkpOr>hrXT~ zjX*ys2Hm!#Sj3PmEKOj^={AiQ!rOKnLYzhoP%z7}UqMO=Bzf74r_1vNaB?svK!+kB zAp|wGd00;HWk7c_kXJMil*u)VYTk7OXLiuF{eUh=kpNwli{|DGRF_zxvOtHvRCMUe zTlYV*Qw*Oc#+Y3V4>G;%;jHt>#%#`C>@22|tDj2lUXrKNRCv2DL_naUNJAPN?5?P& z;sJj@bDsYU52tCbyjVSMLq4=&*#k^^V5R4BcaCi2uWPZN>hC* zeR-*hRHGu_hC*6eDo|fIUL32oVD!&=I@6z9S!kWIvoY9fpr>|r#L7Oy1SB32aMy}lV|4&DG3wiPZoxzmqaaTso2UMd{)(?>`9(~UkpOyY0{C+|N*0N;SSH&@`+wdJ^au>%*+ zF2%W1i*f3B3yvOY!1gU=sH%)XObl0zwt}6#Dcs%dU~HlfeR}grG3eJ9s>tdCl-Pbf zzC3ta9#ifQK4x&Me5~^J;PH1o{#Qwcuu|I>`rvlZxCH27aC6c}T!cM}a)XhR?uV>Y zAL<97q9_>k)hS|HTxrQ7xOq5$YY&=|gBE~x9s(bbG1>JE-mp+ zj#hoe+4VxaXTjfHs!8a@^$1B^_R5#87=n22bBHI&L(zJPW!^sS3q;*Qf;3zS>~@xu ze>OLo_{vys9Q5UKR|^Tus-vKxHWu32b3|f(U0o?be;=edC$z>)g7X-ts*I4zUCkcx zYVNENKhK!O0rcRxRDI_i!tER}sp{uJ4O)af=s7d%{H_d<^ zJNAE@nuIc-f1QKog#FI0t}jwE6R~MyTYn5$5r-Dp?FNDLKTA?R=so!RACBSsFZScR z&-Q^UrySeghR+}F#AhUS%=>pP#jyjOqSV!s`{Z=*?#8XlYjN^$6G6Tjy_?IhygdW4 z(e5JO2Is?_!D&Vb#@zC@ly+3=JCjQ~vab=JTw9C#w>RU-!~FuvpAnote|{35eM&C+ zDZ~00ZJ)xUyQ^^ZSOhK{@WPqho;b0?9f!BN;y{lp_HJ;-&b5x%*lCC6N;71p=#T@N z16xbFgw&Y;eZ5(IG3a@H4qAeqEC$oyFKS(6Vs+lx_HkN_7~ zJGw+Rg{k2$0GePdX&|IMt;Z_>ZHTPQaMai5iTTYEd~r!(b61?+7c51>54pUlw@flj|<1ft0FN{1yO->5aPpmMrOc| zK<(>F@|cI9Kr2yAB|O|)NK{w}mvV9h1z5nxZJt=_&46~a7KLNQ@@`}OaWK#x16_i& zwmQLDYdZAw)cPu@a6Lj%FqT2BfVHOj3@n^KMgi#In8T&6xE|ru{(6KGsJUS5XsKW< zi{8haLt0&Zp@6HNo-RRO>n$}2e>u$Y3xFQVx&Et2c}Y6oFjRKXzYfruxrJVtx#=$& zTFS9`bBE-J-vs4<7}nBk4W7yI`aT7q@9)Nce0v0c{CqDt*>&VPQjnP%iYK?pDHEI< zYSNLC5QKzSe*$qMp5EIf&f&yK*Dr0trL*gC?qoMsEGt1W9p~X{1t)T^e8b1q%22cp zwk9NF*pv8f{o=+fT)nUn5AN*7(}#!f{0YIBfczN&`3nN{7tc>npMd@834H$9X*{~O z8rM!l;nG1LoZIU~&f5b=x4Glc7B}qO=z<+`|mrxTaF=~k8x`cr$B1uxP4}sZdAwq&I3Cf;`i0~PZax^m1ACXZ3 z1Zi&s6Tp4k7sB0f2Apk$ixx?exNxko-gp@3Or+OgHbGCLFQurYfrVok*4jD?p`ktt zs`JN*40gPvd)5rDMffqMiK4Nr;q<;8OXg;>sHh^Us?ZfGFZ1RC0dwch1{diiz0%Rq zdc}#8`oYV6NpjXYWhfi+wqooTLL9$TlaRv<{}qyB(0sFyZxnJ2ny1|Twyb+ux!GP# zjR`M0+T*ctUD?|K{hurb^wWDg@s}?T;PVIDP*awO$WRX?5sV+*>cP>yOOO;tVD70$ zSy4Pn3*vGA#uhqf2OiztE`L!IQRTd;F$BewU{Vds_x?ATl{ z+TGilaCmPUuAX0q+t;_^;T?kgqXPtJhV)?x&;(=_-zfa-Q)-`|A$NV4AiV((K3R@C zH`{9b)5S=);Ncgk$CM3Y3?oh!RlNRz@(=pAR1bbSMFu^=2nMPz-1T1~h%4 zr;|b8Lb0u_MQCd)>zhu;G3XV1W3a1609Zg;IB1r_K@*_4+*M~6?WeJ2%d4??aWxC`k2GrMH5bT^I>N-2R0Teu(D8txf$0a)F$b`*jPuT6*VMK^Ev@89xE4+WoOM! zT1#soIpKLwT`-+Y1lJ)PgIP02lan4pSDoVt!jnYkkdye!Qm#qJZhFd;Nw3t^RUc?; zYd)PlYv#|KM2Qpfa}p))D*!Ge_9^!FCGMX+>nBS~izA~(jZ)4Btqf-whFo2Rfv7BY zud+C~|Nkm+l^1yy2baKN_bgZR{%uq3GP0AsYRhb1wAL77ZC9emDAxyR1*ms#9~5Vn z0sbpNE{99FRhGPe-;ORkxw8X5yx4~qkGA8~p>}jHFGg~F03P1#!S;={NQm*nnWM|G zq&XWYi9sSC$Fuu8@#O9fJSMTDetLfw9uw%f&sA3#*q6_3Ab_qX7;g|jzJ75%Ze8iY z-5XnRkJFakrpI`&51$d7KYw-vpMNUB`O6pQ@Z$5c1ZD=bq^A$LipwfIxFrGl=9M;F zxv*F)RylR70Y?eYJGPaeu^}Gm>Ar|h;1c-j*%t*o}u>rQ=|a#04eR`Y<8TB!_7$-!G5MlCXkio`=Ple z9E}8ewGyDcWI)>*A#G8J$OYZl zP(Y9_#Zq$89UT<{%KdF%`xbT$}DiMXfA`bw4IB_mZPb;1PzTv;>Kf1X&Q2J z5|FB>O&A*&B3#QgmZT9V|Tx!jhb(#pblSfHp$IA`t*$n^;2La{tUO1Wq(!+GpD z0=cM3IOCPIwZ$<{54ZLO^HmZ>l@UPWFF=l;=Tn2`+}Sa>3YNKg}*9JB0vk{j#~r2y2%! zpa(f?OEw-_VRz9dvm|mx)a^*`jT!%Ry^>E|xUpVQFJNeaLdr(Nc(8 zmp0(fUmnEQ&vxPE;~m(#t{N!>=tsA1w89Bq?}etv?W&7qEixP2iHmk)X4;sH;b+v|ZdyFGAX zhZ~M;bH%=m&e+lIhz-kZ(Nt-M+%!GJM`II>c)>VuMsrkfMRQd_A<3 z8e(acDV8<*qO+p}g@s9QR>Yvqjn&{|Hx6M+fF1zr!H`yf+KXe*y7S>+$Fn%XP+gsY zhK52kw{T+qax7a`DS*6EjzO=ir+yPja@8E-C@RUI|FLPT; zU;doyg>#P2pD))aB-biRR}o+pbqc5RDq8}pRJuwM=XB=sRg>s_!l5Mw=Qx6>aK|Jr zYsK{l2aD?y^8bjBn?)d>J8#x28ym}`VPU}~&Q1=!3svX;b?zK4aYdkK(en{C3h6m< zJBRjhJwleI#=>vS&CN;)Ps(tX0nOnHcFuB5LWUv(k!MRV6lHN}L6*GI?>}2Ztt6D; z{OjE_|6~%N>nm(tFrd3TWkAc2R&vg~{mzi?*FH{6v#u7c)u~8{@kV@v2a>7HND3r) zg&{jR09i@?$Vl`IGo?A`eE5dr<_ zApz$vK0QicK80_-JWpUIIKMncI!iA4G+ummQt0zf5998oGF&|xf=dVeap8a;&hGOQ zD-e0X3NKdKxy}u%+nkV*Y>kKzV{-Z~beZghq(pymROT?VFr^QW3Z_lzhv1vU@KWw8 zZ@)=H9j81t)MLo|m8HDzO~?EuF?ioLrU0`n2K0y#9OC#GPBv-?@-aYOx)-X8e9>6$ zhw?l(WF(lOD8~bBOA1g_ln7UM`#wPXGN4@u$RyFe1=2F8y=}(Bh;I_wn;<8PE3agU z3f@bWl#38YXJ-|GxUnw=%~0n4U_e_~nu*k)v2h`Yi)VMt3PE&CFrr8iQGs-Ica&g)5|NI{hZwNrw`d_?o8~ab7eZ(7j2`RZowc|pLL8ms&f9VA633yJ zhC@CvMU44y+L0ef{LrY5ovuBcHVYfn1l3_Sleb7=0 zVf2r`9->e_MtOWFz3tdvI{$6^_5EI)U3gP_`5nc!ia)Pgq6}&wy z;OS`vcXw;JI5X_c2==D*-ZSY-*3U3EG39D1IxsSlV$%kO64Z5cd2Te}V7JXR3AwU3*CaGHHoQkp_`bTj+RqEs7K&PgT!&Dq zOZd7LsOa}r+n*mZWC5B(t!4CF zTJXu0X56^gge&Ljaq)C5P92qs#_rgfhmNK3C@u^@Vxl{IeJ$w&p+j$c4Hy_pxj5!> zx=}?8nn9!tMY%teWQYwlF8V`-HU{eSm%q(#j$*D+AldmKUlJ zpl!5~o$iN*`fRju%F)hBq2*oGyj5 zp`{@Vb!FCMR!mV-Y=P<$JCqeTAV13<87bCuwP=Ba7&F91nIk634lyx41mXa4-2VL{ zD04ws0q>Xqg0nXw!fX-juM2E+jw*0=(1N3*F@0H>i|XGDX|7FZ z!H|~g5|ZndoHvI~)S<042O8>=p{6q;R3MWL5;SQX^296^WeGP{h$Ud{n3h$rI6GUWkqG zMogGHqC?yeMJmmY!TICM@!11*&kW=p z+OI!9hVQ;4$bNYi-@ZIW?P>hs>vQ<-tF!oqLl-Yk)A$(y?Jqw&hOfUkj&JE0);E0o zS7-43x99Q4Z`ehjC0Jj?ci&ybx8GbAF8bx?9E;` z@iaSU^l}Wk(+-PkEa-1HKw=C-MO75=PT#=ZZOu*I|07D@LtSqH*aSV+O zI95r@;{t9<{h`K{x23Uu=PU0Ye2nt`p~i)j0sAHmb&LYW1Ed%i4tn&5aI%^TZ>Jdu zbf1INsD&uc(!t_#V=Qm9!|Kj7bas@Xm_rTVH@`a>s3L6#~?2*0y3bwG3_!e-tTZan#fm zib~$ibwLDWV=)g}TCk!c%3l>{X(KOH6X^+RNRCoPT-ba>2df|=Z~?+Yj1V2=DInb^ zf-<}3*tlSVvnRrWj1lBBAAw%8;qNgMKCaWnA{TduX>hTd3MZRsaIl#NM|%SSX(=?q zkT#Mat*GuT%3c|&Lq~f$wA9B!U3IireWTj6`Eo&%XOHu-~^36ece)0bq6;%od(A{lLFMF0-U;{yV?NW2BYB9y~ z1`{l)GDLlmE-G`i=!2joN=X%`siPo84MiEIs4kBa)7@esJrNY(h>$>MQSl)%)D4kg zZitESAUEJcuE0-dQKCP&gdk+4g%G$y$eDzqASV*V`OzpZio^PqrMP)%omeTzdVZe) zy<3PO&FxEq@=Jwd=2-LBpC7?DUmTIz7f0~zi$nP4v)%aS^F#RVofSnR|Me~ zCusX5^%dJ+NZuR57+VCH?IN=?c3yz9cx{&a)~oi6Uo&Cm?AqXSk$!RENgs2$im73 z>Djs1x_duuJNALG56FFB9yG#}5Wh)&_7h-cs0tScU3!0pppDGP%9S-(v$~#~a2dkFe94VkiDXD2AwC4` zDs-<~OptCCu;zF)=Yi&hD%G_GSiCp~HKo>KnK!Q_WH@ubJWu;oNtV{D{8SBOCN4xu z3>S{&vR88zWv>X-p_alq%W#h3uts#CXoCX`$u-X*IL{Ia@SOF^&wb`AUV-S&H3|vP zym-alax(0!=fc6>SlkD(=?iyo=_>Bqj($au{+S^Cst?eL z!m*;<)toVslUB^~;QyO64|wdtlaL)W1A23p z1vYh>V_lmWR<{_VtC8=F>!Ybe2i19+sL0kpS%x}F(+SS03sIVFin^*qG}NS`v1XA_ zb6qMHH)f!{B@4@zc-7$t8nFF7cQLZ#OV`lIC8iZYr9Jj z6zl^>CkN!^=VQg{E^=VY;Na*ea&hDomSD&JBVxM`h;MSugVYBzrLn>Leras*xZGDB zlgEeJFY9glSiiLYHOWvOu&t=-J!T}_2)tng#QNH@z8G|Fb_zm*Jdv6bfsXbPl$0dF z)!nXdnjJgnNF^}K8aOt(uOCi*e+RDPw-D}5`Y0_7Lq}UNR<9yJuc3~0$k52{HxZ>E^_!HZSI%#dkQUTJBm zKQuKpQsm;0K|C17%45p=^x#N<9`}E|gDy<>Ufb#Sa_ee0Y+1!=GM%xm!x5{O*kgH< z4cclg(Nt!N+9J9%%QGZ5ZGiF|19AYiXyjs=4Vh?d%*5iROe|^6LVIgAI+x~QMSDKh zEHA>QHRag0u^KzK)L~z56OIs=PaGsLA7L0#dzQi)=Lpd3pf8bw=40p_g}dgM^w(dW7qRG!YRmvd}X?x)Q-y{XFM~Rz+ z!{F(vjrd3lWF|YHFw+TjrC#W43B}6x1gu$Eg09YT6cogZnGl?dgJaPC4g_eoQHUaO z`?^L8SSybOI8K12i5k4!Em2jTC?2v9 ztXtoLHQmkP=3!BBssMC39arD52xa-^D5fjX!c3hX(-JIhg!`HwO9`_&m>lPPASc`V zNJgsD?U+!FAH`B{x9RY8nT8wxe;dxQqqA;?P`zD`r&=RD&t zp+1IZ0z57E1bSNU3iPtx6X0QS(9wMUa|hFjuUxGrz{PSr9L-4<)8S~NNv>KK4%XVR zv($vGxjL*(RbZ|+9;P~@Upbi1`Ygo9c1vWSa~G*IBG9SJ$JuPJ)`E#&Eu8%^G*yN{ zW8TL?>T{{TU=q|9OvUVJV=!y#XsD@7f!h43udK~lw zNvNqJL9Kg5InUVm&-p1XEA`&Ct>w%8`&zJXZ$0+zs>ROUDs0_chD{raux?Erx|XG* ztu=|N!(v}=LCKt;H&RqoOl^uoX?kdLSb(QGtsl)EA z4LCr~`NY9?a?PCr&X-QD#5HowHwer(F0RF`%j-p!I(EM*7wn#&>?d&3xkmzUZNCF<9CRd5I|)cXzLZ4ndA|VjpZ-X$n8d*S{yT>672%Zs z@XbX6^f?i4W-$No-Fez~5r6&R3jRX+6G56m&F6kk=Y01KIq9!26QnQT>HXEXdMp&@ z_qyTqE>|4yb-|IX&N#5i5j)q~W6KH~tXXP>#&S~>X6Yj-MjJtX3t?k93r2=>U}U0) z)T}J*Py)0vlm^37((AzGg)M`}l+PP@{=j{M$A%goe2n}Yfr9~2s1NdQ7wn(ICHpzlP7K7vJ5>v zOR;{#VuExFic6&sM}+`67mYPVLAoX~l1&~)_?n&0b07Q1lT}l`KeWmA`>(#t`u^*$ z3jfsBZ1ali5ze0Y@0c_3cd*lVAED;M5N0`wG+JscMj@0GLgOK3A8}r2&IkPi>5oF@ zl7dZ#|24qqLj;+8Ajz0p+BO|V8ZOCX7y?-$FZ73`4-jlR?62XLqrM5Z98DVa4gJ1v zLd-{f>tpcIe{e2nPu=(6!J@v%39bD;T(sVYqsH%HuSQaT4|ZxK&0+sxVxaNUQ1Bh7 zp#g1WtoHW+)3M(MnT`57SfP-9eHCIp`m0c(QKAjAkQC0cWR2-lgcV6@zmzmqC{naz zzKpb{K8wdhpT>B+Z=X_YHRdJtUq;!Cd%3#F>odaW|Le}3uF^Yqmaxm0XN}0SIR3Gp zlJZKgoqN{3Ja}jo_Ux+0uI-BN%p8*|A8W?|i`baZtjqOBzwt@ROTstqHBqOm#z zja9+a2BWDajNqMuw#9h@(97HClD?w=-7886&{Yzkw>9A4?pB;U)Pb|dmgB++a?fX0 zS0)Gj?U!f7%|Qv!yibDhU;lhV=r2E9 z!=Fii`SVTu>H8bxrmy1Ludk4kzKEv}*5mrA1YA52fHQmjaAKz~j&AqHp{?H7yU`Q9 z-ELUk>Wt)gJA?&WA}=QbjSV@dtjHA8ovf@ak(Ql{joWt7rKbHL2o8qg(0YAeKRgGH z_iOOuEBBT4OZ)$qNa392?J47jWAgZ6aC6W@ppON)(GYaEg`=a!A7we7NK0@)MQI$? zuBjEdINUw##Zqq$aRfMwmjEq9aPI5Bc`S$kZEK-LU##{bSIdTV_2}8O1S?lIz|GA8 z=H@0MTU|k6D*ZprMazKRx~&77dfLcIFF{#(CLA1WM2Ld{U6f;r+*D0OhFP5r^D;eI z>^AJx)rPS+yF*d(>Qy;ibt+0;DOFTat{d1_`9sli1r@37ulymmebqro1FEaY`{c({ zR8HYBx$;P#xH^fUqTCgUE18IjDti4DRlEjNROv5y#h{idswjss-d%kaRp|Hd@9e9n zqNu7OS5y&Fs;cr@O+rOw6~#<|p$^jh_gE5FX+{S{RP&$;Glf6DWq z-wf*9!ixV-VOdRXeM|e{qOv+u#W4TyN&kc0 z49lBLv9#Ib+Cw(5wC;%6isq58Ym-|SYH{6#ZB30Z_UB7CAkFY zT&!MRgpC~H*uWuk|GU)H-GC-jc4S-C%M z%rH!zFcMzwwup}KMN54SHj!gqS{sj|+!(~i1R_5-0jpM2qMDN>c@m&4B|rx%03A&r zezPPnbD!H_=Sc$4!Tt{7>ab@+19og*N)EXdK|x+{cCi!lo>!Brb|qlP#fJ$nZ{OZQ zpl-*;O>L;G%!ZSbEo$ou(A1QM(tI;fQ6)UY?r4OU*~wz};jb>&kHs0eLj|Dqe<#FculV=N8Vu)tKugbC8PNPUa`D){zjv_sHIZLK<=02v zR!9Jv_VMej1Zd?Ii@cgpc_pEogJbB$Dg|XVfy-8{d%Co9<=--M3J#}dYL zCkGSwdFmr0Rs)#{dMM2CM|o)yYATXZSCxW>>P2X2$Uytz9CWo85Uh&{))m;cv6f)n zfIZur$WbrG#gi*v1N2=bK=WK@1~Vr_VoCj-czkCUu3zXt&vIuJrR%`LOb529z%63Cpo-1lgJh7xc zNW`Gmt}4UIu1XXaC5c%awl>BvH&H{N<9Gq!Xb%O9x%E(N%Y6ao{;^<}NwBljLP&rk zI+he*>*iMM-qnd+J3En^n?(Oha}<}Pqp~Uoc6L_C%}d6%?VZ@Mqm$ZY!cB9Y4Gw`c zx0IrzJqPvWR;Vu0MN*v2#RzW#G&$%CwPSFm&p{7elkjy1Js8qTFi`+Uc6oj9QH&1| zpQGFt+e)BjxKS$=jD1hQun*9Bzw0X+I~1VhnuPCG)q5yOfc91ZdO*=wg=9d>a29~3 z=h_En`R^bN_`8Ra{8|ip-TGhO{%!fSRRXkf&JSLC&N-l!b8);mQBqNPol1Fa^V#s| zn4f$C0{@nsoBL&9N%4!qqQV#Xg#};a7v_CgR$lm1Nm(}X$cbd8hafr05Am^{h>3JZ zSf~qpd|b$pxWL`rndAglS4X(G@Um2U_6sKcb@o5gQYX__z=xlH*8Ajl#~Y%_8>9l0zK#Z*CDG4(TT0P9+D;c{A8O?;=R< zB0zRxeWwqSqjfNI#w1LfASGJ~3%0|J%Ny|g@ezFa`2pNNABS5?5= zpt2%eB<$xHG_NEKB0$FwgkzMzENx3;l6bry&>;#yhXy)`O7YvbwPD}BRXA{<8*A4# zBY@uL&d!{e$N~QJzUNhid-krzo;@qEYxfH5*ttR^Lvr_U5{p#UtSLrYqaBvi7^1G! z^3y0k)2q3jlfT?sI^(N7>+HXJ_B7+`Cy#UgP+w*B^ZaQaV8QhFuyDqEaMJw<5jOO^ z>?b1HVRE0MXgktoBqFSbkw*L&Zawb1aO?43hFgvQiX_@V(@}r&*82$l#vdWrOd<1+ z5z29Ft8og^=Y`r3%aJ0c&HKZwM*S($cG7dwr>qE4nDvCuy$y!{m1E6rI`6|>m)rN? zs{I~Zv_F88)<>{Ye;>9BN$MZKM(qPQ=#2i0siD@7za_lE=UAI){58mG^5YQ8akoM( z#|zQ(y%na^(%*TD{_a~5))OSzOt=-PEZd2NU;u+Z+6yr-nx9L^>A-*@uKSLI2S^$ayC1;nhHBF z*N+v|b!b|=1dT0=(a_S0`sNm)>biPVRM()SyaGA-c}UO7LRw}f7NwyKCv0J1Dy?S9Cwr{5An-wfFYVi~w&W^<& zs%sZF;_>|h`1J8^a>miPxW^F}_ewgy+W{92MdHeZH8^o%6E%6eN z+Y`%M+>j9Cgx~-h`XUNNetsNEOS56`XbVegD`@LziNr9RBz8(Lb+&_eE*-#`2It-*nV>#(1W*|(2Cy?2ese8)+W zc$MMio(imLbHb`tQ><(?`?;>v=23jO&57s```uAtF1w>6U5^C%+1$1$-;=6pt$6Wmags%e_6k|7aO+pVm)bX&o->vydB+}wqo^$ z9;{y9gRbs%=v>u}Wh)h0wHEDNtEs;R9VFh@LE9ZGR-=9SD$#FSz7k88t-#Vw5{+@o z=d|-N+$xUY$KdmquU?DgtJdJ?Ar5V9z)jL8S2l_ARh-wE#gKk{XSOZ{Q zi+i_r5MX<-YeyT33KK|npGtt@l9dzA|xd`A;4P$AwfQLzBkE>t^~OCMpjw`P8?i}n^!sRyqj9iH@yNE z&vxSc>18-`vK=RmF2#{Ui*cBaJGj3E>(*5uEiDESk%35Al!&y9WV#H_hOM0~%q+~I zrL8Fd&2-s*NCrvI9=uFQBrm^Dg9*sex3(C zZtN)d`8Xn;zC4>7O3+4tT-;QQ@{$asrG!zt2;Hk|QC*!W0Bvt;3KPQx1n6-Bz_Bub z`#{Z7fLV<7Ls|l~wgl*oLTuZ*6#MqB!XbLUGN2C~T8G1jHxRJb5x7?on7eV1_8mB| z8vFM%q`R?rNg2GoU9qOS3BB9uuztB4*0!0Udnq~oR@0wbt4zNy&N6=%8)o{{*In;h zFDJDhqXHHnErt|3p8z~xw3*4qD9DQtDvQ z>t%?q?n4(l&1dF@^S(FLoBGPxW-7d$r@@Eh>oNm@KH3Niai*(UFS@Gr6xHveNRi=W zCVW&8;64NX?lWEmdCmJi%wPLnu&=>odrS34`dTyotgAlpm5JVXnCOiam0I*PM?+U* z9CUS5pslSc@^NqyBy|l{s4iUa%FxK*nW?Gq_Y!ai16mo{L&Mw2(c#v(apUBr-a|q9 zUsdvg8cuu4OVZgz51p_-J*W8pnYbu>R8(Bj*!-dr+vO`)eZP9`I;>f@4&CcFK@RCAwYHi=tOdW8cS?ArEwzas>6_;=8lkHE4a8AlY2H6A&&VA=7G~M zGN6?~_(mx?VV3f~!P~!9@?$DX9v|wMx1IN!ME|#O0?s2aa^!HaYLFoN&;U^P zOAc``pu>V3#muDInr!rJqAy?qGei0?y>E{m-H0Pc3DSqw2spF5K6I#?oOCw9Xh z1;~h(l#^;rCL~tG){6=gP*A{1BuGagGsTJ^txAAaL44ReLjR12*xR(OXUUZe{O;?Mw9b%3U@3{!_B#_g&3~Ckw-rasGeLg0` z$!Zd8OnH^%I07}n+Hf{ZOtfHRs0l9P#$~QdI2VV3KA8}0&c*R+AdH978v%Xe4S@bv zmz*t||l>p~N`=XH2+i$E;qLihGNXlkF_ zR+gqDGo&U55};S%(zzaN-CU2lQaieYTL5*n+2E9iEDJMj0(&62+(^X62Ma*^y3HXl zPk`Z^kCikG>5;Ys=mwlW(M@pPgtJE~abTk>_N=wWt~J)!vDzBjS6X4qa!YLLw8Z*$ z3#@21MN6fj$hnZ8s)>Y1RZ(Bg)y)KU4pt&>@4UG)F@4(WfMy^K9+TAvHHDPN1|F+e zCf*kwp;ka%F;0@tlQq=XV7=`a>Gur1?``50Xq>5zt3orFIc+72uZZMO$H)=GF=f&) zWXH`%eZD4|inP#DqKzeGI%u!b!?GG9EN}M4%H`!KDNYed>20ix;O1lsU#I!-bDSyU z>o7yeU$O1yI71qz)`!Nu?Wc>@(|#@-Yz+|+;v$Mec#|VqhlM~-YjM@JR>{M@l|<6?sLD)es2r1z^0y+6#+y~Gq>dh|e4ZdrRj^ zu$~ToH*(>knC(=!+D(Rocjbd^E< zHegF~c6Pime*Aws2R(SjQIurx&8Ou1W#lMsZAIQyslI>j}Dwz5s56IKD}2(_``R^ca2nXq;P?IG4naCw`A& zUu|tUmevJeZL1x2t+L07&9*qV%NKVpw~M6u3}^PlzOE4)6!qU~5kK{yOq|l{t zOk6M`B3uy^U=CZosRGJ&##}8KDc?4fMyupATGnybhiW9((6je9mW7t_w zpE44q8SFZ(2yE8qsI^6By&aY}*n=0UtXL9;RbAz%sm_3zxqyNeZ^9n9cl zZz5!GO<(9FE@$OH;+D7VtPEjmMZh6(%}N(X3q+CAY+GCeZ%-$BzZc;+0hytE^5kZm zI=v02PHn-7;~S*0Q(I|V+Rw*zF0TXxXPQ%77SFCNf!OB)kwAY!@ z7r7A{O6kkIKp$nE~yLXMn}02i2X?Zh>7+gID1QAj`b6YkMl!9d;k*SXkWM$ z!UNP0<~xTRHG_JFkOXUX<|+vEF+iZ79sGRk;pJfiS9*7_*c?UH3{DwgYMaJp!)i~Pk%gm>z zGSm@(8yXm{3UCrMTL_rx8L3d$&_HlVAnFO?4Fq5b$P$<(QNK~@^SFSs0?IOsxs_l{ zV@mrZfJ^&XH8mATN(d&fI-{o00Y^7l;p|RN+`hCF_ik<%A&!TiY!ji4ha$wGaMR?X z8PIpHufXY@KG?Iy0_zu>V#5+MY+P!N16yNp`+5)V+}eX9hgORmzMP(st2ju29s@ny zh4j1qk(3mIsF*-RMEQ%7LU#Hy2f&%zbb|h&9ZfiOXc^9(SS`XQXHRtE%<&GKKE4bm zjx5E2oh8__EeE@{=3&S7YHZ$IhqY@fv3z+ky;fN$DN90jZY+`)MI$K0hn$6u;wItS z9Q2!k&618&I))sw09xO^ehuDM9#`HcZx23RdHhXMKJH!55h4Kd|3!u~i-FC~THeoq zo;7148mpqQdRaQwbY^1hifpW3l}F0Qx|MmN5iiBTL;U2V)lY0fwIFETFJ2Mhpot5yRFV*JeVg;Nf zK%YJ%1A4s}J9T;sZIiQRNYnnVu39nMqo-#vjvQV~&YB>7XeF73T5R5!hYj5sSlzV< zooxwdYmG%qLlo+3!cbivjHFx+)D-mFWcMMMC|6P7;u27tIx9^73MlofV3V zR4=3?IwC2~4vBG2^m=feLtm1=5JOo2n$+i<>F<{S?TFjA=e}vdKSl~9s8@V-hKAtu@lGWO|cS{l_h5`tJXeK5ws z$k<50IwNBdGPBZyeNcIsnkRI&?`$Z_31kAdwY}6VPzo zH(O;uE0hsMfbMM|KzE38TMX%QC)eWK=?$b!I87hQV@JAi_|PgGqD$Gmdsm4$u^W5Z zz$qx(I_Pz-EkI#O1~Re|5E&gvud%)eaZH^e0h&Q1!%#>Ob5`Ehf6VLP79dmTP5TBP z_a?pTaje0|{+e@@B`4Y$J9Z4lj~m+$XI3AeC!?u072PXJv2Im40j>%?>uQBIbl0G= zECq%J+H|>XNPyObnVA7R$=$KT^K`eyqNE^#UkYlgNR=rfbkWwDjU`P|KADas`B<}} z94nWXAwMSukr6)h9tjfDL3zPRYilu1o!lge{^w^1&}YsNluvHNX@axZK24xLwVB-X z7OYrNCmi(JwT;-brwe=ctiW#4_TFXm1-=v;HnyU>n@eVKuIO?sSzJt?mwdXi%qB2r z5STLv%4ter4Zca3fc*S;0&<+VQJ9w-hn(zKWM#$D=QA3qsS!v{4nb04ka%y$#qrcu zp5p2&!Wxkg(#=8n2B84oKp?*?5%N%gJBGf%VyTUzFRxevaZDt^I+DNK2==kw1b!bR z#rq;T!B2?$39&wKurqZ3#u1h%R+FF7#fw`ih47vGvsBdb<_3PKr(%gjU zGiC_Uw;txso7n8me{YlP*p%&2D0p&2Rml5U%2ktzHNpx$FS?` ztFb60j{fn%s44QokquS?(6=wODMB3EL}){fL37LVpn0m@vxocf1;@(M_H&?ncBi|)pSvm0>n+!mZWy9Fo7MIAlbjiX1TyZk$Mt;E)C z4CxN6T-}V;B^3neJQSB^ASE>h<`yQxK@Yr1s5F0AF($VIH5kzSp$Yjhl#h`gPx-Nw z$KFLl-K3P;-|~1via;zh#5mWyn>b+%B17H9%D#;R=gsSDv2|k|HgBlGCW3Tldx?mv zCdIoUD%1?lcB-(o)+BM9)PP)~H;N16QC1v>26E!7I#RH%D-r9K$718kL~LD`ir$Tx z*t$MnR0dC=tGmPmhMhELf6L}2ID4iCXX#6s+w&K8-~#E~+08hAz84oR?xgMQICp+K z&Ys;aa(8%mI3ps$pFkOc*w_%n#E>C~qANBU;~X9#A>QP&J>ci(N-o_Qo}P|ybF+u5 zi!EGSY~bu{4M#^yI5=1caTzQ-J9AMAOA;@DGKH0uiI9bbk@#Zb^r0*hV_g^|u&5SZljSX^)jP!C04Ro`)H8RrAF*2lBnS+@b-fB#3UT)Be4yO4l9ThtmGHRAUe zJ@P$_;5+LhM`8Ggkr+071U?=%oE*+Xa;0%1)WI-j2rGv-ltC@Ws>PTB&|;j%D$4Rv zQj~%AhVZ@+$DPYrFZG3p>c zec0$uQ3AB2v~Y7A?k&UFqswvX$ZDKAx&{|cuM^Y!u3XxVOBc73i{40=y6Z$dl5Z02 z+uw~H4C(D%Shrybmeb|#lBMNnY%WD{S(Ydm%1O>S1}#HwF!cJy*i9;lr=W3#WLdmD zSZ~^|JkE9H`0=Dx-j-V4uRJD8K4;*zqOW+&q15*rxSF%5=-jXI^0vJ1wf$qo%|pJC zsHL%h+?+SL=rV${3}|xE>j~29>#(vj8?DvOB9_akJ3|9a5a917Qfq2ys)#Em28pMe z1yYlI(b?#Njcpd#)M1H@q@HEg=v^0%1A9Bj@pfX*?oR9@_j{PGjLwj2zCd5d=g%>a zx8mZZow#&q7cQLNhKmH}%a`}iwghb!&-UOthGk_LC@oDxaY-t<;8b$J$;in~AlDm* z^z;}kS`>k#q%itIV1P5ceG$%8yTiN@8sdfEAP)ovx*;&YjU2fv{Cu6^OE71kdwV;< z%gd3#?f`dpdxATI-I~B|MXuixjt=HYP5i~ z4CqOdCnF^#NdhxDXpUFQ{l1U}LAa!}kluK)^ahL<&Rv4EbeuS^t{l}BdFW^e!!bDq zeR(N4XrAx96Ho3jocBuY0|lU;92S87^x;-Ky4i?(7jkgxcm!^riowIHrFj0J3oo7@ z#LLf5;j^dop*b9ZZCzHVEwVyxiaC97O^}o7h?>eo`f^C7=NEtwe+>kB&4Yu{ESRfJ zgqhj|g(eC>AKY4qGey%tw5ZpO9C+i{sdedfe+96!>IV~0Bk(5rFq zP&fAOTO*wG=FM#)PwPReZd3&PN~o9wUamj}af!|5vmmYDaQ^7>)IfEBZ?6KSp`~ z5XXw+-p9uuDW31|m7a^}({qvAzP`L)dEf8pi)uU;(CekCp^891C#>lz!M07c}HbYORId-fI#i0YsNvjCbD+$soarAJv_!4Hfe2!i8nau*i7ccH0U~d%;nqkdf z))y}HitV#}Wp#2Rj?lRW#r$Y~ycO87V;Qz?U5d>;i?Lxtv&b>MVnr1?MZLlj`W)rc z)n$%QZB3SlL6?`MqO5cgii?w_DRv^v5s%#5c;w`8h$9-AnbAl~i=eC0Q2M-)`%erK zH~#o0Ajg~8i1dd!c$%FgDcm7Vx8oTe+{VWEAfC?SxO7~k9ijr~BRXgv;zQ;mIbs1) zqZcA0P7PTJYRFAeN8ut3l%(sRB3mC-Il8FM(|=W#>-^6Iv>e`G_sp{+WR}#-Ntt%y(`|wEON_C3r4M%X z)??#_Ci)PhA~{wc;X#_B_-KHSl6+l}xhNC|wpZfpu`ZlH$u|kRaq-ML1)w+J{P7AL z?F}KP?v1^h{BU4L8ht32;_#96V)fasUCTv&hAmr{Ve{5@^z( zRD;ICX;?6C66VdBDrTF^m^L1>XHKT=83gXJ7(b4unT^BrX_GKw_=ouLgMY`cVIPVW zb{`WQKmO=<7(VPHp^rZz0Dt)J7(Sf(AM>%lqiz1O9Y)(9;A8F&e-9JJ4#(J0A7Kn# zC5<2bAtsKaFM^RD5P*M2feUwXW;Tto0j>M!19CIEeLKtJm3@5id zivHelm^PLF{z+J%G9B|tCPtbtqRVhI6Fn5>#tP@Wb892E^)!)#Zp8M@P1w1u1wGyA z=&UzIL$MBh8LQF%)0iBmCtdCv^#PizeppzT5rjgqwAKyXEk@YbZi3AO=Pk=Euwy*| zdVePl?q@i!z^1W)j+jZHXxdaH;%GlaQ4cW%3I*5}S`BT0bfnDp^u z>jb0^9b6+Iy=zw|dbhU=NOSU~b?X}Gv&W^hs?pJ2hQ+N#XeLNEHRho~Ksr-#qc9aE zC45tm0iA$67D1ZdN7>o2eSqc|G{>J~WBtjI6POj#>KMY|e8V)rBKw%1}eqD%)EH%{R zsG}}V0}Tb5uPXEGj}U_11Y2bdb&RrPILq#NsM!(!J%2X#?ytW7;PW4ko;Z$mYnO`< zM`dLxsSNoAxd;ghLvd*tzWCxZdV_R9W&Q$8pE;8NJO$$?OvKo6<1uFJID+&Tj2I<{ zIS3Y0r_!4tMGA4SYbGG~&Dv17WZoAa9|aAKh2#V$!P3%DqJcn;yO6|8V597gwc-%Pbj4S&cadD3W{SJGaI}l0EcNJZ-@?w_7XsdT1S8YUZ zP(OOJN(v2;l$9Py(5=C_6RU8Ez|3%F@j{rZ7uVwCo+upIY>UG^HrT(x8v8bR;KY$e z@uB4#N<26A@DZLHyPmXG+|fUBc%4{r#@Wx-tSUlfo(U4dRT1oOMwgWaFw~t0D>F5? zIN1=C7D8WZJZvnr#kR5GJm_eQhqZ+s9PG^L*jdomoJiaHur$|)uI5zes80~{fK83H zp`ki~&YuP+2TOvSI&F`mb7sQL#f~0J9op(#Jwyer&bH9gnGaQ!F)%Y;NXJ`2S9>nB z7EXYzrLL%`t*O+D6(yn)&lb|=bv0PA ztc09%Id=Ch#(~{!IJCDNhxc_*OQQDh{^i))TaJy(97R>2W%Y(A$l%}OOwUyh3l~g> zhPn#0H0RSLy%C}#Jg}t79vhZ2oXzMe%L3b0SYqdfFdXJW#|KvvnA!Dq5u}$1=gV`N zH;{TZw__8D^Kz`EtD`MjI?ziX-?h67y9w$%PnvHe@(skJ1op#+)`$fy`}eOF3757L zpto&nlWrCY7hNyv9WG-Ry|e_aErs-XDim(It}a`wj;yFi7l1AxKnpOFd(IMIj-e~E zXmAy9&WXd}4i0rV(Q6zL=7ogVKyd1UuwW0`?~I^84-xy0j_?!J@sr{LkxW2OiVqUo ziLn7TCBu`|Wl{!a&z%Qt9UVA1JN3y~AtxtC0;@e79UbUR z;6dNy`4WuTF)!xDDH5o~+-MR5Ix8zxWd52pYZiENx|x}Y$fe5;hJl?JAA!QWR4l0t zmTnRXKz9s?LG!%l`?q%D{wLJG&wxH4683-bjFTaq7FD@lK9`&`S3mjgYcBdKwcmYp z6b~;Z;FDu6xOv1GR}VM|H+}s?93I`cHYm<8L*612YE4m< zXO6ZSM;zH*feWYB;Nsa0xNv$s&YfCEaPPr|v#W4)M>xURRzUj5W;-0~^}_kni$y&0 zqPXN`XVoiWm3#?&nd6k_w~G(&;X~cz2z?Wc#E9Sn5m5d0^@*UOQ9w-s&AhM~?hajYZ#ZX>oPK8u)MRHATK%R0|aKin%cW}C3X_%B|x|L z0a{dRAwY9s+P0;obOl;OpQR%D92KCxE~gLBJgqLjAW^_MGb@%pztKodi$uzz2>Kic z(Er<#K3B%Dv@jOWgTb7!C>)Cj-Z7EB2oB%`X!LqV1|c&o8fAsaq$HFUC@DYjb;VeU!Ll(az1~X4zuITRG+ASgHxb5-WU*~JCrG*(kvC8pxl%W9BR zS6?l}acAM06(J2-BF4;+rna;sAK{?^^akdsPe!n|vLIkvz{bW3wxm#Us>uxy~7KiTv|pz-rl!RbMS4Z&VdKT`T^2hDtZn$~W9XF2o;qJvuJb$tipFcl=$M?43>XA^9MCrs< zTkKh5j%}T$*uLBZJ6D)t-&$LoIaG~HXV>EbFH|{6uK8HEG;`xX6Lzfi#OCF;Sl4ck zP0JmzXHy_9pI?SsH}~S^jor9@Z5OUz--DaicjFdq^Z50vyU4+B!P(Or$^A8B^k%$Ob06$Ly0aZ5_16Z3*AxIjFZ9A)lFx8&~S4UI06C@1@z6?zlCkt|_ zmeA3hLJoQ&++A$QVH-nBZ34OKX#`bAf~FBU-f_^^o{2y|H*&qY!eN^l&L~ z&Ly{Qp-IqnhPkO4jC3c##nA}f9uBZ1S8t#_5gslU@FYlEm@Me~a&UGqCm_#(fzDJq z)?O_3U^j0-!1nTVqQ@|Uxv>g;8K}aCzF2r(a!8;f{C%7dPL8g*HeD1B?pa%o?VD<` zr?-`y@=_ewwOFL4J-WXGCl0T~$)l@r>ew3kKhT%tnT_-%$?Bokb1RAZr`vG;R1^Kb zTIq_X6=zR0;`qTDa@%zT_y0e8{~cUamaX}s(Q)7F=Wa*b+voIsuTP&-zA~$_va-@U z$V|NV2oMMmAiO{rNeBc;Lf#>a07*zlLf(7tz4zXG3E{m5ptu-WkcRbWJA|WxJsu!x}k>Cdf_NPbFE374>j9WHK0; znO6}TcM(_oU0`E-7@vLi(S)nyNA^cm^5Cz9`BwP**&;Rh64Fw=NHu$rvc7_p6o1K# z7Z>M6aP~s9xH!%uIM_oLrS&5~i-NwW6!f`sD(ueH^(Y)1&2fs}1N)s>IWwHi%y;9k z=}sIvyi?-&ml2>jl4Jfny4M!XAt>`=&D%*8Z=pue0Nb`Opf_UIt}WCvG={USshAU8 z*NI>~)fn7rn@eq*jL+3fSLdwT_i)&WFwa?tx-{blKM%cJLeQIl)?5_~UUpY7c-g1? zbEbvSaR?g^3UagrM@aBM-2d2c<_8ZFvVzVl%tu5xDQH(x(4?Lj&J14xFoTy$_DgTy zxt)IeqtvZ(n{ZbsH-_34g-qb(IBK4-!gZpY-+;8{@;L48h*Q=_v2ELCYSB4VXelXh zwq>NsSI~{R1{)35P*-UU3S!ryGJPjnYyEW-RpKSwuB}l4y0sw*9nCz8Fdf6ayl`w5 z#z%@sJr|Rj&J`7XTL4{w+hnYu@82%N?eQdx_XlFA)djGI9_S#@7 zI?H#9%I37BwHeDLrn)3yF^Xcz;#Z-XZgO^M)KtcztRzyx>9XnO4G%hsb53(fRcwR_ z-2?}yn`lQ}(DLFSbhc-qt34APZ5d?Qvftf7b)7kAZ_Pw&Qwo7Pi9q9vxT~uWa%mx= zLM#v*UgNd-Jel!KZY+Kf!Rr00<#zLv-}9mS5TPkhmt&hf~|@{ucBT|ZDo{<1Ju{VNsg2j zYQWp*|H0PYLcOkzOflYWpyNFCzm9&x+A97Xqp6Ic`UKQbucnq7%Np9RBG{J}htu!N zE{Ra2r+Xtj_y8`Q-AIaa89w<$O)mO-_O}oI1e;?^aQUnrf_ye0)XxABf!h%u>w=^t z`mG7h?0aU5ieeYZSpjrlAOTu)aj+kn0DbnH6$z!|aCYHH5OY$`hj9Fa3635!#u1CX zFy**s9iWZ(ZN;jUi?DFPY*EmQ7tf^zkSFRGhnO$jbT0c`g1&d_)tV8@fhb6qObuI`S$3+JVeT6tK(|B+#;H+dTQ?EPa_Z)A$B^`l(ffbCpbA+;oyNi1m`7KO;BF5W;NEVCG|wmW(B=z z<2pFm?MGed1+>*&QTd>GkgzR5e9v7iDFWwq0$LZrZm@@a&;)0K@=f+Zvx{R`xj1CC z?%TXbtXd%U(F0!cs-8eyfqOSgsE!whb>Zy*o~H= z?WoV)hU(0%s4Xz31|pn*nkr#++*$fNEmDWZVOX0W#S4u{w+L7$23fXPl2=K7(7 zz|hl~DHCS;d-E~amyeObLJSXUb+J^Q(STR^n94@ zn@s>)BeTl%SH6!GOTHu^FQqQ0KDMm;E0!<%3Wl4O!{+D;?A}a0pJm^OU)BEjQpuUT zav8lZ6MZIPJjR1W4;^_q3wXi<67P}2U z!)khMvx5dWVYV0>R?%@%(-x+i=qBC(6MDTh^jZ!!#<=8p0v2XFV6=4|V!}O0AqS#3 zH-L;o8Us*X6hsz6P!2^6^D=Q-_P~j9f%E|5eoG^*;q@R?qCRV0EmyE3~-bpE7o3uxT;H+KjyaIUcN_8PGgY zg?-R2&h|1%g%z?uS`@TW!>p7U(wb`4KrGX{8NjqJ$&Vz2j(yE)+P4O0K0Z-PObJ`B@4tpeo%+|H*<0CdIniKZjUA7T7N7CJ0sBB9)X^Y1iAScxExkj zN!{uK>H=q``y8WDNmd+&=c#c3ojSPdLFAqZlMHn3}me9W&m138ecI(9;)6Efyu(~!t1;l!Y;3ct;Jk|{c8Alno4eqqb763U&+&|Iq!wZ&UrG}6n^z6E;uj1 zjxCFD#B@7?d=J6#_)LQLBG_8*Lv-+AT%_ZhNy+nUz39N5a6LH_n+#UM^XyT?g_*+f z#6nWjs}U0DjI1S^-av61`Y&qWvyOL@vB56N@EK*|5Tey*CsFHP(u{!SU z%AxNsTN=T^z5@B4huH@C`!2=EP^r`n&@r|?YAE?Rz1_L!@1yU&C!cyY8E9)sM_Vg3 zmMxj6tx1safx@CFWM^MNWavTqo(xEFF2$$+fP(((`|rp~LuVc4;qtjv@V~egL6;2? z6YYe=q$>nyc5yJIy$R5lCIB52x{R5)|`&u z^n_VVnD5zrD2`rCHvd(O?@t1n{mxVKR4{}&c9_BY_w1KrivLG^a4rsZaqv{{sE7dY zRBr~f=2sR4&5D^JO`zp%&2=H57H}&N3$$sQmGdOLHKnagj_X_^T+cHX?QKuM-0T2$ z7^&!p-MhA8|Gr%?J-i>gb{S#&_APLC*pA|)EvU-aiPp;Vq?+SpCLt?mPSD@q$%BPy z5@N@$jZpz~fi8-Jz&D(So1=xIiW$=P#J$0*b=Tk_t7cNrye*5t3b1vnct7GrVq5U| zVUrjiXL#QlFUB=$07eH3MEUk~W)K`ws5=~w@=|tjgb1L60#C`ZRvfCt;ahAA7tBOT z{CUYA-P=Kmzc+^J#P+)3}-8QIYr z;bEso3d|SHB0GDZ}_!C9aKC5U9&A zOrRc-vJ8X$#q@g=%l6Pf33|G6l^d!(3vF%LsIN;=)AtJ_k&_clK=mMHYXd8rz4-LA z4}TKMQ|*Jl{s|U`RuTC2(05>iun-3lM=pqs@kBxbhgM7}bGL*OL6j%D96xyoM+wjt?BZY_G$~?JQq8QO8PI15#23$4P1pqw zs|i>OsNIh%Si4y&U~90}0b7H%wmo4kukW9s{nw4Ja}<8(O;8rM1ZA-cU&US7@b>`C zt__aFU^r{w{U!UK?-7@pD}XK{1)UHZLW_6K@)}pyyZM=Cxv( zjmS5Ce|HwzThk=^qO6p=z~RUtphS@ZI_GJR?bH*{0KH)TOeDo!Aiz*hpd$@KeYtWC zUL*0=cq#5s19C^+V};Jel8&CL9q20CjO#w-GQs(ARbu%>^5g61ENT z(H`ii^FVFpTEqu$M|!d+y6as~ov{v4{@an4<%5oDE0iVcAtGQuO7eZsQhEq^F{=^k zcMxTTKFEnPg#Wok@VRgpmBqfOD=;SLu9f6N^;LeT&E0{7t7{P%VvDx=090jeMYR8V zB*r+?z7HxhHX+1&J(6Nv&|2$>veXT@dTA3fQ#{aI<$;3ub?`mE8HL#w(Nt!I+~}3? z^W1{6f{SRcJ4?XVN1)ek)Kr9u%PKoP5D}rCs3+yh0Pbi`7B_?_lQB$HxJremqp zo1yQDzEfV^W}qhvL;b9rsR1M#9n2><7f3^RZIpUd)DYghUM-*=8?8{l9xa!i%qX41 z>r0Lfmt&A1-P@fN) zwm6PO4h(RW2n|-roYgK~;Cva;G2Zmw@j^u8C4`1uKv3|x*8nXM90X_&f~+gS)R9!H zt(_UHtPcr@1<)2cK(mX3-51AA2*4+Bk)SSiMl%i8C&eaIwFYYf_3L&_OoO+!uS^|3 zNAKx1qk1l{dY?dJ(MdEFo%kUw`o!M@G`lynG@SqQxGes?4_464z1LopRg@t%I!Jub zJU}Swnc&L6Rpvh7uHa(~Yf;d;eGSeNz}7)qdyb~0Cw$ZlXfpO`vtoC1bEa;Zqr_i} zxjM;ybaVt-nyQeKXpg*zMJSG2j^;8aS^A27(Cp$E?#-0k8$65f+E9TE3~~(gxF}Mx z(E=GDyft2;TpYJ+NJ$g?Zk6MaxHZ^~L2!Q9jPIYe;rWwh0<+qF@w5fc9w|USeOQO@ z=@={Ohj;4;^c4cq8`mlbu=(ik$w6y#2I@I{t||`2#Zicfxq#E|d$488a!i}{C8kgN z3TxLaL2A6aKxL>mn}9*@b(ECzc)6(hM-LjQ5uo=(ulejTDffE>nEKrqsNIVDHzKJ~ zNkw1PR`gcyqFzBXZjXebyWCI~u^k^yz-YG@+6wj2Sz%23aTxA6Bm3=TyD?5`ysyCq zEqQwAsyRkIizM{c9YIU}TJ+S}Q12rFjfHzqoIu}mg&l_b;?Z7l5DmF&(A#u|8o+3@ zmhM4)_G)SveCWH6LNoj0bJn51{WAR?SJ70s1$9|^=xOt#IzKez8K5@DfPODO^tN0; zUA8{$Z>C;P5ISn@B&@MEdjtCEcwg%!)X}w?iuTfXL!V`+n7-FM33n8qF+rCbwH|_T zUsom_%T?B$O(4#d{3=8Jc^K}e-p!B>vQ#p3$HxfD^d0jgrR&$qs3EMy-8&7qeXEW@ zU4vUUYpM6bkY?9MiJZ?10be6ntt~&kMG6&sh_okHgW)0(K5ZV13GzRP;d{BS;_7TpUOC!u+T)PFfwpc~Z(= zXKipv%=$H(s;U*J6|6O2pC@2XHHJ6a)H?0_38UwU>Gs0{oY7o)6_G)9KLqpVxbbu~LOhf>joNT9Lv(x#Y8Njs9;ALp@wx*IbAZvgYI1`MuQq;5VJWWNjk6Hm* z`LY?}>iWtwpmTkCS`vl_J5iEz31#W~QJr&G(v5QT2G1ZI?qhcbPwmd5GG9e)kg6SL z=#g4tx5mvewjv3w;{n3^x2p)QWddk+XFPe-EUpWI^0N-Sc-}#9ZpX{#?RfRPRaEmG zx_KFzFQ2v0Ic-w+=$@*(d%KPxU50D)n%tG{>c~WM6X#w?L0YmKJY5&V%F+-!cWf0q ze#`_#S!d8kDsPM$l$+yaxP3#pT%J&4@%%}vyqD)s8tFZ>Q3Fwc(WX5Zso#c2x1tHy z85peHCeVIxBOdq0BM8`A&|kX?_iv`*=HL}{m2N;^&3;nf$+*^i9-SrY(Ob0#cg9mO z)MAT{qO}-oI)S@4GBDC&iQe+{7;Sf;;~D6!F+p3wS`4+h(f39$tTjbzA?z z>#5F=j)$SA!9f=3Z7wjN;{o&DkzCe{F<*2ZAz#d3>yb09#2wW+<2A){Sa{ajksUx2~7t?yVZ!yW1#s_jUvB z-J#!->c&RO3B>C8x9Hp(1n=={Rie7t4bt6Rfcp9rnF*Mk;eqggjkxHs0v4uo@aZS- z{Rqf!8s|jbx5q#fbWotXL}^4uOa-);fH@?T;Y=2GUI9AfJOZzJz|YSGUf!glFWKYF zIU5CN=cBN9JO&#(bDSgxdkz@M_%==(QkhZYgPw+N_Cn;v{^QV4fUgy{d+H5*_ zPgU3&v{k8Xzit=VbdaBFmo%emMg+Q`JkJ{zhqwITc*^uGpnvHRo1zqSWlc4b62fr$ zw6g$OgQga}A<$)r>P%qFM&~hXMP;AS)$?<8CMueYq0IZ5%4XA^I{|Jk3EJ!i;n(ML zQ&ST#(ASQt(r7eR1)#lw)M86Kx_OY0-2^vR<}JfQkp*Gs8EU|^8K<3UU6inq6Ap|a=<5`tFXf}0+Wn^8CT z@JhJb8K6AZNff_Ko{^Bh8dBw?(n+l=6;BPplP0|Uz7^j;rq9%}7o&|vczinsPYKW? z_1iJhxQBq9AgX$Z)b((~9z49Af!o9W=&dloV1o(n-AKlG?|F2WkwUFCriLk zG|Vn7`rWTl1I;DdIQ{O@SW_JvNAob8Z{Mtu^3E-4sP9m3>Q0>~>3eq@2-NKIC?`=+ zN^mErQxECpjaq^9byDB#v+nCFLQ_+kGu;4OY=0yII- z#nqA&^ikM39>s~1+hAd~0*4MRA%(se`}QspJFtH-jviSDPmkm9@wC;M-IQ%*KL)qW z8)i)kTxV|_^Zpt0q3dWC73_w}d>+7z|bxK*Qfkm0zBIkM_B_*D^ zmhC9by@0aR-KfnoLr23^bhlF1yq*2dnHZvOFNf9*_Y!Ob%mhmDMQ4eMR(@!nutF;O z8X3X)Hi4Sm9qg)jbe9JWNnO(o`{V(;6&gjwe*a7<=$Fsf7fs+4McYjKbc`WNAb;|( z5O=PHW3J+a^*uEdPpCK0YK*a_?RauG7EkZfXKUP!vF5#ad?yhP zNmUP%x*loTizoN8aR1s>3{;U~Z9G7VIt4fSJke85z^>m%0M8^4I}*V4ajnBz+$Y!C zPoTeQ18(#<(|3_W&pU*kGJTBqcu+4R8^g^O1o-v1-gik9d0(9g0eda34+i4aXd-&5 z_n@=X0M`csaeXKpT@^-XD_Tdu4#rr25W#p8*=7RvRg83BMq9A~I?A@;+F%6wo1I9F zuR=SW!^cN^`1pEsSDVmpmL@I-9x!D{-{2|x1Zno!vk8P*EsMHl-!gqq^gD}>nSOT$ z^bH;$7ElwQ#~IM&Iyl!7oY|@c%6CaUKe*RS`*j5HO5CL07MFK!*W%W#dV%z<8}weT zS7C_Y-A0W>LqjU5=x`**n!@+u23T4w(nWD7Fe^a+7}7jQc-(Y8&O0xIx5p~@onM0h z@6Ct|x047C4zY`hx`2oXUR;>n8|MVpy!tmsarkm9w2u=mc{z}RCP2HLfTPQC*gGAg z-q|V~HvSA7^*_eExu0PEyic)U{-;>D@H1>!H%A8QE?=ZTgs~Q5JbRdf z2iJo!SVM}n`5+$MNyn|hOXwqDk2IMGkZ%%*`>P1JU8nH$K|aPiP7=^J;AWpIHBi+1 zXfY#2y&gCF&ruH}52LL|3FsT>I^LwPGceeAkbtj`+oK_*uv5`jyBA$$8*y_e7&k{E z(OtP69rPVs9}LC#KnOZYH;eK1Sg#+!cq6IoZPdGo#$c<9O#b2H*9HjaeSCZasq_QX zfMpUqYYCLq0&2}Qah;&c@V!akzDdAjKe6&JGgx^{fT3PN=kgcMic)&jYM{RiYuod^I(Pn7hze~`*-$Kf|Nhxf44!g6ija8wyhZ^7Z z9MsoEA~j|^L3S=IO~1w`AOA@pti?QQMq;OJ}tOY`|S zWc(@C>3xi^zWxZGfBvD^S6_dO<;!MEG=|?L2Wn94C(MtO_|$#2%WMQ~Umd))QnoKD z)9NQoSMSH=l>Mm|7j_!8MSie2y!8hsJF_=u621lWn~(U^T({Q#>!P6JVuEF=w*OAIxD}e4I zwK?A7N-Dg8U>Qm9+=`(ZeS+Xx^p>v?xLqf8`kY-D&s#(#|M0SluHQ-5r`Lh*^?smz z+J5zYHE#DD!OhMCc=0%sjG)@QlT`ISJbRE%mWFWx_>ImZc=4ndk8XxzxQ>9=dRPE_ z?^+Nk>>UK+6L|i(6nBO^F;uq|w+GM2{`Ibt^!_$U{jPRw`Mmw%M3_e$CAZ~!e+Zk z+e%^YAOP>DhBFz%?WfUJs7L1;(y<7FcmS#K4b&SkA*f~(I2nv}q7k(#^!FE|qdgfVdDe)J*ac^MJz048Pw)N_ z@9J#owq}3(;Lor+vIrMkmch$yF0PzkfneWlh>Lbca1i79aH0 zpfi#;Tm$qaZ)cplK=;lWTe!Ge!HEHFHW#M*KE+<6kD#yjJ{HY;2Mgx>5i6Je89TO2 zhv(^|xZ>qF#T+J$z%54G3~^-&;L6nT$zzk}XwUm^9I(3p0NavDL_t)MY4y4?KKu;o zim%}4;VrM;0{S0#$RJ_Q=!>$-a#GNtIOD-F(4?RV#tckN;Z7O@Sh+7)K~E@U9h`Yz zJ!euiPlYsZ^K}@|5fLHq@%F^3Rm&vz22Ua9W6IUR4S)i4e{TzlvprFovKuuyrf9DZ zm~e3nbTgdU#gVC89Q_<#mxqx7QhtL3GV1Dbh}|{L%Rwso_PCadgUd3BfqrzaiqtHt zXZAs}54eRCbUP_%Qn3tWQPEurqCfPAx@DF9{gYNaxRoS>bM@J4Q4qfd+0m;}l%$Wr zHdnev10LOo#8~4tjMT0t(Bo5cjmdb$RKm>N+k8PE)3hV-4A z3fcl_`dx30mx&wW#x?3S(Kf5^`!euHfF>o)uB3ef)w|NlmAts4xu2j_#49_8jXz zf8Mv4Gkdz&yt&_q&86)ni)P`7=@xjNF+*tJ2~y5Zh>Jasq(mPA^c9)zos>w%lU7Jg zN9mTn3JmgqpFdAjVK_VCf|oPSdODDTW;X{96q@7sk-0EG@HwgI&#`akr`T=uF?MbH z2)nj^43j6*e8f{i*y(<8!t07tH|yK8{F;IExxm&;sbU zgM`2Qh$ld|^p3qKEiV-X&4AVh3E5adD^s9mz-mz)S`>x`Us2i&c7d}7^C|8O9kj(Y zLeGzji$qvxAPhFF#n;om#yb6Vl7LD1pjo+}rax&cDd;v-l|-Pv+y||-q_CP}(AAP8 zp;nw2iT%$5-B}W{rbTmbsgn0Amj^?e{g*fS<|S2qeVB7|3v_6b00lt!!m+;HC?|`8X9g4UQj)|ZMbCc^6T@U=krHZ1nUYphwGj_ ztRx5*(evwQznwr#>heBcua@@tIxY14W;w>LAc-BPo(O**JZ+xAeEV9CK#o=Cz1u3L zTTKqCB4ASEC~hVOCr>2G!mVqh^lw$r^HMR=aRwuu=LqCsxN|*=&MVQumH^3WS_b*J z$HUNOpD_blWi1>fV2%x!2&^Syhrr6O&jZ2?W(8=fzf*%pJn@JC&4a%R(5jpKiQM3AbJLwTd-^zHqt78e?jjNsE=#)7lw@BdCta3&&bTTg81eDZ^v8_GKI2_jxM&ep z>FL4E-FX7g{JMOcT^!~4-YCyJgu23$=xhwtCG1a|7#tiT6~iG|V>}sQut4BE(w{}! zIi#ZVB?Ru;P&&r?BQVl)6`eKqXeqZwbM0kRS8(RJ5Lu3jqtd5borG}A19og>OAOI7v z@82%Lc&{gVDmSC2!T^0WMx?CG3EHs&%!l`>0U&7d_s(E`Kx*~@D_f4j;6|2SV{C-O z@)Z1eLJ_+$L?QD;Bx*!>AodZJkM7suDTgyYZKreiJnDr!?ZC5VU815TF8(p~HmFXZ zP1oUb9zSHiH4i5803$1Uj-TcUFYH#S#K=$)TANcOsZvF0IEwOvk)IQUyqsXEy;ab^^hik0b88!5A9N)WVuRI06#}$`*Xbb5 zpj9Do+5p}ps0F-l*i;x#HSL%d2c4K0OMlEbn3^8I>NR>;tG`|{>G5kYr1^YS(1ZPL zD9Ug`ev}#{Y^^+t?iOCfJ6U|tLp>bHk)azTRQ_j);^2fyGMdlRvI{ZX9fJ1K-Dt|w zM@7mCWQH$-r}HB0-nAJEs7w0E#~mb zz^)B+%DzCI;4Ur}dObSMap4c{QV)WZHot~?kK6#TT4#{+XX5Ab`|l@J-i~LFO7ZA! zChm^wCdO1dqoLX#^|j$>X-bqF8TA$3s4Q?mZHW_l8k{lE;*9=gDw~~1F?$oJsZs56 zLuct)beF9`cljFn?l<7hwFrVLD_n*oDP96K!TmAU{ELF~R|=!(iEb<9ec z&sVUm7brh{+=OROcoGu#kQ(s(SqFW_E~;-6i`0ybpUcIIS9;NWx|SG=7N?B^;L z^pBV?o6D4KUA-UGY5Q88cHYGCH;n31V=th&A`q75+g`cYo4*D0FFoSZc#v@XMMZTb z;$@J~fmF1!Oj1!%9LguG4c;kthk~!TIT*aMuava7JKj*tT*v3B=jqfqT`Ms$hPrVv zvK}F;XM;_fWoDtgj=a_x@j(v{cAz-J8TpZmP#n7)jdX)|HpR+7p<3#SSM{c{D^&&z z8O{vskv_Gm3LE>Q2Rnn%Qn&^6nafd*Iux#-R z@RI!zm+3c1T!zZD6=Jn{d(qP#g^oH0)MV+QHft3cb62CQoB%x*CT@sF1ZIXY`+<2< z39Dy@G}p1Q!WD(ggMI`~9sqpGP?wpa3}~K=q~Od+uq4*}S*Ivzj%Vi?qzvt+Pugjp zdjt%01!b-ikdsM6!R`=J*!-Fd==a19P0-Ues;P4GIWj|(1a zan@xe-0kPW#dbE%c-gBWCVIDC(n1)J)i4eH|@F%=*F@DSek8nycA79;BN92`BU06p#NFJ#qe1=(NW!@vCn1{-vM&R?Yi zv<-o&fo^IBbge`V3=Wpa!l3&PY@Y(?Kf(K=mBcyopd$~gal{4#Nv850L`!Qn7ZH-?g>%Poz$ohSa{G& zJH`r{;mlBGB`pJ>yie~<6u&N{P~H!_TP6X`&*#BJR?_@@o=kIh>x!y8bXHVBZjpu(G`~rX$CU`njy}B zW&l4YmHbTL+d{{t0GS#(H5rM2H@*(-QzI#W*10+~kaH9Wt9D6Kd%GGujeJxl&=g{5 zARoOwdFW`*Mq7(okbxIysHyNpPW(nhUzvv!=De`Na(wZ{XCe-M{p)`dJG@8ZI`|#GI|EJT)8V&YB6J&zzqGw7so?g!^sY@Hytq`wH{te=W9P!8C&ZB6yv* zL1@5fow-kJGoWRkOAXjlY_g6(EB1Q5Dz#%jHto7;@fURp+UPBy|B*)m0h(tLmRFR? zL=|^V)_>YnpsK||3ov#0nD1IjnW$1z7AfgQTk8VR)e@)kL35HM6~)1Wg*-^8k|ePYT19cNYlCxg z@T7*Ju3)90vq-h2E<;AxLbzDZ!0zpxk ze!0Jr0Nr3SLMz;4*6X*3)bn1|pCGZ1=d7W~i7zyeinhYNkIFY8WkQ0<;GHC&vgT*JR#{hDd`uw0o3PDRZr)|_tb-V-XY4G zVJ-XLcPWU|^*Akna*Q~Ab&>Y>gZR2-1df-zy9RCW=R@2}_=4!tP7cN=B^O6fG zXh(sx$2mJV*fF5Lk~rw;(?7*`-+hknW_*rszWE$Wm(0P%vo;7LAcqB#{Zy&5Nr+F{ z>&FPV6Lo5v>(utoTYCH@0rYWmqaR!ykGuu+FFg|32igD?KT;=QL*Wk4aCste`OA|o1p|a2y zl{rUIUu=)grf~5=t8}BRpvkCYfAk2iM@V4iNDiJ|HqJ?M=qBNrW$c4)E8d2tTKiw$_#0? zQC-REn9JcQ=UgM>;|zHAQETV0@wNH73|M{*buIN=K9`})&}ZMZ_B<{L_F&j@L%`=U z^mX7T<9$^}*CyDDkCs%X_IcQU{pe;e#u_%FyL>GQ={xmwSpoBdYq4U<=a@Z<)ZCnD zSUC3+Y}Wq{W(U^blJi^w^h~i!uHVA;#C%wu*p0pWHj?t2ML;3tN2Sl{wW!G4gWirr z=@D_GD~YLifrI`caQ0xgdZ^igBeBRwQG-sU=vg5l?L3EJ#h z;pyW%V0hy?PoOEs$Z#o!sHdg!O&6f2J0Go0At=k(iu8!ZaJHEbgZ0a(7x$^G%>K?F ze}g~%@ppLt{Xb*r(goOI_$^MFeh#OTN=37Rc6VHci(a<4;O(k&b1i*RFDVCAo zg|_NooH(-m2RBEHw}Aeo2LrlQHS)E=5`D7PQs*6QtwN*-T2BK;6}x zD6Jm794d8FzXw@W(~aF1i~c4D^wpn4UxO9;8m%zUWKDIa(AOS-{;qTk z_N1V_@)#*?L$nncQn!5vZuZ#V?w|`E-?~aLA~2DPWbm?*x-*`Dy8LZ8=d=u_CVDt- zwhneD4M-_iOB4r(t*JpZg0z5;!KnZ(5g9tDs%-_q$$CDIw;9M9Fd5RC!sg=)NjBc* zbEaNL+ox@DT{P&dk@mIs!pGQ`%z)-PR?fW75ZA7)0iCa>l)9##xsCz-^iBwFv~0mh zy#YE)^--I>7DWlGkrK8JsR>TV;dTCE_aixIF;aq;P`Lo{)CflT&Xv`*olh;oN$b7X zy>}xi$xkFL>t~;S2oL*JC`d9!OI;+o+fpQrXm>{jTAI?))~vGGvA=g@AQRnn$IxD~ zhJLekq~`T8Si`d+o#=O}69vpbRSLOPR5B0Rs(l_fY@+QBf^avT$9{NL$PDE!QO)YP ztfD&w$n5Um>+pYoebGD^skuAu-r|Wfr1WLhBgacCKo9m8Vt|a*bVo}VDzlAH5WfuJ zmlwhM$SiE%^a<9j_%k-FnT`$mi^Yr#=fKqXOW0d}30H!%>nSpu={PNbK7|Wj)Z4w_ zgfj%_(`T(=dvY;O9{C!_OsB#8z%(4(`xT6Let~_vzJSHy`3Uf_B_N;qkwxfC?K8Bs z@^y&+r2V~PZx{o*xiW|q^eeZw3i_8H3F*0REq&KsRCAbJWS~s-RtlPZ&}#Oe237$x z*+l4^Zl8gx*#w}a)G23%vkuIxl;vCoumDt<eojhqyhL&2r#K)tY#~aM zHlnrW3fdcD(9sw}H*Or7YU9z-lt7T>s19~@5Jl7yRsk+?G!gGaYg@Zw1YfwmSrAw-lY14?ERl9Ifi zhW@%;C`np@w9uuIwQUW^ z3eHOXG7yy;LNksk`Tk)Vo*s>ku~ce%LH=aIta>k6RR1;ekyzHMy~QthkP*4~%S1wx-gR6VJ3zSiUG=kRF!EFO$`;Qpuw zZuGfeyzd+s}3As*k)lkz!_4G?5`fba=Nb+8MBGZ_+?AK#<*JbDF>@1|0H z9o4CN1~rG{vHy9(C;gy7{NFs$gjZ)BF zE(*}+?Q!~y6&&piVRvc+>}gU%x2M@E32Y7A^$ zIThfO5T9B{@SRexfUY|hsE#W;gUm#4v{t=^Zkqu8+N2a6sAX`E;HtryO=6;_Kw7D09h`M4nvZF24OY^!W+5HtFgyWtsw?uM z*Ptwo7mW=-dm}06rdTQy&{|I_nv`^32PtSC9PDF2r;*}HMOP~Uv@288^tIt4+!|Lo zoY{CHgGy4w6D>GdziyD|Q9YhMtW^;hFWG0yP-ci}ij()1kN3rsEZpqahtazAGE1<# zOb>phG+9ouoQ=Kvm#oWjFVJ3PI4f!=#9oyRVYZaleh5x3g5;8yEKvQ4<%VTAhw z7Ie)DI)~neC~CewHy8|dothSv&5-6g?Y;4P)jkWqKi+5e2tQx>%LVG9w3XTx-|wR` zJi3#GTceyqC5nEV2sGCRqagPpLPMM+eWuxwefa9j&+(VP{25<-{wcgJSfjk?D(b3Y zBnqOXF-1i~)Fq&?K2gHf^76uwo)&2Qj^?}lITkR`SVCj@ZN5MTvAzZ3BBv4pqJNqBQ!XdgFt zUUJ4+0yMigPM@`fn}>~r+c~*e!_n0W4$ddw;Bpe~9;Xlz;DN~Cv#%Qg`nByT#_-n4 zHz7V*uRF#-o_dZ3=_z$t$vz~of^ouP`zv>+w=Rxfe6WIU?iqVgURjRhgm6hWs<}8+ zCOZXWhOjoRTbrc9fYy$QYGx=4oE5MI%A&p%ur&yC9JB^+-j{R8_<8EM4&oQt#i4R> zlobS_y7(-bD!oWKN0MTWM^|$kdfJqGgG~Wit)9VA9bK&{Xm94#H8Kd$Su$YAv%fg$ zj+QJ*ZY*6KEQei5xAz$-sizH8vJ%xG#l~=C7%|XzP_0h@eY?{bYQQra&F2H!v9sE#RsrgK<9-yg6f z_-?{Yg6~a&?~Rs?3clZ0s&fdG53ilY_2$j=9u258kaO?#9-wm=(0ok>FvFF%r~0Y+ zwY2xo`IkaD$^ghfA*G!9`Z(3f3I%#xplLdH%>yu|zebrw1Z9*q+qi zHW(UifWE#Swr<%7|4aLjn{Wu#Wg)UcH!J7*S{15RQ^V;#W09EXkHD*E;oxYFty?!j zf1Mr-H*df>*X@Y$Ta3E$%Mz39>tl~qD;HqPriI9e+e80>9Qpm#Bp4MZ%`*?9qrK@G z%V4-^F>(@i;K}_|dfyza(m|$N9PERC{+zdYVvCCGU_i6GL*k z11Q8$e0%Eueqt!GPvCXr4*Pxi~yLRJu_u zf}R^Q=xVmU=?H)yp?f1!^0 zcae(b6*$u2z*Tn(&J4Vai{kvUOpp0ib~d?r;C!902&YeF`zY7%ExtX z108_H=o;)Qc}Xfxy$^mr3Wl#{C|QSV?WWY=6cI$a2_AKl zys4GC{AFqSC@14pP6q1t(`PMJpGVvptd#kEGK{Cb7Vj&7EAXmw)G_)T6VFlmN=a+L zXQORt&{$P>h%13-_i;!Xy8?Ix^J)TAPR1GdUNFMJ1KVJ{#}J1P7$L}OE3#v@qPjE? zbrnIVDf35VNdU@=15i@vkF4}d2nwQJ-&q?RJZvPZ)_m~6`=q`m3qnB@sNNoIi~5eX(m(A3DOcb-x-AFQe!lfSt38n7MCwu z!PV6i$1RO;9ifSD=T;T1Sywi2hTHzU~J8BrnUe$g~&N9k-5;*<5S zfqTM!uAWQ)eHm>N3i@a^A?Pij|K5Yc?8FCMSA)d(Py(h(H>x5u2&zkBuAjux9l#tkqi%y;V!G zVBRdu_--1NGhnuNHZnuz%RpgGz8zX>BG6VJB?E=5qYl(X~1CXDZ~Wm7-J0f#E?QQ#Xx^9%JN7-Ij+XO zy_*Prn{Z(NW`z3Dd%c;i1~PdNQ#XM|ndb6PfK|Zd*VbT6bv%Xqr3PazC(q}>G*+Gb zeW~O8-BBYWA&Sbaz_H1!T<_fCH33V|-x-4P3`0a+S&A^P#Rw-$zPb?k@kXd6FqdVS z)Al+7_FAMx=piXo58=Mcan@xO>>W(8kAVK!XP-z0xsN{l07iz3v47_`us*RJ9;YpF z@ZffW^HQwWUjnbQ1}HDNf?87IJj<_zdRn}ll^p_GI}5B@y#gBzRw3MP6NY=k=zXgA zX`UAT=mGUw?$%Nrht{!6gB5eF#A0)<4(^?Ceiw%G9d3l=zr|$@hPs1MpSzYm!%}#< z%*W7bsSav81FK@8|0-nuycfk#4Gj$2dr=!;TblQ8P4 zZdGq*rJ!}{SwUC9ncWgn>RcI|m5z;Jtr^$z`5LqZ)MR{2!J6zm4;Y?-i!=KT4-z=G zQY~*7#GAvIG{Yp79An(=ng-NuCO!c z3U@RD}bJwuw6G6R~y%ivZDTGfw}u^(9jBg2}X z(@(JL!R_1S^tsGnX}$z&)-1wA*;PMzkj8oe~_>=I_D)H*FGD+e`+|M zchPsm^_s7pw>f03hZHCexN%%IM@^`~x93lr@bFd=h8uUHr+h6Mb5@`#Z7C{}m!c|b z51MO(QJ!@G1+j~f8?zXxp$ib}KMw((vt%Zo^(p!f9Z&;|3}~Jpvqo`cDX$3DTOIgU35=ajuYCwIm3#&{({U8kog! zwVh4xYncF=W5pTHlYpLw%?1l#W%?OB?4}E(+0K!9o!>5bq5ZF(#pNp=xa8w5(H!iH zWesr(r0*UcqBI}mg|5fe7WCSd&!KwB$+))?NZWH3+G zDa%RqLwju~P9ELy%H8Fyg8s!vQbwLzQ_skY;?iP7M+8VdXwJoWk*lmJZ-)c{TEm;ue8)&Si@>bavi0W}3DP!O{O*%4~inveTz?Ax_~USl!V zFZm7$AN?6!fBY>v|L|M1Q`tt=^v7SL@-M%|MFXA zXu7FuTn4X;4g|ksf=oBQ|GpIk`C&MI{2+Bx_rcuUm{gk$1_ny;O8nTYz`4{ZX>kuI zcg7E|`U!MAiG++36UjaS_~j58A15I5%t1OwMTOAw=$af&FfvkvjKl+ULwp#aI>9ew0`}3cE4=1bT80(LdNgJHij{U^S z2d#k0@0A;jmjqe{tMVhGl@>Cj*?H&*y7UCwRY7*W*D?t&x&J zMfz-<+j_ih4~A;>B^O6a{wmaGuRufLezequqA1k_Sy2S&*rhTVCg|cEQI=LmXXAvG zF%BFuqK0QCzWm~IeEs#81f}Wt>Z=d&$)|tAC!c(Xk3aewJ|t!R(MKQ9{@?KVXPnUf zlPUHwDe#Z!*hh5E-{ibc>A4H$e}{l8E+{LB5Z4$FILaV1!I!h#X})G&k%fKOlYr)# zk81ii``j7O*T?hGTD}Jb3CnT$>_QlAU5>ePzQw!m{1(6e-LLWc-~R@G`V-F}oR6)W z7Qoix3!HVBPU@Ke&E_%_zTPId8sdq-;0y2zI0tWEcU~hr(3}%`x6y|% zT>n1S>-`yPSN=)zK?nHQ5tJ|JOoQ|r+YInGjgDym=Y1*ZJ^TpXQ*8p;I-|OrRA02$ zh!6VJX_sSf0sTu4iQ?dygq0PdpeGXclPYG2YG7tqbDfhDDQuo;C@|LL*&tOt=~tfg zFG~c6?!1X(3}&72Hb;$E6QH+m--1nshS;;u1SSU$g?>l&li&gXOZT;&c?$JiCph3_9_;%3KQ8Dt%(T8GXOJv0-fn@bL$k#6d=7-M*! zUQWt?4V+J{f{o=;YKXptrP)lJJh>a@W(M*e8S@xyj~)&Z^*7OS-s_UJsD3@;l*ZYpIsef zye;S4&%hToiyH`TBo)d%vxQp253^y9?r+I2tjWF z{r4X1;@~Kb63GW0gwwioqaGe=MQ>5P9MM5$Wqkt6R;<9j{rjf)o>e4=23&@)3y1g+*89}U_Ax%oUoj~1OA1yA5?1)834N`!%G5-v6X8fMIe4k_aH=iMi z0NqbO?*A|Uj7|b{7j1WtH87x8%);*Ns}Xp1DasQUqpe^ShU<4pWCq7Tw>76=_bx+( z(2eq(y6EgjwLE5mV@FMpn-hZ0_Du0@4i6RM1!sPfusrthDqr^V2MM^AS3w68zI*I#{tZ@&2yhMV1$-^siB5FxHaTOjY1_U^kS5h zgwtrR-w#Fzc3`9X*C^9mF5JcU}ZQBj-2U5^{&Ywx8opv>sg$*81SDcsL z;`J8A&n|FQK4@`GaEKq78VuB6%g1zSFfA<4yD#Nk#Wm ztVMgV9@;AoqrNHxVFA>u+Pj<@?KRSHZ!}m5%Y)N!!h8m7talOAR${B+Vysv;3yT(h zhv{Gc74N_II-nJFUx%<(_vSIJR_dy zosYf+^e;UUIn0g}bXi3i;$uT(kWc~IRUqx+>I7Fe7lE#+>0x~N^)xIeNS`=)94D<# zz>1B)t!;BX@7vf|(es=I!UAZ4GP^e>0nMeItrfOy-He5c7vtzj8#uY26?4>;mX;Pc zWU>>d9gR?!XoRYqBLwEFXswS?gM^}>Un1-%w_ma9-4w-oJ#t1wi*6VD#zivPK-IaL51 zDuCuGzbz;(ipH^H2Sr&QI=BlLFW94}hZMJjm}vuzq#Ox$Pwqrww9ydV<)qM)mm|b$ z9!!k&p{KWU0<;RYzsItri%9(#pfGkN+6q_8(pqC3r*QXHF@}apQBW9#-Fvsl^Vom+ z4n4=o{s790Lv#u{2q9q}*uHZE-g{5ELH_o^U*O?tN`TH01^w(%{Tm9JOHCEC|5yX= zq+-@wAlkm#R$+EZMf1LLd1&Wr&)2Ta`kEq2KRgy#JT?@c#SnNp?I7>dHG=&BmG22Vr+|DGu)X79cll z^*BXl3l}P#-EG8pGD}3rdBjCrL|nMCSTTmMR%+W*_jUFrz;)1`G#!k|czf!;X1Qrs z(4q4|pK*Dspnvg^n2{%dE-o#hKR_Uyooq?fI!fXqCnpD396Jiv(;ld(tiZ)f7xC4! z=>q8)GiPG@H{W2|^y&DD_P_l4YkdC27x?V+&&9s|j=G+fM|FT!t_}vYY?E<4yGl40 z^rA%z@XdEKNI6sE;OQ;qalwa5FKQqhU}s~23$9y{!!rp}shg>rsKTmQ^F6Dn-yCX} zBw6lQMOWn?7Z*on=zPTZ&W5}7G^}4U9rNbR#PS(mAmNX{LGS?Ug` zYx?zngZJ9G1n4y|-ldPcs1=ehX{b&CnsXrwpm%D3=43l97#*!dM@K#i@*{BB#|b;> zxVM)R9^7vr08Mdm{LqcZw|T8X1?ckB6$tTWK(7-(^FpJq1A3tVIxlKDnsZl5*MG3y z7`Mh!(bt`fjFeM2cyI$XJl_&breijhXWfiZS$qYhCDAA-2tj111+B*6#`Cf0zLD1blx6*gv)X?KfXy`?fV$tG5K% z8NO(1Oh89#3Vrvv7#b+RKz9lTdy+^UGnmV9Z72<6gQ*1NVsUxgrrs4R>D!!zPgY~8 z!uYicTpO#v$Vi#w=jiOnLThUVnwm0DSC@jSs(6%^5vU6zkxf0a^o*-WO}~nylmNsf z_#sNSm@F?O>*wzdZ(lcD@^Pj6>IB@}P2ucv2u?1CVefQ^RP+JZJ02v#bxgwD1ke$e zrr0E~HE2)WS9Jv72~+!VI-7b-Q`)jWbz5h71nADXP*@$^`Ra_T6Us{_R)zZ~yvlc<0?e;jrmJ$jn2XYSso2#oeJ((IzH) zsT)5X)9AX+?x%6-vL7z{2g2`au#{)dxWd8i7`)t#2+#{q#(=KzC-uw%LP>VFEKWuGH$*-YfDo{!`uGZ4SvOT^B3 z7fH+hgo}GQLCst^ouEb`aXC7vt36B#`sssQ2}|P{ZM$}EMhJB^c{W;KPp;1Y94Bg; zZ&Yim!#HvLAl-~*G6<&9cd~-+#G~u}1n5oZtym|yk5j`I!{OvwQfezPd*k$=Tgz@17aAv;mpAw*{XP|}5O-7wCSh>_( z8XBCrPE*jluZ}4=D@Co&Rf>9IpSF3xQTeo01Mqr-z}KLCYRtI7;0TWgr0|=Yk`d@{ ziN%Y)R*lzhevJ>_|07&&*C5!>gc=}6T)D7b2GneiegX4+A7kg153qLSpYicW?-GzF z)$xx(%&`7>V1M=Hr&zmsAy%zefaEw&)K*5Iu{K5)A?R$4Mq}wwG!z-5zw;`FdLz(Q zz7MTsyD`}5h3ljA8+BjAP}c>Fk0eVx^!4!?Ss8qcYdZxZdlr4pG}P55 z382f%V^Lfjh1}dwWMl>*jRBp^3&~!VRaPRSFNum~K>PT*;*z<t73?fBjp6^sjy`fPR+%ZEAK%psY>(W)&?1hZ8>OGo<`X zuyEl5EMBq{_71iJZEZ4(*jX1iJDz~oX(Qx@FF;A+dNh=slL11uj;2^K_CI$_0dyyo z^~F{wj$ewR*hR>XS%hqQe!`Wxi1MC=fYaaM%K42553(m!!OQWSg3tK_xa2e!!Dpr; zgD*&r?1 z8)b#m&5hoS)ZhiE$yh0_jlRmY=&#bpNYh?CxS57~;|b`l+=9H=<%sZJgh=m&lAW(4 zX$`s?JaFrJDXtGCqPchneFsaBLp_SBwB?e?ud{5s#6feSAYP+Txj58>lF79Y+10`2 zq)%D{xZ2j>s<}k85JC;OZ|u`?j-BSI(`wL>&tVq|Kc7qG?%*laTEcx^9HFx#2T{>p zSiWN6MDOCG58uNTpHs4IRC3}4g!*lg#7h@lzQJkRX|O)>1won@3wTcy^HeZT+RxQb z+Sgxw2K}{*uw?OUgatXFAlnb6g;!Bk9);?%%P2|PjN&Bf-BdZ#f6y1z+3UcI4si&tOi$V5v^8X6i>QNv07D+tgf zQOL^+MP^ozsOXf`03;;(A}(G*IwZ^!R{~DsvbZ_y;cCAGcE_h-%cigCUY$-o({J(J z%o&(5dnVSbU5S9pu85Dkgak4!Uo(NVG6i4_)>{1(Fl(j(TW1X6*XyS2)A{+Npm~tc zN?aUo0sV^)_Ca$LM`lho!a}depq-PGo!CjMOzY+y)YIb-6#u7g*5h0TbngPtN6g#_9)D5$hIB5p7 zc8tq29!_u(KyMR37sf0_U7-Wo2+rc-;4nLh+)!}lFgu>|-P4wg<_ag2r>r6HtwvSm z7P@hEqAYzoic_{BKVd5h(oZ5c(+6ou7m=HB8F?8VNR2Q;;?=dtj5I)Df+0O`J31@( zW3cfMu6Lip^T)-K)r|8JrzT$^<&!V7%Q)FiTT2$ay`5oiZvh9g;Gi>-Vp7(;dr&VK z&z?W;z~lSW4eqqXNQ)W9yH4Upj}1oKPolT}DEgXCVQe54quSep(%HzSXb$KjQ4WmQI7{V(lA)RThuzM z@6M7nbbO7d@F&#Za7H&t;?EOuCI$!62@&b_@ zwHr}>ixBF)00Ex!;OR08C(Wm0=64_BwbhF?TqjcSH#75A|b{J;l8U8d~ptvV~-#&(+%-K%Mf#A5i*l3 zP@M0M+_<&Ki(5`TI{F<4^DsJGjK0n=w3Hu0W66Frl^;W6g$?S;tWjI;fJXXX*VhxI zs}n^<7Zye!H!lo1q@**mf{~gQAWAwW&JW>{UK74(-z!dVcUlI=lhd$&*B4m4@FUEh z`!}&Uvp>MPH8W*>!GtI;0yLSf{1K>s&L%*u?C&b=H%xk{uU{iTD+T@G$DiPj@BAMB`Y->P z?4JnCzs7GE(7*nzDCmFvw_o8;e|`_<=B5*XR!~-IT8r#p0RJemL*k^>K1Y#Qoj8KS z2X?{LW*u_E=A(!JU0>vYjs|vb#G;4Pvhq8tvad5$rgismTFMscZdUX9cpm6#4nl87 zj96D|q)dFMtqekCX*j8&P?Q#2MM?e@6z5(M9BD6=db~`n>XXwa#kAU;F%V3C7zF zVyJdK21$+gSFICR57cbN?IAyzp8V)eHYx7?qSo11fh!fhhpt&b%DIEoeVfdXWEe{p zJXXx2Xcds9ehQFPod#G2F4t*3X6+o_Rz7KUj^>lrpgrlMR#5tm9ub%IP+8=Rmc~TXSNfs6z#T=|PRL7lKw6?L!h?_NX6t>8 zZ>E2VZ@>8p-%R@gpMUy3KK|%EeDo0m_%m^1eE7F_@xfpJB=OOF-t=joW7=1L!*sGQ zKKqdBK8LyKHaOZHgvq{5Sh-?8fqOQVF8mlv=6^uj-(aoYT&!695tc9d5UW>yOHiDP zwW~;hul^V|$MsQG94Z<3+8ew{FzBO-dPbEQ)O$)>g_4w&D9tcLQ$r*g8`Du&myF7) z1eBCSqp&EFKply^{BUGvhmexKis(3hL_}Q{UvzNjc?1Ny!NYkuoUEtA+Tu$b*!?kf z7=C~)8{UWE`oG}7p6?Li@1(%28H0L?O$9Qm?8&;H2f0$%lMvQ`tZecapIeX_fUbsc z<>GKV{ua=`^w0oZR8oS7Fn?0cwghKKxVyVZ6vi=23kjaZnPO|^p?Q#;Cuq~JRP9zC4z%oHtPVg)ffthE-4PM$hCn}CczK?L_r;U&_q9eypgoe}&Pn|3y&LJccP$e4Mz7-8 z!!pSg%x(={NrP1}=V9QH`mxbU^!FDDl#`Qu>AmY?$&xwLHJ*d{^gZ!+wP+#T&`aiG z;lf#%OZzKUETGpvgVCWPsFguDuLCdR#Bi>o*J+$E&SA_M)g-GLtKJu!pQ91C`#BfK z1`O8d08BR0ydMv5r;!5fq~}&+yxX4YH%!2p&l_#tOP?oSt|cxQ_CfPxm6y5|StR;I zxi^&SgCWgISaWe`E($Ig*sOq+4_Q;xlR%%Mpml!csR~*t>PZEyR60M0>v`&U2L`%B z5q5bU&e$)4xBF6rTwIR)*kx$1cgHZVqBC5E!GRJemF(kFkF3EUa2FTa@wKSzloFvQM#m$v0TE;5*EkF%5G_p>NRp3`QHjgMt2H z7;IREJ=7>{*`kNpv%kT6e|{H#`qMizKQM34)C+52@!PqitqR;D1WZNCZUf3FFkH6Qd_ z1^vs9#PnQOp6XpuRY`xGV43R8ZUpYG}_wr@7;giP=xIN;Bv5w;yYd=QiF+e0=ks;7IzG1t zPwpk5r)n#j@>Zd>U=^D4R-&y)4};Cear=4^?%uAIi6b{iZL{$<*WJ8PMWD`u$LZtv zhLrK#* zN}P9Dg{-LMC`sFh#`dBxm#usg5Co9?>$1J6J4`QYF=byWg;djND}t5dX|iK92TeZ8#8R} z>}{~k$OslkkLX+z3a|{_sWzGCS*@C)mb}tZjcS0_4FYPuW}W}p`QIfa;&6Sr(J;%x5pyt}p%6?e_ixc%{VX!wFL%ms&YLq7y^tA<|AX2I0>Yf@J0sEhmg#ERZiSM~OEUW4Y`RWd+#jo|j|aTNirT>#C??BBi9 zAQ2m#4d+miYlgxcj$O6G*)ztNIpgz*8+HQJ+P-f4(%VT@6fB#l&+@vRoh^98WQvp2{%32-U(j~L8dE*M~Gv17S z`!-?inx$B|VhL8QT#CIrmLSS^A@b<|-PjO;rlxdK(G2NiiRh@Tj1yRwm&ZwD2m7T9 z*f*UUCWD8`DgKCy_a#VQKwuF2qdBU>3Fj`@~PW*CNs_>mfR!f8o2O28x& z5X)>q1yC)KzpNq10M;#0#o$#-Se=z+tF)y1yw7S`;H?9-?2DU2WxQiRt7|JTGpxB} zHGkf5HA2qKMADVH$PJ&5vefNps}CZ@oG8j!Q_Nb)>k~0gy~~=Q$YAUsMcV*g$@$Lh zI`NNoG@LgI-oW8hRW!tQ^}f-nzkq15v+0*a5XoF=2KSn zd>-#}ZV_Fs4qe&_Ppw-LA1=_=>wDFz75n`ZO;2aF#oj%>Sa7Gh)IoA~D)q8G-qA zSpSp}SSReweKH2{#P*bZ-kw_OtdIbGZ!DR_NXVrO#{-uYtt;1Ib51Z|?JaHo0 z*~K}>#^&T>J39aZLH)iPQm?kKw?C!wG}~IywyI-ua5yFEmXFJ}lbtd;#^=j(sop_% zF1twNd33&Z4GyVOu9H)+rPpISb;?QxChc@}c6KLlcfT>>ZTnfUG-0<;F^iSqTES^@eSQuHfOp0XNs*_%j3M@rXRgEXr@e!WNR z<{&V0#0dMRStUMs#IWVnq*c;+ZJU$#uyIB;p3%l`7+&E+CHCQDKD^Bde(EF)khdS* z=g+46-K@|j6g3;WJp|aKoOOwtCR`pmm93&Z)PSOj`e4Xv>X;$U`${1zAGD^Bxt`DA zdJXQ{`D|+Y#gla0>)nT2?S{C?*2cC)QoE}6!q?Nio`m*IxgHrWU~sF;1S9qO7;7=X zowU2*Y(4P2a$z|?FP z7A%}S0cZ`xZvy(wW9&-VpuZG`n^$4!vN?F?o!{d(za~LIHh=bC5$dxFg{gbc(iA0t zZfi}aGF@V$c~Jv4hBVJMREjzdvg4IgaTvJqRhY=WVoDmlBHDmRPq)a-5BlyNJ4Sv zh)Onjt~^J(u6jP3p`p%rTk80ln{nmhZsaE&KvBvelx3Qtw#W``4Plb4j^mzRb8!%; z*~P(-9w0yu%IYf0#lg#9^|uG1kpNwnxdPSc%SB1&$1Fy)?|g*&Z9zncBSNp*!2kRz zgm}(Gav&-8#AWC%U4#Cr^|;Y(LyD7CEw9{Mja%2tW%d}a+T7ihgxboBD9CX~a-u!; z3=Uw{Eaj&ZIE(4FbvG~DM<4zLPN%k@Jl_?~Rp-!F?Mf;xPLl83BX!QHEm^7Gy~T?Q zR128d7}z|J_)rH}hAta}R!h*MtdbPIdY{~w@IEK`;jC=Dt-+g3xm7sNv3d>V=T<&% zwwDBK&KoW9(qx=pn#42G1WA z;`_%XxZZgZy_M@RP`^(m|BQCi|0GWzm1)am)%V=QeTa`a2mdQhIDgIxmdE#D@#48Z zQqVtV8laagnT3t(mr9D!g^Ok@K=GSD?VyKQQ)jo+>_9r0&LBu!uTh) z6UnmUozan}hxVN1uL@#}(uqAk1?XRqy#=)H@gHW*ne(4E8E&;)vTS+P!i5XI=co*} zg$w6PUR*BKzOqG&=KshR>qO&Gd|PZ#0+NL%`A}CZtQpQ@kf7!tJ7iBR79Y&l^Pa$-`7Tp zahu@JYbJ7j;RpAqK_GZCh#%>a-19asF2G6SIeEOwoW_t=ikaURFZ<64dbAZocmY#h z@{9Ksuob}70;imPjbDS|uOdj)1eO*lpOLColWmj>ga;DEN6l)Qqd$0GH;^cR7D#I< zRzX$)SSegprzvROSFq-~NvLaeysgwQPjpf0n9t#3Y*Rt6z1Cy{p|+`{_rxmt)pK5L zy_DWBe})!3xtoTY{TFffS`;-HuxHc?Fg(or8DZ{lf&Hmn@orv}7-|G*WM{D+j&ZIq2hs zC3^Fy@y|h5XEu7eb7i}|Eki)v(wr`;ngF78g3BU98cNbTOv+D_L z+^B~I^Jhv3A%__5-nJGNhql3Zr#?37FTrwB`HL3J#1=z+T=H}vu zjo<($G*m^Pu__YHbuqFs3a^&J`8L#`AcxVVNoXCHL%qB}EGuUAJLh9`fFYfWVcJ%{ zXgW5Kfx$ky347^z-HGUI@<&f=5Y^GK!F;Mu#pqBbL9v+BGRGd*>a0P+y?9WK;mA3G z8Ehkixu`8Xgq-N5NVvKX!I$R1&hl$~JN-Qc=qW&c6Vx2V;pSwD>M{m2H7hz2{icuWCFSZfYJ6pUf!#pV0CS_(-;;~#$~a^b_+n$daps&YRwEa?U;nJaGpYRGecG0~_jJc}+f@Gn9bdD0KDKYw!x7W1 zIIwRGwvv+GvRRMR>KX#&N+bm>L1o$sbT@inY?vGBQpw{oN)dT1Anwyq}#>tV(6`LI1{f^)7% z;cR;d*2nhZu*o(YG}(cZCrt^^&T7(0GG%9HFoQlo59 zNJ6G0cHyhkkhg&T#fSANJA>^zch#>qFt~B>(4o`oH*EN7#mbf6E?T^J_Wb$t=N+*y zvkMPBcawdympzu@g2OlPw4aXicGJY%Pkx1cMqk2U?Kjx4<~u59VDtJ}*uHrV%#6Q< zhxOO+beIi)uLFn-bwhg61>~fA6L>EnE9Ih;*=b}{=B9h0FxwZUc~?+g5P+(ZtEjIC z)d4!3{tO=2y>kPuT(*^LcK(;`q){+Cv>nX^)Pfv;96DeG?@PAm?aUN+K}Ve@YO*$? zCTBb93e8ZNcMK`9=5TX802`Y<@HF3omNoOywssNP*DXdXmCbACqDg-~N_MY-lOnN?GoetJ#90H*}u&`Z}D?8>|gLqPL5>ZIB?qMT-$7tKZN1T09HO|rQE0NOC4=X zer{#lcyOK+?hWvQ!Ouud^A!1Kj~Ld}L%CBW->+n@qwj@(^Ux3vQlcwhVyuV#J7-|8 z(KMLsSpwrd>m~CYgLuzQeH_}ahl9Ik;K=@&IODn#N6d`i<#_^;K}T@;^io`MSp+Y) zMF{s^it?1@Xv|xM!Pc|%9rAxb{l=`~`Fmzy^Y6>B9-{A`8{58~d~~$)Z^|x_Joyck z-#VStHHYeP1V|#Ps0Wal$qRBErT4uOCi^yH@9y=mvfK@O>wTo4_u%BwU9d1Uq6WkW zmPhx%;nYF6lVEaV(d29n4>l4{r*+$YUN(pbaz)ftON3wELS~2<|E)+4F+xh{b}}QR zlBI=jM`pwhWJc~lcI0LhL@h#b%)(d6!G=FKNca}e+QZq^{XbgS*v>RHKXPi?^y&XX zRs6;L8`jU>+NF@kUIzJpw(KQA_|X%JCBz7w7s-SP9iv6$gELl8H)Ot}~AYvoWk|J4yh|tp*=w=0- zhmQIS^v7R;lEfvFEGWir9;}ai3q8Gsq99D?e2t#}@=xg2<$~r_RXAyX3t7gW{|JMH z-@tI=8o1c3LsRZ*SuuOK-5$4ZaQ@$NL`7b}fde~HnD341Qdi_?@jio^>+(rud3ia&)6*6gbawHgJ-ja267Yp9=!~-4IB2HP9U)!DkQ_dKO_J=MWxx9uW~2 z5UI0>a8I$=7%%GKWQdPjsb&H+!I{@g6kj*PnvU@}0590esa_`mt*K;I)V$syXT;Og zGaD;vO<^nbEcNny-X}%R;d$a`=Li-8_lpi{1UT15EX;Sp^XzdHQiEL>uZPm))v`wB6<>Q4<_4g(<~%A=^-z(r6xHd= z(3H0lt%a*)fr7DaPx_rJ#f>JeG-{A#$t-TDbq%sMo-o;4DpJ3{Bw^BAB8AjQ(|@2R zSA5#t^jjy!dr^;95BlqtVcnV~r0N$zZ`FbcTfLHO#eA$Y`njk_PK8L z%6V8z_m8W?LF&<-K|<&OL|mMS$cr-&e|Z+tuFjG5L)kLPcm{A@#C+sO&L=o8AO*bu z#j%Ut0{Y+a_zz_Nk&M3(4bZ(gO6$rTE21CPj$V{<8QL-MXg(V30nGc5()A8Lm ze|a6q;?~fa?5i+4t3zKQBXl8(6PBZ?%#v=jd|AKl-d)wjo^)}rdqb^%Cj)ytz;~lc z{KxFd;O;MHNn=-rC}JK|>ZV4DK+I79JgC&toFNk+8X8j2)Rcy1s%xlEhUa-(SuFMB z$wN4G$_#e4=CHRvLZumOPaP&ZBnzzC*_qR}?zr6%F|}Nta*PWnD;6Uh?LMGehRS0LJoHd4dB z9%H?iF-Es`?aTl@wpL-hj?$imWdF+A5 z9e8X)xwq7RfuYU+2NjW1MZFiz-KBi!3~*jhfO|gO9T~{axr&q|FT_QkM|7A6!h>B9 z66k~=e+LBm+R4CtAlX$v+P-{BnXe7mDfs(Xi-q{x(SQCTO7i`YlW2kDfO%wdBpfy? zbRMz^$~oc6@}_{fD2D#$u?tZW_ZHCqo(F#c4Cw!r?4Qa0m5deiyJqHx%+gc*Z)ByO zM{?wTB!p~5V(3;Rg>6Gh_*SF@>mfO42~x2T8fs!O*prDto;}zVkLsLV0%(qV4)dCgV+TLOl7*j;`kn=| z*K)DSH|C8?d}yww1yKzOPmRneb2Y{$Kut&pvq%r_8^m_qGBRY5Hib zv{rz=si1sU{LM;1bHaC4Q_9b*{FCE4II};QT^ei*X71*;>q4}&k^VXY2dA;Ds*INr zf6a=EBL$=fOsET*6)gM31;NNmzku|Z<46wQhvcxmv~7WmM0cbmdLkwMJhD=~q*s%f za!HKSa2DnIBQN7JvQoTs<}EHQ?lF~7FQY8m5#<>cC`~g(WsV)%>w_^in1lPbxhGIY zaCQ|~KfGHFPDmw5sl?q-Pusk>E!T1QU!#DU6*a4CQP>Q0R>JHCA$$2ft7xUB6@Ya< zXn`}kL#Fto!N<8?r?4dt37^XV=aNkul;k=Fc%LkEJJ!5Qa+};9zJ#X_RRoNRgdz1i z7D?dUg5JuFxIGdmE|Vt@s8=)^ilI6~dfqy*!J2itnUVUqGwdV2aGp?f`(}f_2(i|6*W;>&px^pEtuJptC%4!}JWR)fU1mys-VAPaHqK*_Y zgSfUr0lBf76Bk8F$#9mXtQukj(!8yvbgOj+JDTIEwRgq(b<1J0Zwq$r*dVSACwnt& z-?|<~q@Eq@OwrYrB5}~{gYG9l*XHjMV3{qf}}PhKW~RtmaMZUP4MR(kD{qAS!Ggwvlsgw&Hi5))i; z{5Yxo{adhm=Xz|}ypkG}71*_79qq4^DZiTx7UQ5X&ph0Yx-wUEHhR(f4ac=nQs+7! zG{gBeDP>OdF6xM0Q&bV%Y|7X-N{X4fvFu-FcLu|m2aB4Tlv1wI#mbhK#h|P#8pTBs zk}rfOHgMvd^z=Yj+Z@KO-G+#Z^F~5~H@sZ8!*cTnIJ)8Yuvq^ao&63L2JgXQ5n+R>9;t(k!;f+aBBNU zh`6u~<3m}vPM@1s&%Wq+3OBEn2&5m~tERF_wx2wxm9-PuG+?vOSb)td!idV&+#w8X z&d^8TWp&Nl0%Zm-1Domu$Zz_nd7ITZALsM=xOSeVxOK4pp&w80M&WwPHjFkH;NiG0 zH44r2ep(2`JlUrK53U6hh&N-f)({V_hluOs<+DaSydHtk#;q8x)5l2tdV2n(-5}IT^`;;M_oqAEmj0&?aqk{IUiUZ|1 z-@CQNZYW9FL1u(fvhuX;s7T*IJy$YaS(UjHHQBqwYDq9r`6?sY^yiW#y#@3e4-L@& zAF}^U_Fu_~bXd!F<-LGl?Us3zp|1VNLeg|8ZPsc8!WpK4wj;hq< z3ec^#q*O}e#t6RZ0V5*=R8_>|1_6|pGa4E!mX%hxyS{(lR_xr)14rwq0a=S3M(eO` ziypQb>R~%=TOHp+jh-JVnsib(JaW&zMe3>&kTt)vK$>99t3tEiS?ji{r0>N9=KP6) zzfLlCXEYL+RkED~l$NTMIanF1WILhAE&|BlKR`#o^=Yf^%o~!ED$) zxMZH)OT?|NL%7ktN9<+?+g{x2+>0l-LZxxx=oOy5$xxRt#^yLrU*4dIM z(B&VN6|n%AOv^^c6Ha z71(H?hvY;*>cVmCGyMTM+F&3BO~w0Bm9_#E1lS^ibb9DQT=AHRvv$*Q*7_R+pD{-G zg_C3_5P8W8!ERgOdvY3ltiFVo<8(w^nvG2A!qsQ3KwF_6M%wL3!IVju84q~v*s)36 z2NI{uF|<^&vgN^>! z0y#OMl30gJR?LZszKDqQM!;21$=R^qWINWbTM0KeGn}-TgMI7&r~~O#5KjX6&3y&z z*C9Mv$3TDmm}WZ(&~`ijh}W1GW#m5tNZeK6O9Rkb!+m)oG zscV0S6?K(T(gZ8b1@hu4XX7IUO+b^`jxz8^u$58)Sxtb^fUE(SONO)N!eAJ4od#qs z*$B!Qr)ylNa*S+9LG(qFlxiUY71u2jWazc|*vscN1X^w|`1g`-ek3t4hOANWEkZSDi~UX>I?{M?EvZvp)i4_49tPqP0+#*k(u{m(8g_B-oql5cdir3;X|+f(VsOF>Hm z!#S01B$acyn;^|I{A3adZ8L~DUj}b004ItH?j@iLfOT~YWQM$ent;s5CIL-9?rRfK z($UkAirA=g@NhpSik@?9FyMT>?a3TaSCc@hAdl*EWl&^fAXQebsLfg{`4y@%^iZC< z8hJ6xkr7U?4qt)dymLB$UL|OTATP}tX`w5T7P1Ig5lc`MPwF{+HJbC+p`&C2MmwDd z#^vG<%t#A>we?|ib!3W ze>p!x5K>bEBo;O~`HC!;6hVqA;OZG!4f^~A2khLv87o&U!O7zrU~cjSjP?KUBbaKi z*1$W}H2D4;h_z!{Dcf_D*=+xV3^L^<9)z0{$Hkk902ra)aD2FcfRayL^a4_V#ke(I zf}7V=$*P)NADS!VDJjY43~W-<&z}(d1Y(>=WYR}1VSA)t#Y80&m_<>)31o&XCvIX8 zGnjdMoQ&bjC4-g+4Y~eJsa_1peF@uuUHO@jjocH3*to=Rrz(e++7BXk@xQ zN4fClp>0;z?5h{0O~z>fc(B&h*%GzY@dyfZhspl!h>AE*^%f{841=?i1#GMjqM{@m z4z`C88R~%($Bc38$ZlLXdxCnoqb4{pQ7b0^^IWrLhFZyDg{c?epmXd(zk&AcRl_C z+5e4i4Nn;X(^^mSzsIC;7GbW+f1Vtrj1GHZ`#@2OQx)NDRhy$oG8 zrGV86Cv2>Y2D%7LbS(zFrjQk=>Bpn(K7z2Or1^TV@|-O$;ftfSryE!ECwsBl1Ig%etvB1l>A$UAlKsBEn9 zMNP3CYKm;oSZ0T|8Ygr&xMHB~G{$<)45_h{N3*c?5|P>Vh`o z#rNG3{>5ES_6c&ga+Dx5Nbhr4Vu}k0*bHj^P77-POzk+OiJ=2D0?F&#!K88 zVd3Wyc+~@!eO++jqCMPCTVcz#^;oiW0n86A#-Y8RV(+@&6GRn|C!svmUI(#)?xa$l z+@C!6r;Gt@z3umi^O=Rzu+6Zy-i=dM`%zO7iS}ld*PH)m{F}4dQ?o&H1==?_e>SOW zPS1LmzAIMMkMHvYni?u=m7n?v16$1!WEaRwo)P-E3@@IP(RKwvt&*&ofX(4}tXLU_ zthCt}uDs9CWJq75ZO+C=^{kp-Hq*9F=?a)fhXDb+R%Bs zux-m)oI8CCp;w*7b;oN$I@ui}u!U`C56X1Eyf6b*M?LY&r!Nj#)tF8B&}zE zwjAf_)vRDS7Y09%T@5_#n#0~?pNwOahkEH8s#Ct=Y?Xmdm&2Kp?6aw9+gSo;u9v(T z^jdtgGME|0e6#XR%iGsR3dITVMxI;=3#Y=TjpU28MPvxfz8(|-T761RuW z(K&V)Xt6Ji(!1 z=Mfxoj^KP+!TFK{JkFkiBPp$oo7ZCDqIo!EvIr)-KEW=%-|0X+31n?sgYKKA0a|Up zdF=JNiG2d}$t}M_xaW6>4>W+y@$J-&-h+Z1UX(Q!ZH?3$qn;ZN{7y9R^k3lLo_}W^ zOk_39pk@~cFLJ;WOV|ypz4R?ZLE`eRC>=%#X z@O0b>j|R=;oM$)B5I8I4n7W2?fhgcI*tw3k+4$HsGHxgc#uDnsjRXUnpF_u`o)y2& zhfbk=*tf3-PK4`4#%x?v=1)=p?VdK0_uInTVZ#~lzJ*hV7zw=PPo>Ca6aN^kBc$VvL8+PYh=B-`dmG9*B-@n`u=zjaHuB? zjrj(sO6N4A%Vkw>UNBYz^hl34+Di=3Qn&^UxvRmeM0YiNVq~No0|SLJbF7Wv%)V!B zX(WboSy?RdNj+y|XmIwCl{SKc&mbVsLso$Hx$FW@x_KGSE^a4bYj1(|26|Yqa4rrV zT!no*KgEvKza^0V6r6t=wy#0=js3r84Cv#AzeCX3?-1?3jk?P_NR90jUub1%1VJGl zEe-K#ZA=h|aHHA7M!ylei+FY;M}M&Ur%-faRlf&1};8eH!= zN57X^O`VhdbJWC*&cg)WYWm&!aqoJhtdc%Zy8+i*HsMzLHaxxUPatH!@-QCW48T~^ zX547qh`XJe@St}mzJCx&#|hAM{MoGwRBwpeZ5wgFYZD$18sil~f6`T=eAf!jN_9`} zGn{X#Z3Z(bb$(9_X$5G0E}zG0oBilIg)P8lQ}z7+JmX=7;2;mlox&8y%$c=v)RV ztKAXW7Z(R#oBo`fd`66}%TspyNjbBdfy>_RY;-Y{rvSRUo&Hn==s`}p#P5Ty$%=xf zT5~wljo}EokqyyOv<5{fn~@X09c`tCxO+WWa!BxUQ{B~jkQ}-Mm(Q(1T+l`|mzh$7 zK@Hn@CG`lxP?e>Rl+a}e@i9PLz-ly>S<hS+ zbyru8O6IPcaKh@D6S#Ad9A0H3D=UcL>?=7V!oodqHRufdIKKF@GcI{M;@o*#xSu`= zXID$uQ&-r^#uV$;ufqHVb8y(y5c_sb!_L*eQvjWSv<7Ge?5XaHsivMYx&2f2+PMVi zqnmzJV3=Uy0sM%sIQ8Yh#&?v8>_jd`c(R@lv|5e%jU+K zVa*NpIQx>`3zg`n^hJeaXfeFNFE& zBO!Dv+KRc+B?yoE;KhqhJbBWNj;6E7h}nvQBqM2 zNycur%JOJ5H6%;sJD&OJS)cN-bW4f zMz|+ZL-%vJeAm2groW#v5@Ii+gVgXf5-klIQen3s#);#o~&q^LHZ_tg*FKCUN1?zq5}+2m%S1l6?^GF znS&eGtC5rGMqPhH>B^^t>7g-i4X*WhQqQKAdM-r-HyfNgeE>ce%u$}Y3f&b3xI5-g zaPGj+P%&a7E#P_128rP&qR=1q@4-s}G{co)thqYac$*>3aMrmnWDt_iWyQ`g=6cQj z!RIruH9+f1hVulVsgwwjR`7CW9H(z@Yle!_NCGT}P+Cb(lYR0G=H`Y}`d*6gC4+h??>!x*zi;;^x-15-Lf& zQR8@>8%s9&-Wkl-$i@e=r5x?2{lWaVfd0SY5gHbtKR#AM;;Kk+3xb}H*NaqHCEaxSv;$21~o%`Vqa6-WV}7OU!nHJWkNqb z8UM)`&J!*T+UIT@!(4z)P?Z#;6N))c!rnMXg-X|$EymlNr=W|JSU16$)wF_lmMCmi z-(%c}kn#K1GRR#U2uDNyMr6k<#d-H_usdaj_^Wzosq+`Wjt-@uHs1(-=N3>G&=}4R z2ap_YgpRfp3=XRN(U~!;NnJ0KDbya08<84qOz=%be}6HWYtA4hU@_bs*W#4zQJl72 zjEp2JacOWE9Z%2J0L^jE1qBh}+Q`lckwHOOn~vbj?hIb;$nCT>*-5y%ozTJg2*KG5 z$4(rEnZjc`L+(gkFv`H-5vEXHmR4pA&2SeH{bngFRYZkC!hy5g+G`!-sa!`*KBIPOv0;;%K9avRIt5F_X{fV0Q$K^(iPTj=~8`6S%op z;;4l&{Cu1U&IJexaKkCbe`_wb!3MYLdwT5_9^P zwjU~c`ltm@=+DWJet54QkEtb=Y-I##$tz6YzIU5|O{$vRAGdGv%s36$^aHZuzE1nJ zEsC4Axg}>P^KrG$(|~!uLI?O#ab>Vw=PA$ZXMWA+%u`x9Sqx`mQ{iZmFouki2gv}N zE^$yd-BemKp)LY6M@CElnv^ytq0usl-JtHCOdKH_=?g=3_68&bErh$1Ax@q=h@cD0 zP*ZjpeSJmr+ysA&R3y20G zF5XAn8k}D8EWz2qnf=UkBht;t1A?{$XX{g@IBsy z8)pzeb>N+)0a%#^*Qs#c&gV>=H}$v<#8XPmWS;NNYt4}6Nk44;y*Vhw$gLs(b<`Y@Gxr}vsh2?GDXOxrO1z4hRz08 znM&W#n1=8W3pm;v4@sJ>ApYQ`MErsxoVt6DT4{vLpc!$vNkolVmW15p%>WV#b^;F(AQ& zqKHa-{`Xz`?85<%mR(`ag|En6=S1{yH6h5r~&l5 zrj;v~Dgb?6^oF!Yt-Q$jSpjLz+xh@n$_0oC(z3H=&@!YM#uAVv zVE3LYfK0~^?(*z8KIgRs_}*b^eld`F#D?UUd7*s{XGrm8DaOp<3wb3k2JqF(m15)r zPlY~zejCo8+p1VZi1&QkBF;Hx$M^ZO?56AZchc|YI3|w<;q9YXH?J&3)n+p+&7X|; zXe$J>yGWge1G}^7cUO{AS&gc#w#ZJLME4vK7VLyYdFD8LXaz1_+=&xMi?FGj0G*+W zurPPTg`1+h)E-q;%f;HhhxR3s`_@8qm_7mnJrLwM5z7{Oqxw*VSm*cfkqXjUI$uk! zc_o3l3_B{9itUcd%Ck{Gl_w)B3dt#9!JD9L zV5EyllgGouYc9N~k}{wrkTQ5F?*nNCWMwG#xhFwe9hgG4+BvP>J74%wi!d81-wJ)WS#p$nkM30ypbwzA=}`BnV;eMpe%G{e)iTou_fFkwe{qSx%rljE<`N(C zR{cDKiE_HmZkpjN=W?h+|SyETUkuxYs^7Ubw6F?KdNWN&h0GqGcHx)@1uT7&8A5KF4K=X~#BR;Iw#8w=e0?ND znIbU2od7)*d0DR5vSlH5>{udp_u!nTYxCq2G1i%yv!$g;NKFetVsa4T$nnI)`VpMH z5gP7^kT4d5*$sXH?3A5_ynLLXZ>WO_lg7c-!vXH(j^@o8M*vkoR~5vnFz$1WV9Ov^ z+*5^gfAxVi0XoobIEr!tk)IU^CxSCCWM7aIjMBmgv4R?}s>Um=m6NM3Uy_JrixRN7 zG!BawCScj(B%zhd(+L=bsN7zH%5A0Cw`VcE1lJIh>4kP^C93Jgw{2?){a$Cpgv}(E z?1GGV6Ra%O#g>(`abVvfR2^7_-1&Y8^0yRC{h|y5tXph|gS%tIcVzG06(}k8MP%4q zYU0l$fKNxoA|o8$pF*vgtzsfjcBYGP-)V7n&4Bl=1 z<%?^gL%Fl_3W1iLuk4WJxU-xyh$SFPl0zCYs2R>Y-deuS@#rgJZEaqPAUw>AS_auj zPm2&?jf)p5v9L51i3!12y(&+eXPtu7 zq+k)|ICEk>LW5kfcjpqcl51utGn`u$fEK_eNyn;=`j`UJ?52+rpf~O!#ApEhE@}Px z@?Sk_K6kgP*Zy!T3A>6RRypwfI-f{mK-&&p?gl`3~L6p1nyG; z*6gY|M$M8OHl1@gM0qYR7<5tz>WBAhM6+xwfok2_0<2$~k9E|9J3!5_(ilgrz_v6${Hp{Do(Y+aX$it-e!EX&5~ zvK+DD!1hfGr2AV+u(^Vq;qo-BT$Y1X%QCQTMFuugvvbFm#q@i4yCC}A<>}-kbFgAb zGS;qO*H}u;{!(n)xIp9^D~bqY3CPQiLQX~m(x?&z1UMr!)E!|234>f?Pxn@Vq(4U6!6UV}ZDxz^$^VQ1n_X{|UtWtYG@T1tUKv1O>TaD9jB9QJHLBg!QZEQ(0wEdDHzB zDcD5!D>oNn*Y>5@N@cQcRW{wrK?Qv$Hm*vc??^g!(RXG4uI1RbvmAS=rE_TSa-2F` zL0X5?N9lWbXqAWow>@L$dxt=K6K!pm@a)-Tba(S`yIQfiL2D}+q)r*iEJa9zz}((W zty-#ky;IqxY3)t)V%S9gx6%?`k9$6ulbz(Ouj2mwlUPsRrN#8U-dVX!Y^hfJ!+sIw zcti&3%Ed}-SX&5QABIPMEGkVA=Umq~tg(UW-W4)C&!3(~TgypmHS;1?(wOsSk88v= z>E0;;Zl0q5jE^Z7Zo9dr`%KLije~yIwEw{R|M&6Zi+9mY1y4;hY4ALWAl*Z7=IgvT zj1t(CcToOO)So6O6Qm#TV)b-PVlcCK8uYodJK*SOE!GzZq9!^o2(x$*Ri;fPBF?sx-u@iY z;BWYBds*Lf{|Ziq%x1*Q_muy~8Zn*qD>E z@DmCO^dwNkQYEI!zJbK~PnGJ=%g3B6v`uKiYqfQ~EP6qZc)z%eq(H<)c#_-pMtrmn zX4}q$mzO<(*oib3KGdA|_91WyC_4!tyL(C?X1TiCWBLqjj2k~1&aSiJ;%1LIW}}rb z?E_=sl1Va{)dHH;3*r87?jr)UpVbfovNzI`ykKjk2Xm8Yh>LPVLaZl};=PngN%W?s zxDUbDlbYgghzN5wgg+~rT03?&rzMW z@rzJR8N5kS8LGc0YsY$eiEkvR)Ax1nwuP9V5k@UAPu!@jBCy^jIA6q?Rk`$?PAA7r zPV~t+Y^0yzb+hl(9a1=D1^_cb%)T+Z>l>mo@a*Z$*t@$N9UTmL*-1+?Av-%6@Ye|9 zJf>Q9=(p(lO@jJ0%K5XkVvTFwj*NGgq1JLI8KWl;?jE~)t9Jj*D;IZOxpV8_t)}`z z_oy}e>?&4n4v3~O!UL6@3ToxMQ zUlth|v??hnYC};``kq~t_u?)fUmDBIkuQyu>P1Bw(734)ZLS>QRQX5 zTB&<0eJ`A)oHyc(4R?dTryW8A<|3S&GVgdX$I%QfF8mU+g{zw#NzMttu6CG5*XN1c z4s)GtFm3u2j2Sx$bLjaw&9jB0>GukV5^QBSs~n3?LDhS*6maHT4s-B%|6C~ow72D8 zB*nTQK58B;&2%u+Uk(mvs~8~%zf3rEM8TAD2wt`Iq$D^%gJRgPQv=- z83gM>a_O03y^AZCwi76?;qjy6A_U`LZ;68kR^a*%yWr>R3>#}x5pwJ7yhNtu1R5F+ z;aTfBaenU1ChXr+MlSpuTF9lg5)gT1#TPFa*mAf;ifv2hEcsXtozxPSSqn(rOIN5JhS*b<}((7eQI zA3&c~xN2SlTiQa5b9U8jEvLKBo!X{x(C?a*4w|9N1LwumQ$CiQGw1B0rBDa&>voku zeT4ztL(aH)-P(owlagY}f`bE!{rr52eSN)(eSEx1e0)3?czb&+lH|E0Ai!sNQc~oW z?c0`Jtgk!N#&G6YVC6nR>9Y zHX|20PsrPQ9yO=`3_$;6aRq)G2Q9ff&Ux45umC4GJD9*@-Yocf*ug+=614yf;oxA3 zIZhVzOe`t4gwxzv1Y?5QTq^>xBtCXOn8_b0aOWH1%OpR ztQ@(~=Xx)ERh{!|K}~@6G#@CYc!vc!z}QF&`nnSl=sO!h{?tP9vxlFz9ellP;Y0HB zuz~YjbJ*D$(@WX_78d$2nyG{7x>KO5t0lHT;~n9h<`AISLH7qT!MN|W{ynx(1Owl*7)p)R<5aT7uE0>SsNn7QZgJ68;G+r4uUf&%8j zb)KDAE9T7U4Va%DiR_FB6cxmyzHUGE?_Gu!^emq7iYr}^ROyW6%b*_)9TxhNvcCo43_D~*&I8tk1M7VMK47UGi-5$YR9 zicW|PNhmE!EjU`e_8>XxHU@D!y&MFT3D%OMmd*vR`I-!D-fZ~EneKC^w`&0XuIcve z)Bo`J@s+z$&ohe)m3x?_DX3yFJs&H9P0gg2SG#Z4R^M8@D0g#6NMM1#zi*zuzfXa$ zpLd}Opi3n$v%2EeoSu(r@$a{ZAT}PpGz4w^qVfGz4=Gg>gTNu*c zK7HCa_;^^s&&vkhl)KHdz`VKAMh8xgCgdayVQQ)iBXZ3KhSQ)sV+v->&?0El|8cej zLE8xKuJ%%hqYsSx>Qx~3m4Ne40<=0w<;%xw%QI145<`kZg#dIGB0}a7pf^(8I!~>} zYD9&5P^&E*iE;iY%#TG@Mi@eZT!mBS5h>fY6l3$oB6xW^ijGj;YmmWws%E1Y!@O@# zIks(GLI%Z`oHnlo!u6Ji^2s5N-t(@m+U~}N<2RQq%32o{?w1!5k_cLI&a|o z*`0UN)8khJ1p4Rr2l(bPp#A)P3D7=8etzD49JH4N=_Q_CZc7N#%RD_@m-+a3EYHhJ z-g~#{c>Ci=XYuIK8O3s&qz9)2pl8i8!O9i+xOVLTu3Xti+NA_EZ$iordG>5e#K#AT zFKJS82)1rpjHS!61e|rIPeoQv3@WIi&ULng*=q2pq=>&T!cQ1M=GoW7=+K{9k%(9e#mZh#t zNK*N!zt^kY&um$fhYjVaSjU}|D>AWteU1d^3md2|(f9q~K}1J*V)gP2;hcTF=U~ms zED@*X#f$drT7sOc2$U2hh;=oN99ktt|L}f~yxcAimAiej3YRYKK}5I@?$jL-byOO{ zC)Zt8Bh}eEJ@@XOs>{ueFC!r51P6E!oINub&;)9B&?#ZT-bti{@DKuYsBcVUs9#h> zm|sL>xPMqwxPM4&R8Yv0(##d-Pi=k7g9RAO-Mk|^wW@nME~}h#3;T*V?|ONu`_lPc z8bH5mx?OkXA6iSPaG}a$Go_A(-om~qHtF2GqwGmkWXP((K>w_O0KaU~d;)Z? zpPx@2!MTtDO-@?jpgk7~NV9_`NK-Ccw1p)JR~sRzgL5McR9>) z0yQ;TL=3uu+~e)rhjHUZHLhOWgSBf5;K;GZRe6Yt@)dy2%Zn!m?1F^EV6ls|3pp!G zg1foJOcBN?E=_}@lMVC@XCNaxRzTW-06k}p4HDvbAsB!9c>?siI_UnQiYn!jR4X%I zS3OtND}W}@EMJg-1@psELXa-VB0%d+go&}XfV8EBo(Kc5tgH-SZ8H-#w#Gu%wkGrp zjA3DEgb5SJVEBk31Z#dSbl+fz3Pe@ZAJD3z`>FtzBtcvLUGjAq*qqNZ`WoJD7H}gV zPtzWaiQ`AW!Ono(upw-%3Cb3_FgMkKnaMO5&zuSa19r^hv|mkK%$jRP8S#K-=R`)pD#~n@50-#L469 z=sW9+x?2Yc(7Obn>uw(s^;4>+sv(X#w6t7&uxMfCS^{%+aG*yPi2*Gfv;=7H6mri= z5}f^FBg1^7qQm_oqrwBiq9X!Aqay+XVu0vXcE#xu19&=}Gd<}(P;daxw- z$#GlmRFg#Rnq*;VfbkPXW7zN^^x`t0b3Iti7$D#&fmzN;3J|{nXZgCS#5KjwzH%&| z|1;+5e*#x012{PtValYD7&mq(Y-Z__W1ay^^Xc^em@581GmW%hsDQJM&IC*)Fl%X# z!{jMr$wg0wi?fYb=h)VU0qrO`Xa=;}ksJhJ8PM{v64=snmY#L5la`

(u{6`#No9 zK$j(B?a~y5gU&{H&|F+RwF*5ikE8YB0aUC=7hB2g-MIi8D(2(%^&Mgt?pw8$sM@y_ zx!I8@UzU#YrDmQVggT`JhHB*y^XgWyCOMgf^v5|uU*X!njJMkyZy4pLH{Mvo%-|t(DJ1A zuG~E8>EUJ(i;o%9((I?(H;*7AG5lU&fNyDFP(UU*=S%`LLwY`kIS9^qloOzR7}6Z- zDDovplS;`=lam&1dNGGPSPW_}FW0id!nFN$bw{4xyIX_1aXAK6I!;Z1J>h`w|h_;DzfqZ&`@-8%jmodFASSEGf&u!o``$ z$xA?9VKNFzQVG%tBE;eBJR3=gp@MOTW3Ro~~ zBnKUa()kf0%)ucJ?rbw9ut|U>2TGD4txqio1BDDpMgq#?#*f0#VS`|1rU#RmqhUGi z4@!qCOLoIb$zWDWabF4G{*v4^-0Xjl~p#^Q6gRM3}>aT1W1#4zRPcfVZcU!a)~HfK~(P zzEFOh6wmrc;LPH3Rd>C=wyen|_neFh0`w+w&^tK9K@R%j>D2%M`o)t&IJ|!`_EeS- zpi6PAx*YYlcHwzj4Z1sdXYT$0?-6zl4l0F=X8Q|3OVPb$S}Y7sBr%na?Ftg;xGbo zNJ30VKtfEYe_~vi56L4THq@Qu5f$QFoR=2ScE9ncG=QMz2MN^Oyr>foDByG6Yw=q5 z<%@eYfPU9hUw`o*o;h9fR$sZ5B498)7(fi>oMeCGXNICMClW>i&{GtE))A04H)BZ4PFkN_vMd9bnd@Qf zxRDq#bP#6FoC3ocU&C_he<*<33uqa#N-4q2*X3OPoT}7ZQ~umP!$IdaurdAuvrNZe z+?XL4IbtA82+I7DVKD2>mTyz#?T-jwz{K#=ZkKTVLMW8S~8i+6Y7eGxCBo7B;95r?ZQ zuyREn0h%YR@MIP#q#*;E`;4j%tUID`&+MGDf&)n8pvgIBa0em5IXN=aFCjYIKQ=Zp zD2l)w9v>4DloS^hkQ5*8o01UWm690ck(wCkO2;nA@!|6lW5WUh-REB0vtwCLN4qo@ zTN<9L7`NRc4c8@jcVE7=PcshsT~mGi1p;(!lkA|Sg z0Kf8iMK1r0@@IbmhiSjTEQ3#Asy_&$zaNOBK+fHA_Jr2VuHgHV?#rd z6T$;h6Qg|6lcT-TlVjX7Qe#~+Q)8VoQevFwnp0X*lyjJ`$L8#$uuksOms~TuXMRyg zj+)PVx_@9mYaH~urXK?|hd7QL+yFn9IS>5(d=>`<1*Qo|6QHGzLjP>aSvf*M0rP`` z{8gOjQEkMm74+8a)qQbPjb+-?9*4G~ctFG<{Zr(gZ4tWi1 zY%CBL7lf6o3J?+LNAQ`6MT^prmKF|c8#B0j%z>4)Dcsy0P*jov7jnx}r)gmpU2}1B z5TiM?r%pj&h$r%jk`;i~7ZX%Aty_roYf7+uSuWPBDCi5@pCYQbLMq2xndSTHDzn1Ig0!j0bOQ2pI;PxISIF3SI!2Efj=_V!#f<5L zFk{*$FjoMYq1qSFvLv{^3S9ntZ!Y~TpZDGu635atdjhoijE`Y7{cDUIJ^(|941g|y zS!dcXa5r=m9JEm>!|g{U|zdIa`@ZU=OQeS09~^JJ#=r%}!c&(;V{f_3>Dgl@-6^Ms4+TcFzqB z9Nsvl1T>F_Ha9nhy}cD|Z7mQ*PI$w{QZa(V+s9dK`IMR#A%@oR?jhXy$DM%bS<&Q} zlVMFiV?N6S*?9>lEa4Cb$DkR|?$}I~cpFtL**VD|eJd#dta^>t&*%lS;&&=O^JA_{ ztrQ?(*vMK(P%tOWg;TXh#))@rdsegjG zRxhAs@ww_X8N>|Q-sML70$RS`3+TS$&&;0s8<^;R4E?EJk$e6cg9m+$>C?tw8o6c$ z^F#vhB!V)#=1G$n&Lc5?JWGP}I65{ooQlQt0_Lgj8&(&J8J3$XIQ~q4CLs46$w3fi zy$Q~$QuplNL8=a&%YFxeS9B7dR5<9mO89!thJ&3c0{xue=k18RoN%#6=Ypa*#6^3F zMelhdWiNvAy45+@wy98TN5#vmwltqWL0%kEQ^L^pjKd%@AlX4nkbd~!WK(3gU!F3w z(d(Ww!h?NM$UP@UMFhmhMg>JD#D+#BC4>j1CPn&_Q}!VUdlHNp&hzGHCd|#vPIk!4 zNwLezPPUz&m1vtB6PoJfX!B&xjxw>9i1crAE_YJ$gtwan=mQ!+ziXqRK2#-1T*Mb853lxA(CkY3wfOBS0a6o2ANKkf2NH8fd zi$P7-@`5BligM*>vsNfmV(^H*oy9{w|uUy%aL^0BC#eW3hyfPPamn=3xMMhgbBi8jHR0j;A{ zUqF-CMH8s`eDvsH7&wR>^l<2Ee*&{9zwHBKp7G}-^h+Tbz!J3kb^0lCUa3y{y!5m3 zeIW(V`RDAk{|!ddKEjNt-(na6deFeH1e~?WJu{FQ#uG>r3Ct3lM<_HBXS4w?Xswj+3WrxF3aj?^LuNBxcM zXu4I2)`tht-g-=I(3+kcNaxjPzFP%9A19P8Ng;P#fS>>u+;6Hz`}6Z+t>*O9aJ+n> zaL)qJ5*+!svEk@Vf^c4lh&wCXbC6f2bQpJJVn7#Z#5X!~H}YThc0|4kOd zSsDo@#lUa(T)k4ghY+Iy^t+_m8)yH%x%v9do*v$Eo=0!UorIEuZhu*af~+{WIoQ?7 z4qA#s6QG0q1(@kt2Emz?85$a#MLA0WX#f1cK)(XXMT<}e16moA_Ve>vn3I#V?fUhD zFSuinLmap3j*79*`}VCCYi5*?^F4j05+`c5;mFYq*t>59e0}E$NXNtmh>0j>7Bi8V z6(hzx^D(>U;st52wYS9d8PgCE6M%ezHaln|W7$EM^o6V}8MOVcsa%&UU!QxbpP^j- z%ujO93Q1t0V@1yH(URP13R+XhF;8ST4<{J2Mi7vPW9-pa0qFTgLMDV26+d=nE&x(cM~&`?t3dpdGNZG!C7uM}#_rj$!+ze0Y1>W6g>T zEGIDgcshtpTDOyf4)k{x+f4DA7YmA$#QGh)h!W4<uI zsn+QU5h?Dot)47jlt~8eI&p&CvkYm@#SG*ga?qMi!go!Vuhjhg{rgw15TJV`DE9~S zZ4?rqUF@tL2KxIhB`~K-G3bB{0cZj>x#f&t0(59ta0UT7BP=YKKpn)Pj$DpK%YY6D zU>D7hmH@5Lf|8P~-M4Qa>0&^0c!Q2nTU(98M>ZfTIsmJwS$q1-4jezRm9DMB{sXJ9 za#fyKp^hh`I5=8~#p{txq6~ya_(0D<7p@+2$VDeh!|Y^0lk-wS zw!dW1D$lvnDWJ^vWc5EMNtIPn@40Ga{^?>s&oa}2rP)*=8PF1>r;1oKPxde}(k5}v z6F;;t^7|q9?mGgs-V{vN8G(r-|A^6_5)6ekD?|+7|gMI@8oq^ET9V-C+-M3#5oWIAE$sF2XKo27@D>QZ(#*P_=F-i>= z@pA_B($X{u#{B@@HwH}*Wfdc2DaXwq!iK^NtvS*65;7P;BYda-(04mt#&8OpB! zy6aH&h9p9a2GH-4PMiJ68c|a?zr*P#KGsAnjE`*B7l_yYRRO zZ!{c7eZvXV5u|V2JcMgMRN>;KeYkLOFHWD`iJFs=gFbL@4R-A=$JXsju#PHU#kyiK zf@9U1LX@w}Cs5~L(b6m|T#|*-#hIdWkX1+(JSQ(vIOt#kx!MqiqEe~7F5goHs}b2DBFR^rv9**l#fI^ABP0 z?R#*Z_>VZSavXZP!>G*TNQpSM&jug=n*z?1Gn^$rzlTr${XN(leT?U=rSw^9wqrSI z8Gg7F0dwu&W9l~_z-TbJ?oTB^j~nt4W*SToBR7T({YD9BcF>a*4q68ESOuU*zXE7& za?lDu_fs#N-{hQG3isUax&GHla?l*&2xA9bLoYLO(47S7=MVRzqoo?%&yJ$=DZ%;a z5p+E}hVHiGc=_ZAo<68T+oQwiY^y=%vlDpvl&(KLf$kS)(B01KVDL^yy!+7wg7YN- zWqAYzL%Or$a#vw~(h8+}4)jcy!yBS=Fd`r}j>8-A;h`x>QGsd6QU2-4(LQ|voyZ}M zIl0-%3P7ikgHE%J3-;aQZab^9a?=uYb;(2fIOl-{9Ok%9*Kf6N-n7_*5TgO~yQG8F zd;jiw?b$_LUH3Yr*z-e$I3~?{h`p6-;BIf-?d|Mzh8#1;ojJsj!GLDx%zzFF2~Gt84`q~c% zaq04YoKXREl>qc|Y_D8~E!&ogvCj~LRHWn;qKxd(NVTORS1n4)# zpjBoHGE`Ob{^ILY36;mM+*dSn#b*@9bp6NR{9|GVZDXkmYfBvg>RBX9a~=yVhd8E5 zfHovRlMD&a`UK>WBM0M~Z@D4^(e|EKr2EVYQW58sf6@v;Qa1!XQ}MCEahve$EuRc zS_ZTf;vhgjB|x`S5uB^g)q0qqd_*|t4uW*ov*V-_bbM5(i{RY#Tmp0lsr$t#biX7( zzdTQnzK9-n%cP#p%XBOOnwJOWW4?Fn=*F6eP~V*1i77q|=;Wwy|Ag46pxA_%kceag zG`VMvKTCj4i&Fx6ejh-m*sz1n&r0?Pad*DrJ9l=^$)j7T{29s&X9lx8608m#9k-q= zTA1xfh*1aV-;*?ee%o~QT8&kEN5gZ~PC_}aK zvx80x3kyvn2b~^HE}CP}JgOsvTy#*df36tOL69cLTtq5nNCyOXmn>eKySuLL=!>Q% zX$E0E!I{ocdxPOzg{#*NNDlf;C61rig2RWU5Xa74WnvcL=B-SeUhl#q%Rq@$oX75SvByabq-8;PY%)jH_@qDuD0>x#;#R?5%xUXv=hT&dMp z?l*}6ZEH0{0cgoV^Nc(>#9?C0u34Hg&CZ#nrzZjWv(G-kz=7Xj;Gl0X!4NQ&hG?hNm4ngxz6RR zQl|2EW7n1f#Du#Lpv%zlct2h~+K(5_`_bNVklob-#whw!515ZYUh z()lrR)JO4x#E|ZIR)dbVGw6IlkS6CWuZ1BND`GH<>DGMxGOxAXl$9B?h^KWcW)3RG zKKG8^NKS|dNllIx9fax15ge}qTEw8|r`n~*MPz%Vw8RHB|1BW0oX$65hg# z=htgPgS`w1FK+_$ha?T4e=JoW+O7NS*{%B$pk?RGorbJ?XnlGErMXFPwleSX_i#Hz zE;^fI&{BvaD4ifJ95gv+0ccieSa24>IY)NU3}_zFp@1~Uql=@WLds5@*naKay;D8C zfaXrZBT7JDxypdvgHxw>;Mnm^Vn07sKyTWz2l zZqVRwFznlpG4ab@Kv$^(8Zw~Ydj-%8XW2nN?*r&Eg@gXR05o?#j{lq;^v^K(%ioFE z^ALhGgL?efA(*N)NSqqVDZIgerd-YQ zd>g4Nx4!4Ezs?T&)S)u$*)ksu*EbQE_o3~k zQ8iw+941g7L2L6N5*Z+`Y5>Ktw37 z{p_6<7UG>6&co}%{o`Yzf}%tRVM0W38g~#%@n`Rhv^Wofb00wG=cL#%pz|^ly(7Hc zkGoh~V8x;=w6*cb5mi9T;f`CVyM1gop+yzWGNAuN`VZ2-kQmVaK+*vEN7COl-MzA( zVB8HnqzBAm7tJwgDdchP^j-wIJHgG)x-G!RYcn}$(LpF;&LS z8I-4E>C*Y4!U}K-cq$~H_rE3|_y3Hl-r|05+RQ8eE@gojP!s-GMeF1r2MDRe$RC%NW64*II( zqRBmryyrTeK0W_<&8ni!VZlD>p}h8n0CYecJLq^Zf+LavEjkDZ&R&@kpxv@F6oAf7 zb|OH}&dW}j7Z>ci#lz03J<8t=wb!cA-OU3DIIO{t?hSEtci-;VvuAZIapg^b{uSv1 z5(E1GA!*VZ(*Hhp{%Asbd((5EnI1BWI|~`oeEbM)&u&xmx)d%pmhg6Rs1NYjQ#KBK6- z((jimvvf^;{;D?7OK6^hHmuA>k;V|9Im|I#CB)Ge(6WPOKnqBdrW2^O#tp>8F9^_s z-iI>*`hXJ9@uXJ)Eg=0ifL1tYQw5;E`H!Dr!thUFs3&z2>d%;f8PmrpCaN%`M++A{ zY2pZFsAG%>YeQ@=OK3U7|`>@FuP>uq=>*JzK(W}yc}#$xp@g*zTnXs z90uhHZX9=JI7^e=p10NB@%ML`PFzui^OvO0NgtDbOZp}0ebV2PG=Tn*^uKrS*)q7L z<>vLC9%&SZ(EQ*M^3tP0O`INr^ql~2a?*hT+3cc2LV`KW!6P_iF`zR; zLV5B^uZs=~4P3CitgyPS?%0#3PcNaB)Y5W+0DXo4eTo2mN^}%*m_u|Fl7qfX4*Kl5 zN&@sI96h!H`wy(a=B>-Har06!l4Bz|Xa@9Zjzh00M47UaFjK^!3raHx&dx}PoPfCS zv4{>CgS!tOG*A6D<`4&inV`&);5>=kbFbJzPZ|3iCVWm#R{?1C4qDwP4jIs| zi9stIGy{4f0eZmiWI#`Zq5ee08XS^~o<41?fV7rkxZT7FBSff!q0KK6E2RFIlY^5PC?J>fYeKT?Eq!(J6 zwxjjIemo;Ry}yq{#{$#`(MmZ_Txom6PWmt%bBKc-^iguy$D~k4>nUZ3gX7VBEY@Qd zz?Ndryuuudm;P+JbL7^d(u_6H;Q^_UVg7M3kwH=MF(Khe(hxf-{wzjt@FbN4Hy*(u z0G*NG6(8zX;X7ycBTsv)o+U*oXn9QkmROd!w^LAd&^Z;^>qR_y zaskcFvV%Sajz@DxAp`n)Z8ff3B|x9ufs+L2V+81`gXEwqd6?ZYa?wl0Dt7CrB8V^t zIcSbUFJ6`{!W;t7CF#gWcS3yl7{r8pkEo!L$jz|BmbHbw6-`muB#^2c%jZA#nYR&F zSdmNTQYC(UpRnOmCM$&gf z-E~$e0eT)zZJmyDmAbgFYX)kMx#Cg%7CgDT7fxjERd5 z2~Ug*4^Byp3P?{T2dw~f7Ee;iNOVh!k4Oslc0J-@XVvLxZ;kQ=nP`4^p30hm%wjmJ z0=gdUFK<51&Wg1no~XiE2K1+-Ka&29^mEeBNPkDtq_;@_XUUSHkDolbQ!RxxBrr?I za!gtphWGTzE$rA_hDd*RxZ2F>@|bP&*n6JS`2cT^%|ZUY1k65?uc^EDQ`P@>a!!&U{dS<10c~mU2`r7ig3T;# z(OJl2p_QXJ6d?{NydlS*8PZZ5T6WNrzW4xU1ZcO(vV-mq=+}oh9E5|G0NvBm+eyfP z)*(Qfk%ON6<$L(<_dmmw?>~dd%qfzLreLPwWPkiffnMcNA-;L>(IH96apBR)abXFG(IFYp z!M;la-JH&O%(iNEvzyf&72t+L``4oF*$w(V9Cz*;(vZ%@x;-7|&mCCz>tFxNx5ShF zfR^LWnjv;SG4Y%1{~oN~ZP(H9@Of{jLw!uTqrCyQZ=AsDW%)>o@JFDlQ;+wY*)K>f zK64%J`MWwbgnGL^NQ(=3x^Ycu$MvgKXm96r0;HbauFhKe9Y2VvqR(Gk6KdA+8YOP>C#S|Kfj$Iy$vT$Y(n*+3JKEtS7GPw4hMe~e*+IK&}2XeF5Y=V~OLnEc8W(8-tdXJa7~)8OILqdeCaF=;sj(%IRFhYv2{(z$&&uzM9MH!mYC#lgL6aOwOW zJh*?3K68t{Ah$_86;#?WoVU>8-5_|u@fXjpqV?%T0`z%2dVF5Qqnl(v^N_pi`*Hbl zFQ98`q~UfvnuCYjiAgIvmSW4+#nOWP>x!{rb-sv2FD=i-qGj`un==o|QDYGo_C2D4 z6(J7Q7<4~)s=fY>;+6CITvJr;-b$@nvDHfe+Ga4Uj6Q)C0eZFq&^&2{U9>dSn}^z| zbP|dV!d^IYh=U!p)>j|EV(9zu(0Y47D?=PcuK_eWXacka0eT7ndhj3L!}M`qiJ6Z) zBv2j}$m@uh5v)xK(!BWqyJ>yJ!u?`>Xst0~bjRqCf5Py=zr~Dc{T%dL=xyOFsqeFw zfUP(dx$6BNDJ#X#N)wbyQLPAZ$bi0fcpmQG-h@XDyYRSix5yt+&Mx}Nz5RH6cOP2l zm?6!fji(O?+8pk9d<4&1j*7hP@lj=Gq1aJd5rY=t43!wPfHT8dxM;^keqo}?>2b7F=r{9Awin2-JyDXt9kpjRZ+x` z{&1E7ts36=1xXWs{t1a6*n9Eu(cj&;d3t|WS5s&I)$RCPx+c9%x${thckg0L()ek) zFh$3K05re7g}MpQoebz}JYoCY+tIFxU!(n#Fb^s^HG@ZhP1eGNQ@kX*wF8hm#GMG zC}F7r&Ue+@{4V~CQe2^bq|z(2X-y$qY=^*l<|nW=WILu+rE80y{j^q%r z=su%32-3Wz6aktYwDwmYV%D$^;HCXfs9voCXvIvzHv;-~4q6f7kO4j9Ki`AF!~t-y z)rUQ4HvO%(Ry-4Ox)>fPLNoODa`Qz+^-U1NIz?4Cw&;tSOjTy(LCg?z3r@kv;Z?Z>OO#$ zMt1Z9nq4)!X+CDdB(0ypdyq<7+%b^ZO!bd3tBW~Hb({>?vt7GZMi4t*2WNTo#_vcx z{+YuY|Cgi*Z~U2w9~j4lK3uRcZ`_?b7mjpwJ?!MLh74wPQ^93NtqO1n)(mF}++3hi z;Y&HMBg%tAz z;`jhlzIqSCK6(!(THj&boS7tJ%ypcJIrfGE)^^r<^mj|)8F@Vs4$<&dSVr`6VNg$= z@Hxhe{0|uF4n`RRS_Qyw)~nC%^%GTkf%<0kmX$IW<*BYL<L=Ii~>?^6A3cyZ*&)}-J3=3mvton=7t z>_K+VzajDH4bAYnpP2Z8@q^>$$1n2oGbh}{^lxW(nL=!7{UPC^ zum3=hzP5*)^iG^Uy+uI!*zt`xba)+h?^#7)F2}YVE3ji{xq$ShEsL>{v~JU4EL-e@ z+|-H4j30{>f^>0CzhQPVI91R4X@{Z-$deEH-+OB*DzWOhRI%mb-U{BU-s_tx3gGE5 z46{u?gRSW|aI~8adpkqeTF;Ostys(;(CLWILb0kHL)t(~IB5noi&wOpI$;oW27Cxh z0<`b6pW~3KgZ|M`9Phnxm>oN48PLN&ejk?82gB3V93C#_aCb3->s%87Y@QM6ApUke z`rCD>6(GH2cx@32GkVdGv!1T~6(*1S156EvqI^-R8W8uB!eNVbH~Kuo*X#AqT~%^< zy?U>IIV!J<^HLlV4q6wd$w8k{0dzA1x@nI9^`pi;BD}%zXNGgjy#u)4P=&j94icy( z_smdc*ZjPNhuR%SC&9V%`Dp>^u9xQt$|{bTkHtQPB+*&Oj+sHs;_K|3XMqc?tHQo3jo4<`T3rAx<( zIyxF#CC4nspk*LSpq2_!HRK^XXf9a!t;}Bzg_G{SiEaWjL%Nfk^o!?L#AuGTXP5Eh z$$30{aDo7R6itmsP=BWyHx+=sMu6rHLmtslb8@rjFywFtcNp&8yHZGsNlQcUSX;I) z!>Z-}D9M_P{M7NtNg9Vm1&*(eLBFMBV86ALm7FD4aJfQD*X7FnIx(Pq=MIOHVAZ>uzHteWLoZA=( z*;vhhiNUwfpZYQEEJtGb;x_|Y#G2na=G-f(JYN6oxywe2X}U&xqc@eQvR@hmk4dN+}(#ql=HHqkD3mUgFb-A_oNVqh&_{we)dR; zMYp%|+8ifEESe$BvkFBFS`mvD+flJZc!M3Z?3@|aoT~y`s++y_l%dV_mc_?1q@}w2 z^2N=@U6pI1i4W?)%u)?)@XWzqlQ{OQanFB&#Ia}|qxesxfBE8z&;Gb$$6Ei^)>}uq zyYF{NK$hRGd@RMFUwzA}7OHAf>NdfE;M`R!#PMkES#E2)On|*fK}*6za(1nJ9{cj4^0Z8$|Pn&Z*Oj&Bg1h6k(HpsGrWN$=cUj-9(mlvnOr zfpx2curyx_3v(u+Gm(TjZ==lw=wSDe zaI^ag&bEW#>TC$-IVJ*f>_n{y(j4aC-BnC@!G48{mKRPEizgAJbtVpi;lO`{?T8N$ zF#Q)ey!zD;hgge4)j`XEru@|q$E$$W`tm)D`RoHY7!60TpDluXZ4uyOEkNz%W&sZZ zwHtxjd5*Do$*`OpjN#-+;C3=4nZVw1D6EY?gPY@MtXi6;7R<6_IE!Nfqj+XN0obof z25?_Mzgo6^fz3brItP9C#zx$)+bK4Xy8(#H!xZw<@(E#j~md{b*Js- zjibBgIonMBf>1lHrS__7g{s;` z6QpXFsuC^XsXeGI_KJNACAAl^#7?Pwr$q!!L%w;x?_crWIX~SqbLTU6=FGkGIp=fE z%@)@6A)D*P{@3yw7EkukFG3XmF$k&*k~tE5BJ=vfy#I4R$py#+%F$(0u}pHJ{UA@O z_{oDe&$7+AqrnvE#~&X=-b}_dESC(i4>MR;m6RcCWa>3A!TK&fDN*)DPiWWYdhU-` z@4HDfhfZ{l<5`Z+gftOMUpstQzRa2~{Cx2qe@Q7AqBr#~E4S>7UFu&0kZ1eU;n5_h z9{B*v#56PfN&S+9-Wex5R#ST~*5TiX$2TLw#&yU_y*kGnKHoZa&i*>50qsN$|6U7q zN1lq<5%opXr_L|xu(JSa4gSp*q_w>KW)11+>G+`iQs*E3w{XYJkEM$wt|MSze^ z5Dd|ZirJlH@fJoU8zwOv(e}SrC=MFxW!x-7r=Z+f#;~wHB*2)%aR}t1U^?=i(R(#}r(3dv=UjBz9~m=AsGS38=aKfcvm? zZ?4E-N3H6rDqd^rI+^l<)ro?*IOdmga|8A*pCS$#J=jr(@|&$+Q!*PAU!g=~DEx@D z2!A*CU&Z2v^c;bkryKj1)dK?9(WdG<PU)d?POM^cQ7oaUBFo)Db*m6L(k>h||5CX<4dU#57B zS$C?ubZ$IgePN-ZbzM9um8U!JO&qzV!!ijNdHL0|1mTFcnT8K9eb{W2178n(>bL~z z3M4Hd@UI3ZPY|@`HMc0y+qd48qhb)Psh@;&Cv`Vf1n`(wSv=C^+yn92I^F8dT^Lc& z#3eG9iDi;&xb8!CK~x}nIDrh_^AR%3sS!(?ZgXkKi4fiE%Ux{FPwdET<_-w`w~YUtrp&GlcG=GW(K%1(r$s|$leh~KSn zPZFZL0tY4g8@f{zf_LoIn3=&Ui&L&#@(cOZmUE}&x!!eslX_bd zZGiaXbkYaIgiF`K3j975G)eIlGbxz)tKFU1hQMZ3T4B5CkwRE~fUp_GK`_aMf&!Uu zt~G)hI`Q`hWe}$B%m1XU1TbibUkM$O>SF1L@{AY;hz-eR3oyzu;& zlf%tjAPxtH)oJ2dD2JN^88~zJYzX!6?yA&3sMZ?U^uN1XX6f$k+v;Uz@N_(;2pKftOEex&r!w8saDliM<;w>N1^X%)Ik3L ze|@r+?@zH15s_@$e~7J^BP<}@L;iB+7&ca;^=W}FSLPj1$P!1B!>+HtLmo!RSz z#hI4KubJ-aaHS{c-c~F$F!St-&6-W(kuQu19M$($;&2h9jSSJ}{88KPc33ZUN^)JMKMaF1B;_4$D|s``Px zBL56sWhsP~=Y#=BoG|o9$8z+d2$^3mA`{r5YsY^}ca9(1J_mFX)c`I#sROYQ6yUAX zZm>SHiMt6KW{Ou>-ExH{{jlS%F3TY)s~)O21upe;#Sd+xC`5un*%SM$13Q zM_^lz8wCb7h34STNr4xW#f3+Y-`tyg5)$8f6Tnj#B-)@j3azYGbocg^gMTwRhT5gT z$1N<&CM!cRjvZOaARzlAUNEEbaK<|T`?P~JkYKh;@iiVJ} zT035iR?Q8Ig9D)ef7lMLf>2e_y8qfb)M~Cx4c#C<2UW52C+xe=okrdAJI;ukP@31W zJl+U1wI{cvHyLo4P1LF1wLe}VVZO@@6u~tDU!`nKUN(|hzyE`JcrY;WctX51I~A@D zZ7Ccc2M%S~H|tQyeTgZbi{N8I)4oe5M?2Nk7r>>}~Iykg=b1Jk#Gn11y?->|mNFmlL%ZdzpG9jiIJ>OSJai22F>VjMfRyS0P zrI?wGWrBlQanm&ekvluYS}!k?TCXzG+A^F;ZCP1to$Ek)iHnDaq%SM0o(v)df4~e={31Xp?$ozliA7pzXbrKM{L)LMt!rR6JFtx=)lQ@0r>BPac^T#eU<&v)gqD9?C))qBA!(K<67D8QJIKL6cAwcT7j zF#z8IF2AkigCE#7!-Hb*ZtF}Stcmb-LYx6;iBV>tdM0gjj#|=mt>>4c_8T(=sw&S% zHHYN`R94r=!qg%&J}k(G#)7-D{I0eqUa(v#?jHWAv8v;Qo}=_wfTJk*R_$*PS2yWY z{vyM_Mn7JkN$eg0Ev)B+2ssQZ1?evna#veQ<=08d{)r z=LGZkl(;Y=vT73hB5MOk0EPT2z8G z+Q4(#c3`-=Mt&^)rIVPiTA$nZ!LjNF(BnSG`u879Hf`q-2EiblD!c24SvzPP7N3%c zjm%d~c~s$gg~Xci^QpyYP3DrK+vAGNvO=OYX=j=zvG~k{S8gFj80HCnElW&ZRulD2m`=_l!N zsAXd}kN<&yrlUrB1>XuFCREnxYx!3_!axVW1l9=F`>#j&E$AGU)dXu;`1fcaCy&FA zJ@B9E*Bzn}Gt9?WsIaDCS?Jzh1@)!A&vrN3vd7~158r=#>U4u&Z6(o`qxoYU#joq| zw*r->(06k(OH;^d+e^M|0=DH=Cspq-o<{2D0!02E&SSay1re5i(G#>=60_4 z=ky{UvO9or6Az4js;r=fBELqqiEvDtk|9Z~v8-{+mUht!l}c3L2$I2@Fom9yDp1HH zlmmdia!gkUS$H!K5Z2fl<-{5w^{FA9|LV|Hm%xOxRVZa&7^(4M?AQU#tKoTW6H3KY z7_b4Uo6+%M^leTgZMQ-{ccbqBZSLa7$@7;z_=q%k>EjSTBvv13 z@6)n+m)ITC!OP~N>?E+{EQe@JMDqicVfN5&RXRZY^(d`ANoU}47yMzA(oLb8q6A00 z_ER<(17#<-DMh^Rjq{W0jO4jpWHRp{4PMeDe+D^$KRj;mJe>S!2gkG5?7z6!?Z_6T zV6N`iQ+CxA4Lt*zDiq^$8sFdQNdKgCF@rU!Yhhvou4hMDNtLwGeQi*hlaf(S=YG*6 z?Jq6Q^5_nsiC~Q-#H|GN`=x~wDNmymG8EYTJipSkBzto?{tN43MptAhX+G{mye}Dj zN61E>Z>;o`Wh?#5FHt;RIs!vCjZ(Py#$kg7F8KpdqHY_N6YNr_-}G9zS{0rr(-%4; zdm_IrT^Qeh8<+lL$%JL|#0%@dew-C_4Y*9p^ba^Qy|LR@qJB?ea|R?S86}>0;GP1Q|M!kS x#8jmVW*9<}gjweaG1HO%HKUenB2O#m9Ii-A$;f!z**V5Cx^H%`T=)6g{{t!fJ{kZ3 literal 182625 zcmeEt^;eYN7cPyIC`gxnD5XQXL0US7nxUn8hVE367KTPd8U`48Xpk0=96E%Nh9L)} zF5h*3yMM!d*L&7k=lpoiKKpt0v-kd_tF1~#Oizr3g+->W_D&xQ3mf#m@r2-UXN=pA z{&B+g(N|T(f{iooJ}&Sa6tonuuIbrao9$Py7Bium?TL>>fAi!OA9J z1CI}2KWlG$EM03ScQBu}vf)c#VLlN)K>>kt??NoBhcNYb3WolmgFE|Vc1_>ycu(^)V3yZu zHRR=zdlOG^Oi*&%4Sz-r8hs^quE6sD|Nr*{Hna-M%P*nT)ff9qi~C|Ju8uAq^S@VD zt>#xj9`kb`Rn0^(`X;}bdRj2}Exj-J?eEl0MKQ;1NS+N-@h32a_9i63TYWb#x3oSb zqg}hi$6_~^?~h^wLR7BCHV?U9q6yr3?v*Yp(ly0EhCoESmuc150)O0@Y}+%TX0=Mi zfi<7~z(cnct_@2*rZXus-dT<#Dtm{9of;k<&_HwZ1Zz#r;%A`28)uIiL07kGQCGLh zVs=e3R3-H_N^~|&(qrNzF_C^u(ErA4HBNzn*NKI`Bja?IzM*kMoa7Mst-3n#$H2G7 z#?L>pqtA?7=4N$4tCo3cF7AJ&+hyF8ZeH9J9R@s9=N3foCBLT`M7c5ilq~l#>-Zo= zomf8vPHZLywjCS4k__Y~DPUkSVCDUxxgoAjl2@5bpK7L+8?(vNo?jF9hfV8;m;SJ3$1;1dNuLY7DNh|n$F|*Plh?sw<5vCP6PkY52JrhHU4lKHW_;ByqIZ($Zl@IW=#q1O18Mi#4cCY3<^O*pRyYj zRZUChRO%1?J$uOo1VC@rL(1<)&t{K~jez-QmAf_h{KwmaOZ!J*&WNLHwT<=)*O?PA zWSkoUk@a3+&semD6xP>M$jV;UHUm2p#(k@4X7;MPN1rssG&eK#_AWnXJcyj9 zwIn?kE9~sVQi$MtJ(Q#r7RH*Is+bIAP_kcqA1FgWkS!>?s&I4sPFwq}qSDImRb!4h zsuw?5rGHT#9@_8hyjD{C$Us4f^N!hL?Bpu=&!5}mFTHeEh>CYx^at3|kMxn9Y57pnTfq(kr1IHjE@F`vv(?os1?qX2iZtg&@SGr|} zOgBo^OUu-G)I8m-^y6rVmn6wxK#&_^vA}{8vU2MjMro5L`f%mXnI6VEFyJqDdJ8^t zsZm|EEFOjI1zs)w7+-SQ&yY@>F}gr@9GRVFPRUCoG1A#;-Qb;zk|zfTQSlRT8j+agB<%u5!Sg*I{q+lto^^T;Zo0yEBum zsc-Ty!&Ie|{FZa^1Nl$}RjL*(PN3Ms%;AF{7&NlkW%}T<^iT{gK0942)p-y8R`r%j z%Gb5`XvN$U-K~AF){I+MC))x(!4vf`OR`nP{8?Sm6c4%-(9Vhr3DZC-agFpvcMWowTo@8!Y5XI1i=KZ}ji;u?eeeA79QBJShtI)TiTN?}YOEzm47uS-=QDjBXUCs3D9l*XQ2R2f$$wUuK@6Z59mY(?{ z{>^|B_m6bMH@c8JdG>_yqW!9^03U)?as2H0F(4xW>^ zw+*rRgZg>pe~jL7^fL_$+fIPq$%M^V$+O(cQ919AJa9v%GoC)}{7B0XBvF>1FW;pi zJ}!2^ziV*TrR}hx@pIh}y`@nCHrh3_oE#i9PcC3d*c`mv7~b69+2bnwT-4SvG9d{# z05pdg0d^1B5Z9)F-CRKN8KUb)mwQ+kFA(G3KBEOdNUpK$Q&RHcb-i<4LSS@!3#MipE=eKnceG4u$)b6{y2Jb$8#m3FZPWMm^q~b!RePB zln{tS_P!x<1l8l!8CvWUuv1cb8VU@hF7}Z%dUO-JyxCWl(*X>{X8~nk>XloKV>Z^p zPl4F0f0)H3rAy(kNp-;W>~-Z`{p-AG!xde(kJys(-xufh!OjCVE0)tYw7r`}MR$#N zxco<*J8lnc8FK><22lhdS7BUlMUC#@m6ek|c0Y2CKH?M~8Kf!$j!PLXpi{+sXXsAw z^mU03zJ7WHdOTpE^u$1_YDTn#upO>E4>IvWi2HB)%PNqVPcnW;3MjN_lZCT zb>UCWj1-0l#K^>wMz{+EwnIrNCo7kg#1Luhu&>Od<30#fZwwpfZ-x#6ZZ?AvgPRxn z(CrD$)dFKEvgow=cU0M@?woM9CDCW^3yMlO(&c?=Y4{oYQ~KJxu72}<&EWXf(Lsxi zeTg?b_OW!};c8L@&f`akmH*NE%cqm?aVCP^KCDjyO=;;X;*yfce!V}|4On~WlHJ3Q zFqtAbzd-NQ&7i!V(8CA!9veHN{K~Mt=@xSc=EJ^!YR8NGwE6gq^Qu;%suL4=2{a7o1VSSZr$cwA**nEE+FFN4p?mBI1@BX=j*w34kdCf zuROp1R9FaG?CiXxqL<$3d!Q_=Y};+d#XVfu+*~PI*ll`&d<}G7wl~l9(j+AIBoDRJnOa;H-BQr~?ODRyc=r&{fVtbbJ>68W6N{SLc~~ z_U3MIaJocChNW0XYnz=V3E9Ed1snG&-X~@;_Y2e5Zr1?ZIDXrQaiRyT_l=d{{vK)l z`#gwi%n|6ByzpC#C`!)DzP=SwA|hFw$Z_on&-+`wy*~xvX+_Vq^TosG=7Q}U;)nqF z=HoIl#ZSn*ddt&pyfEVu*qaT>)Mbd6$|mOchZbk3J9-0No)N2${#R3+mVaC45~rM zXu&1|!DZe_!_y9Oo47I9)z}6%R#)&NzE4?}R^E*DhB{Fvc4ddz{a^;=XY^jwYZ&;k zEO$j8!4$PZ(*b{x`7H5A*QXHg92@IC6vR!l+0DB%EPh-_q$BRgNXNs&vdvc0Wm?Wf zw~+kd_=&P|>qBv8r#Gd{iue2mA4%xmm{q{am~~e6!&)VGCA46t;-t20fQ_5Q{3$T6 zzt^F~cTA(A#W0{8$78ug+r*UBPT7g~U89USLwi1^kcS}gEKobl2#TI#)-e+o0%C6M zWFIfesMnZ;->5I;8YSy5m1Sx6Zt<{qJitHi=wznJ`@x_YdgJ)RJ_?H;Hy%iMAZpbt z5B{2i-qnzUktqlfpirO0L-vwug%%pS`J$uoJR;Zhz`nH}VsscHg3eXZM`93NeMreD zg>WGDue5eKqrE8!hhqBIFS2k}RY^gTr8gKpVsvbbgaNcop+%s{eI>jSpuIknvLfzj z6<7P4PHpPX*o;Lp4|zbCVSuMaMzhBBDtU4J>twIc){ZKY+@$GNo^-yXevA$*ZBQRI zwtKqj+#_xTAXf}vY?TX0$}Zy{?%?%@p`(wYAr-J3%i=DlFat=egx`vhUrNlThDXuB;^#6o9oPSU6Yn^8 zkB-_7UKW-}YHlG#6|1@Bk8CT(Z$dlxFg*z8Uj~@L1ki3S6uSJfVOJlpU6TU?qdu>z zj9!;A>+Hdw@0FZgYCr|v@Txzf=EwbF318{(dCog_-Qu~?QtP`QBP_cbJ3dYkd4#{= zzJA-IkZ9*cwQ*VPGc+2{;VJsPx%taWi)gf`7~@N<)z%PZodnpUQ)9Ps_Hbac8le`d zv0XRMl*lciMS@3 zi=_rZV-czkbtkBXX#r597vaZA?g$=!(@q1(s`hTMoJm**w_;G&k8xDZti-*u;AcJ1@Hs__8(@xDY4ua6}FY``t|kY6`vA#W7m5ISB#5=dqkh( zCM2EJW`YuiO25A^$S!~+Rx(^6z;mW8`sE{o=?R-=9d&{_?M#5~ysCCK7bNV3N8fdE zvTu-k@JLPReajfk z*dE+(q^?@bNGiST31~z}vK(GC=wH_-iGjKk@9G{;nndlxhgf1ioUY#prI(i%b%o4I z&vSG0<4XW$Eqr5^>dE>=;gzcAjt7g)n!N3-NZ=c?n#%j<{CW-bq<`+TF81~m7`0U=G0eHI;5)0hVQtp zX+5#ky6C6Gy}O0S@sh({w)2t<8qug6hE>4kc8x#4JS`$}1l}5IrBCDS&%v@Ays5zH zwZ}aC{Hcj@vx8i19*Y`PZDH=!okfvlVrRQRyE$phW!k5)Q9e)OdI!FH1(f-o{EC$+xZ1hodI@{Di$pM1yL zb&9~rxQ&FjW^K&99I1-uSzFAugMXdY1LnQH?N3SJqouEsw+c^~pFnAHdLFMTW7~=W z405IXXdSd!BBMG|Xk!Of4zBz?mWzGVwNLwY)Oe+r$E@FNPtIiWf|lzn&knNsTDHo^aw5`Q-a0QnORdqx{BM1TN4L8 zgyhpl1bfhuKr&w`OVICWXXfC|tLL9KRZ;=EiuOvf*pZT)W)Qjy|~GEUD! zYRWN@=lm&j$t>&t>HkK(Rb@ntOO31ez2TIo>!E;&NCu^cu%6QHY__x!n^58>Zwhy- zQ?o`{<&`tNP+3q7eF5I5bKHvk6v+Y?9X~ped}rq!WxMNDs#;#YFaL2j%YQN6*{}Su z@AOkZ<|l1x2mi?Mp0y*o6@A}Qb!Bn2xc_ss@i`7>DFy@h7y^b+6DOksWsO}lpPHG$ z-&vR?CcLQmA-$a3N}9bB0ZgQkvHvdCJ9iyVQ;c^jy=eJ{sX&g+3ZsHgRA4DAW9Rak zydX!K^9^Y}pofcBHw)JIY*ywm5HJN*xL%t`gOAvI@IDRN;FLd_G8)U=jaVW9XhwcL4!wvZ6t5^OruuA1+cs9>z{WSMXXUk z%jn2lT|VMWPJa5!6D~+15aw=YeY!Qtx~WQjP$1Jn^8t+c5HXqO(qTMtloWR*S%~;A zYL5`g-E6)fit=iZWO1>9BX2pY3b()p5NO!XwR@qe^Dy(G%=B&sYx^_m$8bav{a?^ z94yvJ%W}-=l8qVcy+O(_v&1W7t_}i!cWc@T3JK(=Kn7N9@lBe7uM@<{Rc$mCs~u#d zm(%Gb#Gc?Q!n&7t>;RUP+$4rZ?hB5s8({DjtN47%x77H$4RO+@6_v0v5z+=wpY9Um z&7qjUawug{2Q^Lu92+e-6dCLkH#u%jyRWZ!EvYW)A3#XST9O(&%F3V-Nhp8m*@=n6#@kp=DN{^V?SJz!pp{=T?6SKRV|GyH=B%AQ%Y-ZwLcjr6kQC_{sFoH)>*jRn0uC zPA;sA3ZA5X8xqrrNZQojF8!e7_B_|^%L)2lap5-k@rOk-^E~SoXKT$rTWmjjhMgLt z(l+UXRO1>ipI+`W=g=$h*~{IfsMb}(`5 z`|0PCBtwOO76X+)T1bpcbU})$=o1XCLgrn}EkPDH4F35Ceh-ytr1~SD8j1aWTjiQQ z`-+qEefzq)`bpo=s6061@SW-j0T}B3GyYUdF_2r0tJ$g+C1eV>!zW?+@3@P)kEvNu zw~a~(VlHUWjNf;`SlTYa29XjFeWrFzOA%}lN&>55l%;9PY&jV|o5Zh|R6V>9c<0Y# z86TP0E*c;k9MWDLov;Y{tLGH#N<>^ee(ldtKI&r)#01+doJ48-wasfbTB^J|5zQ?b zSIv{U>Asc@=pz0pH-~DP8sx?dOAcOF$~5YXSK`;56LwWR2GDcO2^W+H%dJF&yZ$+r^TLk9wO8;<8IO1uc;R}KWbZky6FNKh(BO*4rw3x&*&csqUoq-prqn=OUsTHpF4Ab zL|b6{{-3|ss$zb}axFpsI+f9P)zKd7{Oxy<_p^iiXiFKQkwj5ZsWFx{et%!gzs#B( zUbF0SKe64-^v%%LYOWC1s+z8C<^3S~s+~Sdl14~z0U2q7zLs^j5E|U}j{?EuhVq1m z#;S_(k!RA&kT%uV%dBr5^wt6k@oVs49jv$jc|WH3ypB6b^Psj1ymhUO=RJVz>=9w7 z0=$6MFsDytn_k6wgWKXHVv?qHZIYUvhkH&E18M6cCs*RkJCAIayac z#tHZkUr`Q{l0+UoSj(~i$c<4SpsQ=kPv?ICDpUFJ;hTTJ3!3f32xgYIe?63dmy&O{ zs#JYCUuB@J^s5z1c9i{v z@0W|4$pCcSg8qj}L*HF&Ne49YeU)(X!kB_C3pe{D1cFXopRFFKVMujqMgmYNEcZiGZqitif9Jg@hAZ5@$+k zKGo~{Q~{5GencPe@WYd7W54*&Uk2MG=l@Rn zl839>ynjocvIR|j^(qlhXEjNZFtnviw3nQcde&Wh{P0u6yb^MD)!YcU_2LC%%lzcR zg>5Q%uEp{i>(zbM`b}bG8)nHpzq9LcsnU%UTZgW8M#y1KNdD2VtaV$qNJ{Y51^*Mj zyzXFN4RsgY*|njeV2LZ_UxLlpn={io3cI^k-|^EoJX#TPb@eQCU;v?Fx8YRqU1(Kx zW%@%jLCbniBMIdrocxp&7k5SC!=eaUrh3!68-1+mEOl(;e~Z-C)r&OLH7>}*CkK&d z?{sui zgvUYCq3n9}0E=1O7HsdnO$cc!GNL(=UYQCagZtC`q3pE-xDiqKpBv?83gcJ8-uS_c z8NHX+`X+R|5&dcGwIWM69{j8n!jgmAY&z?%9hBN1My);CNqr}vJ!{tZ6$Z${%Ae0< zQ09XFrp$fb$MW5L3>YReiOAeA=X@zOzZ>3J(#D4QjSObNt;Pt>Ts~7eOmdWq_^OkS z`RPxsz?IIX+{UO?auM)#964V5rAZBet2DcY>0ji5e(VYMX)Y1$X?a^Fu+Vr;$q>7Sky1CmEp4R^6BFx#)E2@p9- zbozETCi!w0DMq11!454tX; zSoHRj4D*_k{zStE23$u5ZyYuVKk_-2MnaXp=+ai#@ROj?=ecg%>*wViMQ5B(wfR^i zC0pNI-4FM#>@xw#3z~;d*{}Xl1mDf0&?IERVSo2oZiW45pw}5HN$}xQWyJ=5Isprv z7yj3o!LHZ$4*oxiT5pu6%~N^)p$C#P^8eMZg7!u~DjLcHjLQB9E4j}{%X+fUI>UTn^mOQ>MbhgUWlzC^sJpfgHXFSX zHACN(&wlWH6>0_5FV_X|*>q%ld*woAMj~omHkg;#pZo{vPSvobGLeuGQH+0lWg>{E zsQE4k5b>O+l?i|~noM!YkybWw%O@0WSE-K%n=RsT8w(DXI>ed1?UjgK6`wkhWqeCR8J6cvmDxP+n-> zKR0~1h~rAudsXNQSmuYza#YX16}ARf*@%-3HH~eb)NN_OeE#4AR;?iQORG$~hBTm3 ze_559D#%@2QYwB&`a1jiUn|eo$_Pl}8Khj2WB;@9_F;qMwu6hPoSgm_oRf<>MHg-c zl3bk<%?-C}X^HVcS7i?mD*e>E82ba1lXCZ_5NbaehF?9|yB;(<+kM#7(eX+|;I(IQ zb;ss5Tfu^)c&G-}{d~_PN{NsYNzMpdemFSTyH=$UtC4GI4eCN2ZJbHrpgp8JZbOSB zj=P=(hwbgNob$tG%tgY$HLJHLOor(W(;_FHZ{2f<5mTk_ACIzfi}%rU{M{Iu1WDNET%Cn19ry-CaZRHGofu^ zsCKOqHKhRaR`WE^FD@ML@ePwOvK%u^%jBQ$dRs&Q{-q2IEQJ z8Ds!f)VylxDmBeBnw7^a zBKKD+Q`P|wDhpnRN5$>9F64|nQ_kb*--!a=m`wxw&d)yi67x-7e7!)L!v6xO_TZ#w z_{yimepc2Nb1h@~B=ECtd+TR_PgnDv%w`(=g+dTA4GO@kc%GxJWD(E$6{6`ubI-HS zuV9wj*JPI)|N7Hwg_mMx&>=f~D_>|(Q!Fx5Zm>7FvFy+&F7nvd@p!Q41TLCbu6Qnw zU0b67lzy?(h;EBA*N%0Mf$CK1R)4%jX4aaDag)r*nQtMRkH}{s^`;gOP^M5Rxo?zb)%@3^0h!aWK>ASN?2@8mQl zjxPkJgV(YG2eg5w*sqsJnieO|H1M***kV-y3$v%JKl&N7^LwYT4edU#l0UhN*b zY;It?&lGLJQ`YU*_nTIFdiX5KK<68fR}vz-501_i%c7!lB5WS{I4=i_LBK5BO+qow z{M9z2gY})3m@44zM0&;%{UOO)UQf4}7|q{}bqi|7eAvkBaF;jXF4p#Sv%OQnIjzOl zm&w1ob3#IRXKZFqTK;>?C~!Y3h_A4aCdq>TY*DNq8hOJ@;l#dU3|bla72v-^Va_u3 zpTTZB%UtW}nWXy**8q6&0QCnd2<2#U#vZqK29lT1q zrBB-VOFm>H;00%uV&J^cmBe^d>m)_4OucG5-NSm6-^rj{C+}9t$>Uk=}|eAEncR)9B;vo??s4#=U{?@q;*5h%MZo*#i{p z0pZY))*a3bdmjUeaga=SKu}lz7odmr!1$V# zxZ))$u6zGCB>prcMuM=5Qs|}|nc2FZB&2odvVGj&`Iqr~2var(Y8{!`h++CQueBQ# z7G-)97QaBa7TbDE_p@J$Rfbp1qO{7~;%P%}gR|*d7=@lM4;(hMN(3c>;*#tdic)Th zfcXP_#g3eurcq7pa*uiX(&eOO8fbOui6F>ZvLG$8CQ!U=^~sHS@#>^0^v?!LVq#?O zlG}wrisFXf&DE4qwz-aVAGx|~Af>vUG;|uWHoR~+G0t}s2Bt<|+;_BAJAaQT? zw{Xo``*nBWW`U(~8wU@c+KLJR1<7sGl1NLLeu?q)_sH)yFV%oJ5lFA%uis`Pvy}IU ze^DTaxrmo7$|aJVNhvr;*_&oQ6Zd(Z?=a)xFTCXJd!gW7X>|wYI0D^W8lkoE581*Y zb14G;xChiPlX&J*-{CeOO>KAV`C|Xo3oaKZW$>E*-DIa_e66w;uec#g%koC$A^z>m zR-Tf=vIY?-Es zcGyXpiykXg+{zuD-zz!=;2mY>_pxN$KJCiFklecW)ToEXtc`I#_hJH88F-n=K~|*m z#Q9ADC&P!JB7Qd0ckt-T)-Ax*b#KAO^4UdMCApH0A2l$(#PtfrB8RnW#)ftM&;Jd} z`DsrP31|gT6u}YUXY*cm{)KJwhU$YFY>VuC9ThRGWy-caK-_hQqTv&J` zR^{s2*$8jC9vE3PX7#l+eI8!z7K8umC{E{qDOV2c2@Y6GS=XF9W&u9wbf@U-N=IKj z0Qir?3(_ub_(7n~u4ci2zaHKXfBp4j!Bvf7T>^ zD5C9+Pg5oTU(S+=%y@>2Nc%c;s&>k?6@+1+UAVOt9Nwjcx+ zbB@roDUX1~Tt5{i5vG`C`tY|z>KE^rFMH|F#l$4xtLv*N9k!&$tdb4@W=E<^fICR{ zl(@Far{7Ngw(+qZLaWEjtxwbaC9$H#No9Gwi6XF{c4mg-TiFmLkzn)2-&)+HN89HN_e0pH$|_x7@z#drKevV)>J}veZZoGR^dFoh0q1Xf!MS1$<#(EMPv7{=L0GW z|Lo(%C@++ex~c7S5`qlRcI)YzN?be>c|iGvhtoQ;-8aV%&so|ZIDci{=Ve+gubz@> z7?2loxe3#IHx<>)#?n7&5D0$5U-r>o843LTBkvcgH@NS;}^II?}4Q`C9{57e30hJ ztp$hhyoTG*F&gnRen!^gofdNz_ZCO+1n1)@A$>&offPY|aQmE@ ziD{UF#2e8yQ;KL_x^7o&l6~a8u({Nu=`aqR&UQn2EhCT3-I?($$qUx}{jcw)rbmx0 zJA!Y+jt(~;Y7&j9p#^Ilf?xArXp;kEON8cIsz2*|47fvg%TMT&eK@yvF010Y$r*?J zwc!#U`wav1NJ&oNvWS^WBfN^o$LIdmo*!x_P5^DUt@tg!tMAY|@~k9`BuVWW*9xq0 z{Lk?SiilY+sGk5+QeLUBvgSpd{ynKnPx9NlMw5N0#26)yKsgv4_Tx846gMG{Vo-|~ z4Bei{eYzjq4zF{pwv08PQYjlS+eJ{;xL6eA%^C@-tf ze&?nBLP!Yr`SZgsn&gQa)A%e_+ea7T!JawEQ8&$26Gvq8^)68#D=+k$oZpGTxSj79 zrpRj@<b6lkCSmb?y1mxVHXF2^T(6R32O}DEZ!A&N#Y9TNRw{`fA~0KAhKIuaoMI zjB}U%T2t-9CgD+zvcOk!nj8@~AFzP6Ywy8xsXm&%@K2}Wg}CKy!J$?e5a=;cGj0=~ zQI3@h!1v-B<*+tdVyx;gsQfo0W15Gjs#DCNuHj$4!uwNR+)N%Tc<5ngG8)2mC0U2M z$xkEcLC)SWH3b7#IAS(7LKNvN-ODFyElDebO7?mxmey6 zEj%C&EXJGrnd{h-20RO499Y({b}F#s!vIekE>8RLIYw+68-a6@q`y-ZhU%fVM>%*sIc=N-bNX7rBV%V#Hmef|?NaenCaFGl%5-{-tX9w)csh9X>1908@VFU-6K$ zm$F%ydp3W%hDu}J?$UzJI33v#=!g^Z(}N|RsfONwZ zw%l^`B0>P{_v52C{n3O+rjSiE(zok|Ifbrd;0?YAi-*0_gq$v$#H z>N)$nl<(nHmBQgDU*aJ%BtDckep$O0x?dVBz-0-0%QycmnOq|@YkAVt^u5ePz+dVN zxy-uEc+}fS{!u?_#j37X+$JQJ2}?bb!xun!@Wa-@pB}XRD5jY?U$*NMeR_@GhwSeO zO+V?#sjk}q%`k5%$xEdwUTUbburTbKR`-07eNSeF_KpzTG4xZ8^mA=szy@9VgKq+5 zBm7DU+W*+onIBxjn$bY}_&kTW)CL|zyI(*Rh|G*4xJrvuW5P$cL%5LmL zw_5R>!Xgmi^LsJ%^G|$=czhV;*8hQ@E->Qh4B{NMeGqmH)@>_peL+ zi$9XL|LPm1G2Pi!Qwo8wRg6UHnbXAvMtT92U(;8x{$9!Fu%L_LFDB2jTr79VdB*zs zDjOB0Mq+W{ImIi+N7I_W8T|Avg#G;4>jAXYbI=rSVI?>D*ce?|*=JP{NI-u&_&Ibv zp<9FWM>p$U0e{_P(C>y|#N!4-mh z?r93{3A%;7y08h>15m1C*qHedLg?=c_`KIklc~+jhxmAF|0%VXNy}sYOMqEMKv~R4 zL7|>r0r%`^jo(~(m{(_Y?N8geL)Cf9-pxE&ws+ZSWbU+ua)KfNxl z@3`~cylKuhpj6zk<|g}(2;^Rx%8F-2a7_Py0j|9IHs|Qb`1@xZz8fbKljEY;dkUh- z2!HQwv&MwRS?th4j^)Q{n!H;9#iulzg*G-@I7)sD=B@P2kpv9`ZR)fwZ3#q(0geew zcBb?i4Fx^g&ao`&>Bt}w!drGW2@ydj{2duc*D;c}#}~FUQVz}=|K2@Dm5D7(wdHI{ z%8YMQjnBhCL2kb}Y+gYmiK6{)z99|Y!hkL+wO8J*xRq6AfsF2r`_Ov`d*yUKk1pYs zoqr+Q8jC%C=WG6R_SdoBtKVP)@qQlpHmOWM`7D8_e0lcQ3jDeN(bk_y%gf;c?HaKi zZOEn%c>{@2FD;gaI$L|e*?(Z;VkTs$a+bkI`~P+!;d4D;B)jN%hKJB z`{;T=+#Z|Vc34K*GqdlnBoV5974D4y%o%307dNJZVGJZh{r zk2WRM+LAK6f0B{Yw(YUP9vo)x;nuja)pK~%UWJFi{33FPB47l*0p|%xiI=;)t70*W zk~khoeEzNIhIN#`x;1^iOv}OtCu`q~!u@Y`z9PTvF}+()2sV(7FYcEQOL|8{?AN(= zj;z<=#V)R=@1OKz`Uhgnr_+24gKotlpxo)OBq*;SEShJEYdX?+m$9H?KN8w(v~Kjj zn$h)HH=bpzmgio5Hu2FsG)<9lW&3NR)DB!`^ftqbU*6fPf2?(^9R64JhWwT0Ta6Z~ z?EUX*{|%2Myy6zi;;DRp?wcaQRb>%t!yG&GAJsbh4m`~7Yn5vgxRqN@((v7!eFRqZ zEx5%Z9BS|1@`7K|)^Y8gO~KLQlafI?$=>L%$;ln1?aV|Pw^h4g37Z!F*e3oS^ym}P zXKDkn!cLZWXs9)9=!WLtpXO^3aIkNHZnmeE+PsFqkhe{|hii19!{o$KxndO$-L%lob>Q+}!~28WMZEm`ZwM2< zU)Lbo2+7@qhmewqU?e1@U}Bnd(>Yr41KummL0T z*MldWPYdQ3q(bD;Arr$37dqoGcaOB$o1j>J^Uk>sB@S+1Sjc9O)RP@hS>S@K1fN0` z;jtx=NTa>oiKt#e3J{MMZ35MSAB~%}%x98jN{6`e$R*cWI+UL5FU}7`op2CyX+<ud(3FXXVks!Tvw!F2lx;-#)nQflQ_~!MmC)==*%0cApwe(C{9ygPiKP;SQ z89xI?uSj>&Y+0NT@UT=rPN00JcrQvOyZHe#=&(P15{sTnGtWg29 z2csP5VqzBqMN#@{vPnl+DLce+DTi`$k}>YG#01==>(?Z#)vg4bbNfBnjdO7vvB3ZFJWu2c2I|UljnH3D~Kb*gn9q_D?lN=%c*62tAYRa~5kR$DA z-(tUn$xCS5f&#*Ni%9x!sek^dGC_9Iis) zQ_r)vQH@d06M-_}Np$VKf6`@FA6Xyq!_i>Dt?89NhJ>Xi@-M?X+zs_)=egZTqfb~h ziTA|*fRKa)RqEbf2aL>e(w_)1iJN<~O5&k59kGWLxY)@MIj;W%O8r9{J@6Cn<2Jk<-ADj z8ocU2XY~Meu@iiu)IQF9x%M1u7nk~Uo|TJJT%v?xZXjtID{XXRWk3YSGBI%z-s1Lv z4rVen8me+5(_!HbhMeS*1@~R~Bi4S z(c9ED0uk`VM+%5NamU-UC#=~FUZ!n{(A#8ifXYW;ZI99{e0Nz}%8EQ{dIxUecxE>} ziA+=2PaPK0RFa-=?Ynr_|;r^AX118Ye-ZY9F zaqq6dQk~DXS(Qm6t=}kyGf**Olen;|HC-=t#fiU0Y<6ieh z-WvgMC)ySkKx8@&l{D0UIcOl?xMi_Ra@rQAMig6UAJI`TP+=343FfYisl?_RJ}bR( zTq$g5c!x=ur0F{)sMvgijD(Gg8D7Ip?ChsIt*k1ckVKyt!(D{rwqANVH{WAZkLkS4 z`XOx#PkSO4qU?O?zl`t?8^H*)y=JL}NtbQk0rN|juT~?hFF?Mfl=2IK>;h@_QfS3a z5h%4md2L2NA!QMJ!;ix!ovy>DP*>8`)qF;9O3cz+ModPD-CH3~?(f#;TU@5Gc7mrm zuaXX8Ynq=6{nz|b#Gh`8)$h9ilG^F{QZhxu3sWybJ$eRtl&!9x9YLoVm~&8>uKr|TU( zWpE5iYGr2mHb~f~DX_Y;sR4eU+I^FiP`$$Gd-;@QQA)C7TOQ56kHIC`bU;RiFsgzs zz3#S~$}Py2ja&0ZyxIc+eU?OFbnT>ae7{2Be*^W*)1|CkPNaKAM!dz8kY+T9y~?*l zpoB)3s(?=%RV(T{vcjT^n1j|ySwFv01|}vl5%2G0kl+C6>WfNnD8f6&Mz@owN&~vW zTi!+2AVj`T{EedBTLQlw2WGJ=Q9vR4wA9Denj~gJGlTR7sP6xwS6tz%rQI<3fAf~+ zk&_B=JHo5cx1j+80i*b?vnIgM6w#ldtJrW~qL~moRMXqiZ!kVOqgnOW{7K5z*5Wp{ zD|NQpDuT}^5EtCFPSf+KY`d7eooib@lg8$9rz>xm$=! zkkDucCvk6QY|LHAw1AyO`4}IVk$hEbA%uJd`7xSbL+_@{mRlPM0prP`-t_Lkm5-F1 zzP4w78}W*bY`zx|VkQb(1+mA-PReQ$lpsc=TqCx+7L1>km#u#MxO&MkN4D{t4^7?> zQ{N`YbI80oR2*`3rMjMn0~9>EG}_VbH59vNNsh89Z}g{Y=Wd$ljv$2S7$JerCp2&RMaMwlI}@bRl?Hj3h6 zLAE+aCw0#KWFVnMSPS!;_zdfcN*@c=f&X7={( zPZ}phR3`Gr!!*$BDQFR6G!-mvm%b7s_S4EUah@695Wbn_+RI% z$u{vodIC2Uu0cd9cjinnNyH`(sn&R(7pMlm9IRQZ1Bgh6*sG%@6Gv5E0ZFEaQ-Ct7 ziAXQdYICHJ60{2lrRML#vVGt-had3Keuy_FC1LH5!)N7B6O>HWs6{2QY4nS_UJF$% z=rh}4dPgnJJBL(UG>N&mY;<*L6@VDsA0_xNrKhNjMRjWZcNN<)s|D)!Kc0W?s{C}O z|7nWzY`1C}Sd-)DEpr?;BItNMsd~J*SFH4!msl}C{RuWF9(zpB>ml;TzSw6%LboZ; zj$?<^IPu~ny9bdJm)a@*LR&+N1n#RSQS6ZQE$80*G{6{$YaG_tsh z%b6((+ALEWR*!WIcboRQXEd+a=jf4g7{}Ng#rv%WFcbuzzG4QNN7E)1zaAG-FaYvM znx*~Lw~t>uxO4oqmNY&>vg08#ARi||AjKO)iV^>fE0VWI&_>ddkJi*+R_>KyyCkZY z%Y>jvIP%sQz5qTK2HN~#6Pz={&c^gW^q-!jUF7c9&Op}uNXf-6xBm_-(dE$dvtIG} zS74*-w=w+^rRiYuL>@{>P|-KWG`(RCn|dK4yK-+E-jzowCbySFdWc8iK+%3#0tiHR*>1&>Gd5uzrt@XWrAI+G|#foGn;jxuwf%SMb(#v8ZBu*QV3IU10GD}hfpV)b0W?|(X@i03W zV5wkvCQOP6d>$?wjgpf5n%Mc29Na8kSTu>9Fxynd)2Ir{m($n3d(Lp2Q2PYn?{E62 za8e8B_`mjt`!+M(`ygc+xWT!fWxY1wA)2RqACUBte~AV^0Glo1{{SpO)4s^h4M0wo z4>HnygtZ$N>w>UwdjtmC!PDCuw)T(k-0Thxp4&YM-dAAy8nFIHMF5$s*;j$Pg}^HP z$UKZp7rZNW%)k}uAsjopkI+vm5uFZPEPg}KG9DJcL>)d%TG+>eg-nx5>e#9$X!r(*=)9R%KO%G%YA z*_F^G5!Np0hrE3}?p9V6rw=JH^7lWXMWCm-cg3&dZ|mak_FJ z@HXnrFIP@p$7x()`Q@4f@7PE#Uew=4Tj?RRlt^hPIE0$q!>G)nc!fE-I; z&p!Gw9A6`E0x7SbOjDxCqtbqqPV)VCpToiWGBT3wkd^L=+-!!fA2QRuke=#=)O|f-gHID|-I1Q= zh16s>Bqh2bA;BF{k&Xxswia#%7uV;ou)Yr?h9_umfOzb?wkRjvdf zw9at-QvCkyU*V_!@)P{a&;JQufBi9b?KBWTX7Cywng=tp^LYCBln~>mXL0}5HXPqK z4TpAojZ^!-hw-f$aC$loA)Y6YmgJ1$f*@3uxS=Fz8_JVbqbhX`YSZZ+ljX}_yS4Gx zZe{zZ_Y_8LhCg;GM{{EmiV8!-kh{UbA~Eq155wbOg32ORt_SJsRhF^x^(tVqp}=)m zx*B9%o?5rH`p8K0U}IxpMq*O<16w<5LxL{59A-Z^mf$6;cN&A&!pic8fFR#Zg+=Mc zot;(Xqob`8vJFb8$~LF#29$0FtuDV@8y$V22k)CgRdp$Ww~6j17nlN-DnM13x;jIR zMdl{}PYe(D40d+a*Ois!#bjosxF#ee|ks!<@mzcLx>O9ft>KA z$O>PEjIfm`%(#JyvM`beRFp@ew7?QsQ3gm0TaA=pk`MxG{CWbcp^)~f$LQ}(MRVyb zRHVoW&hzN_sUgb{<-HVvK9}I(X#zX@$1pNFjf=U54SqJW5$3%YN%0OyPH;g&tRv!Moe&f4jIdA}`1_l~)5{Ew zPEW)H=nsvqVb95J_-N)7@cuiYJLx_UE(0B1W8o^`Dyx<)-JkyKA16Q3_}%Y+i4BI! zrNz7QYivHY5YEmw;B0>b?oPMiZzse+|=HB)q)+4eZVKz{m3mLPM+& z9QYL8_J;7aTZ~ZGWe6h)A&K-@PW53GS_*e#=tYqD+AuTS2WQV5#Kj9oaOU&@I5|9~ zhjR)7{4Eg~!4KbJh_4mJMELxH21}_%7{&}?c1tKQv$4SbUWPFD+LX&o7s?#xy3W6r zZyFySt{v#;EG{oCOY_Ojj(eVx5`HBiA@p=cX6%iE!erChy4=v0FKe2{##)ETVy5=W z?TOo#>|JtP`FZ6!+1r%ujMs5m7lF4+58gM0%BqsT>3jveuY&beogt>HGa%W*6u=V@uFN%4A=sH&Ro)gvDxawjNh6 zZpGP?n{f8jCR{wb8JEv*!Sjc^QJi%j4YiR3>^lP7SrN;TM$k?0Uy5+gmGE}I0(-|N zFfqG>+jo!CKIY=sp=sE){aXU>d#?rKn_L9{7MZ%8+L!J=XOP8f|7-~Y9M>Ss=NJLk z9*J>Ih>NjDY_tPnq8tgl*6{Z;hnJVB0Iw;7_sLc4J-K}nyt**`YoY-ABVqUo$f_m7 zR|{U2g$t(RXJqLr@bZ^(n>VeT1n-VBO9_CF5E5X7u%PFN3N=Nr=SjGl%!2)s?_qiW zTbK}hA7A|%M)x+u=<#{nxOoaYcWuDxm2*jEW6dg!P<-9$*|>UU9*PsTpu5EzeLa~l zH@$^(1l|nl83g)U;OUbqsH=%VLYxb&^Tx+G%~pUv!Nk%g7DbrXv6UEa83Wyc# zX;XC;j`KM%g!v|`r|i_HF6#_u&dWY0ev!a371W$pS-r~t#g$VHPS*ff#JO8nB`n_B zyramAS&78Jr3i9afaj05VDFwSm^XJi{`|+c$lCn_S&Q$8na7SF*#Qr$^$2sGgAnJr z2zFVBnBX%=jCVmqxC8wBEMRYY7B{b~BmnHh&K+BX?9eRFo!Jj(+cO9Ywm^{oJ(xaR z2(w2kU~jq>PUh?2>9`XP4z~!pcX99GHC(-U2Ins9#mUnasjeEH=kuR!ug!q)9y zv4E$7R##M-E_7LD&-@Br&X*7!`T#NE&j=n)bj{9W?b;K39SOe92oJMGP@pAzeJzBm z!P4p;9zDHI7Ow`pJJ-GHX7~?Sy;|_<=sGTj0~+wMPxq5g-o-C|`BVJ*w?7vk-nVC? zbTtrocb{89=W9&YVusiV3&clTBh2?aJS`W)$#^bop3H*Ty%~6X?FT%#wHY^W9>?JJ_;9SBa{?{psOPdrY1M& z9zRA|NjT1)J&1dE&*AQ!b94>c#fLHCcTmC&q3ep^7i|n)>2{EHTi3$n`mgFc16LU( z9OrymUB2_+_Mu)>a~iiD)z-LONsCrOm)jw?D;8<(vhgKfun8aV_{fOf)$qnpQAyzK zY@tUcLyuvn3tqNpS!dA&qfD31bgiyU*MfLrLZvGZD_yx1l&-etV{u--nG&>oqvg$4 zm4Pb(3!g9VgX2>zUanlMa~f|$PvY@LjP`n9r2RgI+wNhg^)3cm?_sdb2;(E^0=oS7 zgyDfSG?(8-Mdo1?Bp*O#>^{T>?Sb|44LEmn4$d84i90tA;lb_wxOj3gE}xnYSM${f z_b@=Pn*oB{HX%IdIyGWDczc_|#`XaoJv@lhN9JPV${AQT`}0XzKIaSU-?|tNZ|}h+ zg6W>!tFU>)H0;~E1G{!@BiL`pom(gI=+POnbkE_!<>NSgc0Ug8oq^rkKgVXnPx1L@ z@9MY?v|xN?-PH9{*Zl`%#X#>i_}QPFTG0Wbwumc;jN65fy1i-EnIK z1X#h7T_tu8@!a&b#^QZff|o$~?-2&8hzrnaEZR3MrwGsY%U168t!o8v+1fp@Zxey{ zE9^PHlDhk*h>Nlm&`pT3MNEV_!U7*5!22$IJZ{6q@j5I_&(Zxnjq5i~;K;GvSg~^H z8^L>c_bep%twnXQEn1tBP*o9ykRTiJ;mhH}yKwy29^_{EGg@RTh4-^OB$7T=`Vx;&iGE<23}_ z`*>Nk1$|YU@uFfAy30r^c4M@k|7t5geBg1keLczOYL7)*OEj7q!ckWhgn}G5L{bUSu#{SsRY--W@N_wd=LnwMm+f#Yk}{{`SqwQ6w(zH}wVT^hm|5P1;jT4!?}tDB2)wUYt3ni9X{jt) zhUgTqvQ?`r+o__`gfMIsa0PTXW4{KxyU#6$yW2hZdOi~1jVJKNM%o}egnJ?;@b@u> zhuaeZr*Y!cKCE1&1K!zM@XlrM?puPykRvF|cR+bb7|hLX(LSD`q%ahL z^f21FV!kK+to1x5u@76n!Yq^_=;&Q>d@EAXoPZ_*Wb z`IvlcJ_lX!vM7KmozGR~mrrWt&ywJk6-iYdSxFeYLv44_SGkFxyOE%~5go-F&|b0= zLoY(a#|@*yJp3z*z?+5_-Kps9Nk>OpB5JE6sImAWFUuX-=^nzOOCZZGBiR9&$@a)f zp(ROTtPLW=ED#)MA->yZ3-8&p>$rLAG)|t_jg_-L#1HTO1k*@(Iph8R1%pMOP19S07Q6}*2Fwr-w=jfP)f-I^~5ywb<} z*MRxD^^@rYj3fNM1YGgOBg0oSL`@Do z(xH> z;QfoCyrPW2%dQ57AOny6Gi*gF%a`2-EDDeuS3X=8-E^f7(?0%Ey3}PJrSq}Waas6= z%Jb2>9auQd-5ic9&~x`jRSH=VRHfm3vU@~%#;b*Up_eS(9u0Jx^9|6Lza2d-9%!z7 ziu$6Z>io+n&AyD{jLXPNK9986QwZ@n2oHxNWcfTnWVkh1zxUv2zYlKK+Ysfq z4++5s5$3%czRo+~;d~s9c4uH=aT$*uU&56uM{$fS)s?e85Wtl}7B7K!{esW1ciR%I zSUMfwfA=xI|MnyCRT#g(d-ueRcunCRgbEoy7GdB{(A{(oR^SzCIT4@iv9C z^CMVU-Nv)$*KqmD39MeTd=k78zH-SH?=gBO3$r_LbA5*V zoIrZ8XCgDhpDf!zdceoP+35*9-KkdX-V z@;biJEUfc+@;=x~mQP*T{oypO1T4Ib1UY|tIoNU+J>{FwRk{%^1%{~2T8FBPEoiK? zMPbTeWJIh$dgL~Q_+5pg?FHCbor8_VSy-5y#)G>@aP8`0+`M@nkDuHii{u<`UOR{z zSNG%Dqoc4eJ^?4I{ctgx56j0h@%;V*JTp3sJ9p0D^yxj+?cIRoGv0eGc=v2sgw@NY z@lFOxgoZ0UkihEUt#U4kFaw2NBH!U z*MGUjaGVO^NzuSoH~p3TI_a;h*NM;k;X^n+UxFa#)rj&xM$mN>lfS1YIg5$ldFWJT znin!sJ;mGktW00zWci9w9yjkC$NK#XvE|4t>^S^2mKlD8d8^*V@(mwh%f9JYw_^?# z8%)EpjWe)i|6&+y{|*aQy@z=#-o;AFvv%_*SiJ6Y+U6T9-7o`&R6a{dpFaOrn790G ztl9JtR&V?mbCF?XDnU&Hn!~k1Z%f_f`#kf!-{R6!qoN@ z^;FCdLXw{BLS20~q!4`LVjK`2YJ-qqYXtb46EL5^#^x?e&2Hhwtut7=Zp9>Yb!9GD zzDEylLvox0ax=Zi>J30yQ4mTBf(fSKsH=$+li>GsWmE4ehk938C@&4i%^Rn1{E01yUA1wz67Tl+HJph4Uz#)73syCE;}( z=Ssj&U(U<>rwT=ta-ik5#@aPRL(Y0sq^?0x(ngdOm?0%{FGAcGBGB^?tgWBo(xtPw zborcIl3cv_Iyocc62-4wy9gHtBUnCKjHfrg#=~pVaqspnT)21u`*ttH_D$2UWZEAl zp{u}au;2q6+&&Ylmi|D{{XM?>>Mbl>f{pzs)Q}c<&+0&Vj(|O3-o^0M5?v zK~APOExpB8ZTv}baUp@HI1Fj2UWg|krKMPsb@`NFcblxdD+uzxiKwuL2nl*h`UC3T zKccj!2=KWH7sqpOvOfcFw~O#`r?Pgu2y3gWaCW={57&Eeusnk257xrgVn4iG&r`k& zu(vq{JDUq+Wj;oL?^C!r--5O2KDgWOMR?#91o~bR`}Os_N*1mSveG={HIVQ%u+wu^TTLIs|00OU@5o~PlOYq)4OW<88Tntme%Pxn5dside_dHT#jF6w@f#N)00&gH$ zzu~B_jTN69H#epri!9!}+yHd8r3jxc55?opt*a`c3Cfvx*_(~Q{#-GK$H2=Rl3Wb) zr|5(7vvi)#j%TuCAP*1l+#u|l;Au)r<^S+T<(F{$>nQOFviMy+16Zz;pCdDXNhaeA zQx+9h7PDHeH*+0|5>_EQ z#t^v~&k*Lb9S)|m;ADFM78Xx&@xmEgCg4sALHIAp%^O#!f!pB8jRm-K?lasv|2?i< z-hvY+c3|tqud!kEdsy<_?*(|Jk5__sWTT+j$k%j1qoD6p%48gQy20DuiQW6}H#3Lw3;-hU57io>?Fbg>ZEXqoZ zMqod4a=asn6Ostq z^6)`vVF0Sj!|2*$(9)QUgm@1eJ-QoD9$i9vOES7U($LwSiq@8Nv^1qtJcF#^O!W6j z;4*|c&cJ0E(5z?R@{D%;sXG6EkN=7y<_TdLA}e@|Cvd7D5SL?YOisF^3u5`Zr>P*G z>LcbQZ_A@87`QC*OFHRS=IuCt6M?r`58gKgb~SW#wl?sj##B%k9_AU1nlU=cej5fL zTazpdN`@Fij=`yx%5|UsJE9S#v)h5w8MwD9M2UdKz? z?*xBD!QCYGXK^=3c9*11`NVb5diL>l*`u%F3c9N=qM_&vO43gtJAt5)Vu}E_EwFkz z1NK%r;AN-^@ctOIGEE!5c~gS-(Y5)wdFE4GKl3dvU)YEvN48?)`Y*ALy1k3Pe;d;Y zwk$u8%>3|Y*t+Zk+&a4uk8bV5bz1H;d>3n$eTGeIzr>y`-{R<=Z*lz4G90D->_4y- zyY_6twjC?6W!rM$;}vr?Oo8H?l0cG6HU8H0o<&#T1flEj)>PDmvPd(b1Yh@QD*Y=&Y@b5EIW-mC<&^ zfdnXj0pel;a$#P80C|2k?LW(tAnAb|f_oOjGsQ)KGdtajfbUK4XK0g^o#jgww-2p% z7k^sLBbf7qKDk*w033)zmPZZGuqL75oJulk_d33yN+CC-8jjT`p63-E#p|zj)$l_f^pe5+C5Nu~@;&TYZySMxRPqP___B}}F>mshBtT+TURWYco zj)%X$HTLY@j3rCxVNKR^TT6-nZ+8a+HLs(5+FK4e}pXtfrv$}ho77Vl__{%4nO3gs1L|E0aXsWBlTgl^bvJQZ>W zPL3wX&yOVlGw>L23_OM%gOdTOz{znI&ci@eRxQVQoo;>>wO(z{aTWz$1zKJ3a$a5V z@;(Tvqsf>UiN(Zl1jc%dG1_^bNl6IO(_P{1v2pKXJS?G;!)T7$<|zQpabpW^<7&uKrO zPCKZ_&_x3(%$%+=e{m?$i|u6BY-TN*7>g|sy%ps79< zO=JN!)I<}2!^t9KV2223v!z^G6igrv6jm|&N{dK}^8*Q%fhZ6__7zYoWIfkktP?t& z2g9|1gtsZm52AFk!bxZAvxvI>YANTdZd&*H*{k)T#YqLiUcf zbXu3Mv6RU=9xNm&5bg?wG5@oVh5roA%Q3cu`QLp4%q0AOKU%Wo%>Voof29_4O|$>F zoZ1t^m_-X>`BINT-8lZ@Ma@19X7pidD6c5_FKuo0O^y!c*u85DOpNcs-0T5Poji#1 z=Z>PLCYuV9=i=?b&`>)`Cx04D1=~&Cl~w{XztG}!ZDcVw(UOOlbkX`|kuKw{7#yq@ z7PWi}+DU0GA`e^FBO~k@P%Z=oVC8z?{V{Oag`ivw1m6j&2wgWZ+I)~?KZYB&VYqG! zhFEI1V4!9*`fIkLzjhD$>yKib;LKem@$@DLj}G%c%Mwvr8;(M1Y$?>8^>o+-(}xV+ zeFR>ke=~TMu&cq(%MK=Y7U9X&FYxH<4|sTY7p`78hy%NSz@F_huy4;c?AWn+QuxcY zv!`~$)oL$-eICHaej8kke-NLjT0i&}Cbz%A!z*9o&b5uWe(eY@Ts%zh-G!Z7zrv>V z?_%AmcQxa935I_So(izK`6m6sI_oCWv~gYFDw#R$eK&XiFvdCJSk*k0*pd*>y2UY1NfcNQiS4AHu}bvaldTKznl1eg?4Sg`OBwEMTlgR@9Ey z)#W;CFryDsLwRM%-?X*YH!^q`w$06j0+5jr?&7PdM6!ej2Ro6S6$b|g6Ife4MRIZ& z`ukf@QJ#+QFgNt}))2t5;N@vWOS*|K>k&cQ=jBDCv$G6gl*iiY5ds42(b`%pV4am2 zhR_gac(_|2I?9vQsTX0&5>_BqmahV@#tI%U!dS;SjMQ%>*@9t~so<^NEXM5iRqw*s zU=UXZsx&d^Yr2V!>Wio;IE~!oqsUCYMc{RShXC&nuv6d_K3;;V5b5K+bnX}~ojFW$ z2$wIOeigiA@do&J88YJVCoPIqDQa3!vt{Q<`hF2s?&^MxGRJr76r z%*T!MOA+955OEQv2=hJ+Kim26vYH1c<2kgCnJ~UH1CQ_Rz`c9?wbUtGxO5PQ4lKZ~ z9Y0{>hVStCXRn!^?2V!U?HhG1WO+F?uDfp5^iSY!Wq>Geswd$WsLSq#!W^<5bG?Q2 zSVIlBp*C9had}3rwq|xMFl@OS&F~CP}e&S%?$}?Yl;`}ZK@-kwrL_@vkQWK zqP3M|4OhpYiYFf;2(wFqEn|+eYofALuB#{^C=*C4Xq`wS!0{Mb0XqUX`&d~fVXn!; z)^$~RxPW^Z={&J}5y3h;(-*199!O4d7t>q@1zE$>%NUMMMtJn(8Vn5A2n$zPy3*Gx zWyi*81m1;6h`g@>FI(C?rZ-snyQ`zc$PfNdf=4qn&~>*oCdl3al~sFd3ficbz;P}! z9t9zRoGRvUV5_)^%FWF57S_=NVD;+dSh8dx7B60awQE+ukj~AH9uN#`1!`eIlO@f- zW#M%UV+Cf0GOy=hZM=__E0RvJV9XX-G?p!KF(lVQKLYHr7TsapE9> z)rZoOapues6y(PvD9{;Ow`_o~j|0le(s26pA;ib~!NbD}*RGv`x3>*$-8=_-`{(HH zu7Bz4zI=b zoy+n0=dbheN}#?DoVxiY*S%r|znV6gXNt_8^(6w_&muYM7Sa=*2{!{OaGZay&rqwQb6~5vhM_H%kpye@BZr9xgIXtC zBAlPV&UzK;{CRJAS%mngf#I8$>Vw!=PlQJ}lQCh35V9_Pe64Wf#&K*hoPl*Kzr^}g zUt+_WuVA?POKe{MH7*?ePJB|G9P>!{mJ4!xsf-Bvr6F`|x(+(O%ye&I@iKVp>*CSU zlqiJ#;4Bin?0#Ttmp|y?-U5{+l_5_j$?ge1A9Lyvox=I^hXsIFty)TT@;GkYIwQsd z^R_+R*#zq>;Xm#n@Ujn>f1b+m7u^KgUbcR7G$76 zRxkfMkbh;xE(spu#>3jg@Bi5qAzTu*S_4-I-sYg88$Y?xO4jgnws+P;zc#?-o1=FcP^u$z6e*Z5>&mcVQP902M+9j z(UV*7_p`^TQ-@Gmnuse`PT@9f%U12vr#A^+CsAFU1zVe^R7sA}K8r9s%+O`XGI*8G zmm$mR-r(b%w0O1P{gK66CBe(%cKe&}U}P{8xv95c`+PN=%~v8NWEC*~DZalEdkixAC(fmzj-X8&bx z3!vVf9~l&$WSqDoCD{w91mlQsb67lHhKHBG!rk*<2w^`xPao-OJRLz!%jkjnM7-Ez z|1rNTWDA?Y&&T6g$qo>BdF(EqOB0nDTd}RwLttUBvIr1U88V2uJcY}K%82#)+IUn~ z(!SDtap=$vY};mtqC$GORK?OY#*6KEUT7X6p_u)4J%#J}=Zbk48fp?g-Dgkl;_>5a1l@9skGD{_<~~`#r_j++MNh$J6hDqj7mpJh zcqG6vAq?4;=6nM1L4xfG>b4k@wfh8auBHU+90IQq?%%&G+!7L|%A#f1@{(b!V9U!X zKHhP<(d`nv>}L3})vL958N4r>Zc*ipp$Ez#>W(de!MepTzP}uq5v!1wa)zuLcSHs3 zgqQ7HSU+2elSkLWaQ$MEMc6=MxQ=BZHW)0y=8dbcZOb}r*|Y+i4N2dy6k9hf!`@x1 z@a*1p1UoK9tmizW2CqX|z6DuP5vZ>UMnhE~8ma?PSK){15^q!$d!eGp6J-VND9Ujc ze#Zjpsxy4$P$uf$Cb}Xr!VVtp&tPqR7tc*@;=#kSICFeD4($Apj{m;&@oHfBS|OM! zShDDXREh5Te@h+~_VGGD{Q;qla}Xc6pB@};!hc$l?<*``wjL!UEI9?os0nf*g!_*kO zY$>xv%vNwT0hk~}Qb!gtTf;n#R)CnG#iI;(T`gJ5)oc}$#alxFuBzZ)=Z6x+f~k%K zBQGaV05~VdpL%*hv_6#9xgo-P3w&+n!OL|UR|B82k)DL1aEDlgM%4acn8tiT0~$| z;OijJ_QB838D~x(Mr;fLAtOxWv$HcMOSKazDPh>Xdn?YJJBqThM6&vhW82n^h>P<@ ze}5eT`#SF5yG)fdnk-{W1P0ilySoCmwomcs;Z@4RU%KeJ5*We^Uk0oKFUzaoognaz z5_pxRJJsUV1@DXUjRL$CWx?39XDgO2T`VS{xpa0lvZB_bIO80p`5-lNA0oXLA;4)q zY>Z~&>Zz}A`S=&OeC#uvIq(TC9{CjaF3rZXhllax{!!eyyaLxxe=XAQocjt^_opGi zb`BDJ77@@lpfKq$LDq>HOsx1Fct>+Qb)(sjNmfm5BuSK5)>X34G7x1&^5sw=HB9c7 z@=&O(3?K1g$KT%^4i1lCZgCez&#uq|#1JQsFT&0pv+>2}A521ZQeJT#{Dl{2N?ysY z6MvIXo>?)lO>E-5Qv(Z}LS~x^Ok{ zk{j>K-aOIW(+}^@3=GaFptzUjo*Gdo;Af{t9*ArwK$+9CrGnDy9 zlr02(;ijmIL1S$+L6~3O5s29xLGWeYvv5@iOIQM}o}kCTWp@L+9#|NL7v}rM560$ZvYb0|#7jCkf}(W1sw&l0gBg988pNoE_J+m)e-}Kse+8YLJkhf1 z+A{zL2*x#Jts3L%l~cHK`6MjNAEU969q2F7)Kr2853a$%{yF;kYT@E+hC6pIQF;ME zy9@dGi3Hyp)QviW+qW(tF)waTg*W+l6^J!?#)~l0c6Ji9 zLKJvO*w3r=@op79Ual-pjV_ZFyA<0tFNU4*a^%IXMrrm1s_3C8&Uud9l+>_eF6LFuQBK8u2s ztEeuvMsuwXS$Q$&;^9H9iDcoW5NN0y*Fkzq0;RE#rNZM_YuL)723{H^8a2Pv5kHS4 z$t3vl6q9c5&tYTt7{;czaOds;oWHOY`wpzd7hilVV5qE81;)v^j_Br5maE9C$*cBtXYqeg+nUjX(Hc zw?l1BJjKa6Ch)N}$vT6qsxp@DTZ9-U#`i2oxQjfHo#Ba`EN}7kUVg5>a9ObR%p);) zh+Ii=BuNwjl&$P20xr8h;skX0_zX@K5vTPMvTULAZ}ekPTTACm);*u6_#lPA$uQ-- zEE23TU7R<;w4Plr;<{*?hNK^DFZLl|OzZ3EA=bo_B+8C`?)(sx7BK&+h+oXHwVQ#C zcCv)K`Qr|@f(gF;CF2zpdhot6l$RI(myV9crrzFqw6_;yOuXb$-F=4K00Fii0|O0o zBlGCSQ3L7cFTwcZh?kVV2VGq?c=3V~xdLCGf*CjS|F@lwwC1ZCjPB`o)FH*4PE$n+cF6P zWVz+uMseyfl#uYUDETP$E{>o)_YPUKY}pb>$--r8yS~~7HD$Kc^RPpGr9Ca}QCn_@ z+DaEXKgvhvSXa$2+5*MHkAYNA)+LMZ50k~m-E;wBiZ@ahTtbN;NZ?{inIX)-carc8 z6D|dYFZWtFE?o>fTrHIHgp-i9OiKoCRi(736?kjuIQ+3mwE%sb5Z=E8KSP<;39Fc_ zcDB%80W(8X`mhCjVPLW-U8OUiSyup6FV8rxz{;YI%j?y-NOy;f>wXeU>nDma+G~yB&W9N8 zAnAI95t6Z<$0SdLjCMbv^hX%#e2Vem7zlO@ZYp5=BKzVr( z@(cWtl^sCcdP{8DxEM(uPSPXf zB;F;tgM!otD9?F{nj&+w)cFgbzUbsP^~saq?SGL$;7vzwSDKJMl5PSp`!D$=5W`n= zZF#&ZHB^Rg9)UL|#tFW@=5TU0f~n~_TtEKq+Z2tffvsA$cJm3a zxdhluVd*k}rJt8yu*os3+~C;~Wec;iECA_IdywG27*Sr!5ahBPfsTt1>^K+EzFU!z zY%k_o;IG-T(p;(cav8y{YY^(bnjQ{okQK2S*^#S}pL~R1%P+Vh=)PS?X7qMs$L>L4 z`W1SBK16BWBa{_9qjaB1SP5&mCIFR1&rwnE1mz@U`HxYY{Q!lT59r#Rgw-p->rG4k z`i;P=`Iv*pAM+43DWRxf_XP=qm|Ylr-&y230<(Cj6-Byqaa2+oi};TpNfp7GAY6-jqy@^r+R5ZqiA~8M~j?q4Mg4$yY zx8D;oLh*@_YyuyHlRu(p$M|R_Z4*ZlE0z-@@xW+;l(8hr!=DuLpD4QV@?{-a&J1w{ zUIk(XFGF`Kcv*NIFV$>g3c&SrzC2KyhpzBfHU%U_7#S(1ZcZK@i@Q7dq?d~H(UC$i zK)k!%57jw`P@K3P1#tw6n6*fY-h=q?!wB{}4nKbrT)MO$b7p^r_uu_3-g)~MB>##( zy!Eem`>mgg<)8leTg;jHDeTR5h#wnauphZ;cH+evyBex1 z!pQQB7d}|o<(Ci@V|NL>JzYFrG+($F#7i|E;UKKuLgCjH&~2AiRbxX6fgpxp6;2TI zM6kye*gTt!E9X~Z&n^ROHJF8UbAFBW^WMV7#h+rslFzV#my17x!Gd?OW!((y+OZb* zZ)`xU_hKXmEJ0?>KI-lVh%(MezJ{d0r6iOVv=k}9%aIzg0+~@8=~^tQOV5_4w0LVO zoRJ&5f#AIg*%7Od8NL!}p({w%p)l(?onx5zaxRzP%cB*dBkd6uVl5`v;g_UQq(?=N z&@z^KF|pA+S-hi=SbDhf#|qIDXW=v!rN?ky9X&Rdzov7c?VROD4mvvjc8R~V<0b#; znMH2vq@z1e?vIze9j{Y5?<+2b_NPhXk150l6`JED#JiDb^~3~s@xqZuLe$lzjAv&@ zx@$0_4^xAqv(s{E@pcMm4m6%Xf8Bn(tlfv+>K*7Q--x!N4QR?UKyyBI=i7oXMgSdu zS&K35BG%tSckv$dlSNe zvV7Ui@H$rmTe=Fmjo@Emj}7y;==_yU1~t?KdICoyKR*QS?))O^8C+dVQB)X?moIp* zc``NlG&I-RqcFjc8qRWLgz?WLm%zn*K8zpC!@Zj;#oW0YHY~&h-`XGb)Xi(IeO`8PmPv}w9>>%u{FUf6@C zBePJw=OYv!`4T~K{RL&^|a=AH}g_2e5Y!SDd}@a5#^w z=z}Q9x=URm>aG==BO`nbSvE@$Pu*2N`?)x(Zj3o@i2$kvuoJ9b0sVvE=6v*7Q8(j1YYhw6L>ot9MO=s zAC38Y(WIncKf3G9gayo2ANxNUPW(cM-#T;mjT?MvafBE<8XRH|Uq36jxf{dU_JNog zYtGzRli*Z<)YbnzqPy+X{U}{``O$~(DNQtvSPMVAOVvVicN)32n5=i@(_czPPs(p3DdnROP< zC(?PJ6!-PDh7XCik0ptfjC=FH?###-F^0RFG2GmqlR;uc@>ER3&f-ev=H~Vc9wN_k zvCe~*o*wcz9`4U+ds`L!N%qRPMq9_>(@^qBf}4Q`4Qvs z34sE zNKEoUc!ZO%dVTp{Zq7!y|L_ulcjhaA{I|+f$W8^T?)ujWr+@gtyI8t-HZGmti?Bcw z6l8hIuhxor+QV@0hYUOcj+}Quehk6mb$Q}%b~W(F5w1d_1uiK zWJmFv_2k%x2zOtGP?vcKah``@jf8ouKvLX8q!91}18qs{;Ol)C&X()pWVRA67Aq0z zx&+Zwm!dqE(F5qdnEX98*$qhvF0i+~kF8tQiK!%cmNOoq!sC8=0yS1qmqfoDMAMX+Aw1WU zsJn=dHbPvCC1PWpgqtHK#syK)PIOP~5gcrTix-dL92sTN(Jn|z_8X6g@bp}_ZtWlD z&YM&A?RVc!eDm!$_?Cp1-+c46Tu#wB{rm5~8(+L+ao+YFJAbdi)PKGp!COw?ZNTV2 z7&=OKpryb7HJNLXAG;DBHgmCO=M1b_vk1r5E{$nsdrPRxy#$>_>oL-H0~jx(233LU*G|L2{E-H{Y~`|Lt6U8XUxqOYyCT>s*1Sj) zzFj#lsF-qYyd0f%Ca6eVkHYwsNDU#l5=8AyX5#9(xdh!$@y+cm^{6TEgP5O?&SqYA}cyGY&nWkkBebW?L7XJXWuF}Lsi;()Ml&^ z;BClWhsGQOvUs0hxIbH1eGDPCdfB(h?gk#}#6zFhznGsFOpV1G@d<8-jC2(6H8s19 z#Y^T-`ey|YmFqxvokspzoR_-mU$;)_EFTbfr~mLZ=Fgjs%NGtHEy+d9kx*I67H_2Z zkfFVqgvx;5c8gC{#aB@b-fUszcXec7QE8Zr6s!?bijN0>;||}9r3i7i6EDCNQ$>cYKjLEqVFTbbtwWJ z=fa#2P5jX?-j?|vUxo=ZCWKhqS?K3HJ;y@Py3qzKf8s9 z3b}!Vc=m}pAU4V#)|R)idD9yB`OQv=41lOpb^9b|WMuyjF z1UfH+pTiP(*)4;oy#c(OkHXLU0sQp(=e1@?uuNjjYIhJHNuJRdaEaz*|S)?IGYYe47cl?IgS`Ba8Rm_9Zy7e>GLa z1t^GGg0}p%7;3p8K>4z-Qh?XY_&oZ1q6o(PYwB7Oeo4mGEV~d0#1m~8A4{0)NsY*S20}fk zOPt7)VLwH5&@qJj9Ym1Ve%M)TC1~>GCZA&7+%K_c@eF+Q@q765pWl%_ULEkV%Rzyc z8{Yk!dthU-A6CzHVqYShs~ zO@KGo06h&x7#-sIRC(~ZoV0}D#O?+m1Rx$q$-drV_DAMO0P&Ew@NfrQx^xta7R{pb z{|>WeeuFu*27i+bZVd5hNIg){=e&hl7 z>`uuNBNzI3s8~-fJ#4aRJ%1(14;y~jDE+*>FY?hvWx$`bc68*Rt}aphwSxWk>1l58 za@>UH_h#bMv6Te2by%@*8oqn~f8pEr{u$qY@Nz`F*Q&TNF6 z`Fwa;&Vrx)62wP66O-S>N8Lk^^Adum1g;0AyO_;{l@UFd&5nwm1%DK@a>Wv?BH`uA z6^pUaU@2~&p9Pyo-^1BtE&{zTA~M_#5uw(I2(yN{*$q1GD)@LA6WH9481oEKep|^p zCM(%%5n{Yw6*GUMJDMf2~QCl zv=8B)D-q_lh-4vI;tT0vLP9;(FwYH$4!eScL?;q@c*S{;#mcj-xgjpjRlHD(CF_-6 zkVS?W!QXW|eCR>qZ9A9BV-A%EJ%r3>!NGVYY>cLpu`&}DPgld%`aC_99>Lo7AUbR42yxj!aZiX){I~lwb zFDLLm+`XK-;A?U7!fFEVaOVx-$lfR#ry@MJkAkGA1u-4RUmT*pNBRa#!fIL8NF zFwV2#j}&64`4R?ex1pzEi;$O9ThUud@$zjLXg3q16uRoA#al!cZ(7(=gt|$$!Nt?F z@%7iA;!l5i2cLZWKCYdfCoJ9&_w8ii*dZm!8OaF_)Mc_oWP}y`{ETt${%IUJwhaaw zS77P#`S_l|!qyx^RsmO6-unITu!SrcTl1?3q9=bu&{MK@jFFmXkAfWPKIZw5_==%m zJZy-+RLV-aPYr1?B1rOM*Ptw!$~e^k9o3I9)XyIhNMSJXxAHtEtLSbMwD=QF9!tq% zH!CWl1cbO7T96+s-kb*qn8Cs3CZ0bzi>HrH;nsz@xO)5(Ts=7rcdu>5<>TMt{K1dN z`k#*5S2xr8uW|LnC%8uzy3xH|xO4t{+&c3a?q6MuCwI3JOuoVGv#c+J(fu8`ckx@? zzwiZ~-#3Jv)m1vq87!PXovht&V6c8ES-dlGVBaS3i8K3l8*A9wjTi0(eqkub?~;Yf z7A?<+)yscL;CW*6$imGf>zA#4Ii{Ciu5mhl?9xT+yE^mG)R+REE1;|_lDg_-wZ+{* zWZ)@SKHrNo$JgNK{>3=DZ!S(AUQRIHgi}X1;rL-g96e}=gL_xu;J!7uaCSQ^OwJ(G z?+QXZ44I&Uh6(UCxtrYl;ApKz}nldwLn`*DV)5 z)yQy51bOU7fWth5QtvFnUHX!vy+~-u@kkP0AMUn*z&RfwlrO|}F`|RdA~n^6tX5xI zdLt!;=ZNs52e6;8)xIjJLHhOAU*faRKE=1+vOX26Q$fr6kKs$;P2Ydu(0@|!I@%F< z3!8ZYnsHLwLZwsszh|MV6bfBQ=`{^l2`|MkD3 z_E$ee<*)u3x$pl5_jWGCp?#}y`|?_pC9Fnw=@yI)29PD&ivIq3+`W4V7EcV&SG5^q zjXb}?W^|QqKuYKa_<5X$gTsC5o?W3lD`5U`CTyRP72;@!(!}*>D_Dl-)m`y27oN0Q`39^PY5*LMz&ZcHZtY{JRoTXFitHkdp)g!0^{=;=rzt57q> zm4{HZ@;CJA;{*9Uz52A1$4v5Q2RX)*h2Nt4iw`;?g3W}l)x&l-oJ>~2*?be+9nVua zu7bt=Ij}P^gs0O*xL6ocgCa}JX&*v-Z_>kcGu$oLz|Z**f$17qJL}VmI8g#UT*+nwY%J3M=Q7Hd~8#}y7wbr3 zPY+;cdJuDWn}=fAAUe_#p~0r~Fy@y{4`FS66HlLC6)%i75O}}(<3HnzKm24;mQMc@ zZk}HYv!_R4Z+!*M4tL<@{0MF?1TfdfcyRA5R#O?-+TMqs&jY$IYvE-zo8UWFfR(J; zi6Ey%qmCwvMl2sK9JhbA0KRtfC&9`27}O!2JINZg6)pmH3&h2{3#&DT>T{s00d2$X zk-6}(nK$lYHh|C*WTB7Pl{cjqB&W#MLt- z=jY+ZtrNI%?IhN$U5@wPe-|IT|7ZO1kAJ{hZ@)G2)mLAPPX+4h<#pg)ma%{Te_HU` z5_k)m+1ea>8HvuCt7xk{hvu>~Xec?2ikuS&_Sy@}XB()Cu@zyDPa*#KB}6_rjgZ@i z5O8HRg03t==$++oH#LNZ%@!nu>_o%Q{2KG-{D9*}wvbh@7LD0!(O$R#{jCJvacZ1Rrl`+0 zM0NTa0`p2_hA%^`-y*o%7~ssw?PTR_z_G(yVEuG60_|rZ(q{*fsH+$5xk*gV=xfVe zs9CUoHXU~_e}mIUKF5JQ-(fdxH*elI`0&GbbfC*F2CcmH``-%idbvCh&`pf8B=A~` zpFQ&byV8VJEgN`bm<@b=jA3he6cLMH9`sIVjOn88n`Y7?)Fu#am z=(10gKRV#gZQ0rt6Tvj{xAdAxQ5eEJfW2M{kC`pZ@fN?o;a`czN17u#^ci(8jcG|R z_Pd8*@0*AWenJl)Ys5vGAvVI4y1rHfQF|mtTOc9I94Ya(;$LJbab`$~HAZ%tGjcQB zk(p$Hj097PyP_!14@GpWJX#+SVu3(kV}J*$(p-)>ohj4n)NDp-y!hMcprDJ?18!QC0JYBfUVU{*xTNLgWX*? zkr8qG)=8|So}z`tZMeH!gM;Z(0^kgKsLdt|biqrz=gSLkU0xe<{LtFKz1vr3?B24h z>)eqA6ZX&M!kdf;79SFSmrZ0bn+o@Uc%c>LLKdqX0z8k<19L9iEoP59nJ#R5et%8O zmGg#fNA?@~?%cd8Z_E05LuU`qg82ghQrH;HfP?v3c)H)!jC!yDe+|haCR`lO!^&tr z89dWSrVpDuSeo3)Nan5 z-H5a24`aouC73z;2W;HD7KWSFO>Eq3m^XX&%=W23{jt2s)xh9A_@5NK4g}uzLIN*; z=39iZksOSUWMg#DGJ2dX!UA#3?@tEkJeM$F~QPfPZzDw#QB z8jc>?iU_yWsLx!j0k5(6XyRq71zHL=qA7PB>ax~Sw|zBA2*4R(%c){7g5`tRuzf<6 z)^;AEJ?0@XcrP-O%@O0bRlL3C7b)z|bEJlF;^24Ku>O0TIlYaZ-WM^8fd3&|ynG&$ z;MK<8dh54hb~10Wq!ObEUIg9bI9md)6M>f+G=VoU&OtQxkRS`VyBWdU^c+r|SS4Ok z@-Qs^ef!RBs}UD&Bqqt>iCp9)FUi8v6_a5L@bV{`a!!HfhA6Tm!_i#N`GZM9&_YsQ zI}$hX;afNuIBmAiRpCvLuj}fvB(MITE5Zll{nt2hTmx)s`e&3}U_o z1}%yFID-Ffz>}yHknnG4N-#WBhQWbip%3&IVsNljfLK_;{ONFS5m~)ikTYkcp{X$y z_4WMlkq;mVUwZK52a7t%Kg3K;VsWRqJM{#dkrc;2y>t|=kc>1R;hssSu6rh3duE2e zc(b3Bz`jmLgofC{kHG8dYBUMnTel^6zno(6E}ljf@5P-kd3qierdMHQehoI3H(_gi zO91%hjpJChYypgoufxIiA}pUQr0)7O0^qE{yO)G8!A+pb(XvHcP)FCW`$XufK} z_YI4te~4WM@8Z~wcX4$4pK)-@pKx%;cR0Lv4OT9mh9&dA!S3xVuxs0@iM>15=g*xx zv*T5uz8y1a&p(AD<^lee62y*|9=Ix zc-z|Yn@2~hF*;fa0pRg!jEq)bWQ2s)4Nzm~rEXw%cMdfIei@Q7X>swie@%5!XsnGu zdvl!lEOultkAPc3u;oz*JQR#aDRk310&n*<0`FD~)@%~vg>z#Fyf@Zj+tv-@h0X7N z_iOzAcfS%chn}8C$!ZOAT_wQVS+oHI?Ir}?atwA@p|fNY!Fat8c15r><*Y?@+A0)8 zFGXg^BBTc|LTcb5WJVuEekOI-g13W*l7+d>gP;8z*gv0vjRxOg*6i81di@Hltj#fF z=1hF>!TSQV+81l`VZiIyD&MnXJ$yYLlND`EK(i6nVp^gj!I!KmYV2(7#*oDo6lf_L zFqKW$VKz_28J3-RauB|Bh*zz$=~r*h7#<<=^-Gk z+g4sS#0uzkx63&wUXaBqVB0Hy%qZqy=;n_|LP<|0&}Lz1Acx?aOW@5Xouoe>g9PJ# zf-r-ZU&8hE6``A~WjXh3IvN_%QCq{q?brpAEXF(YC$0S90#7W&Kg7(*@}mceH;Jc! zZBjhXZLE3NWcrivI9o3N=$qf-+L_HTdUOWHPcOoRdV*#qS72dw4VLCNaOLu0EM7bpj~`v62k&V-xkd5o zU*ql zv^4nkZ?W#%zr(t3{wG#{^>&o_-|1`8? z)?b#LuhDg7*PMSIa(cSDucO_msON?InZ_oMMH;OB^84YE4=1IPA$gA2#! z!T7;Oce=!Qguj3Pvs$Wlpa81?jDq;KKvqMfp{5V`FI-EuKEVE=Sc9HTNq=;j2V;QmGIU5fZ`Wg z@VY-17B9n>E#A}wCt+>z7|!@uXX?5-ATYoZ&SHLrYdC#+3w597;|~N~0p6`-@kUsP z8NK-TGd#Zm|DTM7eYd40{JC(17|l>pM1Y7rAwFr14_Ge7A}9DSL#+2ggpmaw?ztVY z;l_vwvp{HoF#*%0cv@I>Z3onkD(HXOATa-;%JKGRqeAuQZBy8rFXWTiL7k;Ds2SBzWMOlr>l zTb_MP%s}=c9c|TQ-RB)dOXV%J*E~df?IU#5Kc%!dvU24lIqZ61w}bl7g8jbTU2>uv z{;IFFITeirUH&Rg_`V6e?DMWDqX!dDD#T+~>0u)NFidbwPhmHL8;1c({RIav%} zA6inL>;N&gmBGuu_3`twCg_^L$?1uBSUx0ZUb%V<8#NZME_fGy{Tp07Zh-rDj^Xix zGcbC57SD{%<2gat_}OKgKf4bL7tF$KvY4MdI)YmlXW;tTFL3JU3ZIkP=S27(`Q?P$ zfuA7BcP_?8FHn#01{|yx;Say~Z}`nW|5yC>r~egmKm705I{klQyGFL@ET#M%=`1Rb z(*F+IexN0ZTB^9(PQ*1jA7d-UxBj4(QnpM}^0(OZy_AjL{Vg^Sa1FlsA6WnO|G+wu zHDCUBtR`9c`G3cX&;A>hefr<9_|w0`^lv|XEmZ$4GUxjbu>RY>r(^vOjmTrOY|_YP zIv*ulNVd{>O3_}!)*ndMxhCy(lP=0aQyxO5>Rgtp%w@R>q3w6j1I_i>3XBXplELaa zHahCsr@`u950(~pSL7$3Xs*pWgj#A8b@^JURZCi5owFa6S^H3tu@~j(dr+Ns5v@&Z z^$m)Tv@z>cnUP!M2=)fA`Gp1|Eyc@Z}+7Jd{lSpNaouIy6v3R$UZz z2OW@}WQXj;$0$mFjJy;hR24a(pBm=aa2Cc#a>Q>%_>BLBLc6+!j-_)F5iAzf%lOHx;99qZhaa-H!YbPxyz)*8_X833xW6fNgO*g9jjK( z!Ka^oEM)Jlbpn?B=UkqPm;b8EleX|A+!dt^TYiBQioDz)WMz6HHs}z7T&U~%a6PVG zFu>)L3vg!FdpNP}PdKstGo0GH2q*U}!HM0AsVg`Qr}odng;Q%__k11VycZ$SX8}?I z*PtlNjI7!qDvwZteT4YW7%$nn6~ECT&@yZpYGU$j@eee1B_xV@7kF-AF~4w2f`DyT zt8_0gaC^Ju1VHRwU@Mk~$+3H(zn7p{c?Z?$>&1s8H5ois+z@p++wihGjPlA~mk&~1 zc*)=uvzHNg`GX3wcso1zj|u!Wo16`cq07SO$39=4T!?4<60VU#E;niYGJyFbiA?_G zJI@wIWyzD7Gk|lm{gIo)W$Q1-^YTXl!9o04wkbUK;VuLPt-~I_c zBboo@uW|OsTHL;I1o!Toz=M0I@Q48X_~BWya?jz^$=%{(o~s1zJGb}a(y3`UfArId zBL`QyF?j!9?EQC8Rok}if&TH{t5>(qeP^G0_TFo+oL%M|$T{bnbIv(QMo+t=*lJg9pt}z@3#DRCixBU zTF75dKGyqsieu8}^R^;*dwMnzmo`C$)!+VDwq&|}^B$j@9S5DjI)6w~Cy$3EbHr1 zUXjL&BRCAf1=p|P)yqzTa2tX47+%ri=iArabeunr9W!^T;8FfLQq2ZQe2&8!-Lmn5 zn1FjjKgWwF^yVcP@C|~)Aswd}=$SZPpN9IHBy8UhiR=tVL`7J_!a@^z`kV?wV4OHs zA;$Z@*ztx1x?|_I`67YuiKax2b*|_SUTuDMl-n#9(r?I-(-I zL{6x`pEtc>C)4MzAXu>TtP+lw+s<%ZUT(H{jv#WD4q2OjHy#1kvBaKGxHNsFe@3e3BI!nQjw4l1Y=`8WM#!7cUlWJrS{yX8V!? zjP{h0w z&k}S`AFxL&>GXbkbR4Hg#_M$=4#^dmD$1n%MUH9K)~phV;%)YJIu)s!|{VFM7IX+QPzEd+oA6z2g-F_s|gb1&Ik@i$+6Ydt;EKa{+K;Y3$f8| z{lNPV8F*!*47`pq@D}Fzpmu|~2sa$Aau(p_db!u=Z^x_4xSIoah&c)!B5F`P|Mdi^SwNTF?W^alq6Zg0#k_uX4zFKwUoHl3 zvjA`RaaRG|D=j=JN;)Zl_k|3+eKB5cB}3oq$yq#l$O|e?;lYDe+`D^9bUV0l<0$C} zu3R}NR&a4nE5~ckpR1+6?M}3{meNg&Uqgm0ojbM;CysBxsZ->3=|4*Rckg@=CHOjgO#NztSn67XlFqX^+0BN z7^Y@N6I^4-*(PG<%*mKFGZ}HQ0WdVwK}JRlrcDh+8i6+@W+LB!ZzqPB)Gv=2b74`~ zkggpot-3nSC3dx)Nxo5#Yxqum+-Fc3{dcI1`8ynRzCf_`_Xx8aj&O(32(uq0$!;V< zYz85~{3`^SfAc!na?s@vtHI|;9Xtlp=xy}<15f?W;cG-PmgHyp4FW6&Bfx4HX((+E zfxpEN_?ZuakI7f?G5!MnX5T*wvmV+SW;5&rjVD4$L6$?>95uguYODG;*lS3#<5BZ( zaM1c14%*+rLiJ0St9$`lt?x-cz(H^DLjxVPm;HhIdu3*z_Q=cNyG=g&U#|Ai|6;YT z!I!K3`pKVV_~ohqBT0cqU#$u>mWj55Xp}2hE|af+pG*~`upc5*sM)ux))cxfy>fZ2 z&(mj{|JrqN+rP`O`r9AHi>Es@Re9Y!wa)=3_IaUYUkHt%H1?@^ZwQX>3Bl32U>vQL z)Y6bfkI3cZ?n;rLn~eC_V8q7+BaRdw7ecNqOlWdqI5JWrk(m~Sl%#O6pPUqdl*y4u zONpj)(MV5;qU|WGSveaI?wurX$_wH!MAZm?^Y}D%B20Jj%aRLKu&81J?@s`SbaVnvqm)m zaCMPBN(yvQz0n2jCs&Bj0y|Jn3*%73h4WGe3U08-kHp+qaaZ*+tXbxZSvi^t;58C} z?Q^>WgLiJ8FM-!W^nsJWyG(S|Wv9!9Y@~i@oI}i#+$`%?a+#d^#dRb&gdl|u$b}Mc z`Ss*D?lUfCE(7n&XD8`t=M25>XT_5Xzy7aY(C0kk8{lDFX`6y$yPZWPuao;+=|=8~ zuA^QA^=c6h=I#Ytv5aq)@|9~0+q-vLaElzSRF}6&EFtc^P>&0Aqvpi`5fK6K@^S%p z!#zMZ`aQb}P`WMvJ2pjOcXa{kb}z=(H38VL+=C249%`x=(taS;FY~~TZF#8JS%eKM zd{JEFh$Y3zSiEE=Vq!x?9Sl7KUAh^&!qdwgHa3=`b-J}R0hmTd2OC6$deHxJFtRcu zkuxO<)2GEDKQ9sa`ALY0@fYCb`UTUcM<8>uJ~9%NI2EfWJwfMMa*S1Fe1y}Agc#T5 z39*jbBLa2L2YQZv7vMe|L7pQJ;x!WCzM~Kms!8t~AEYFQ(0eBcNr}NoBsU!!?SN3< z@d)uA^E%W|`&49zQ%OvOS7CIx$AVx#%k4I%Bkwy9P+e_)ftxMKZYaFnH4)(NfPes3 z1o}JEwiEpP9O2_*4R_}WaIqZ%H~Z0#LIbTgOpXsqPn{eQ9~aH2U8Rdqxot73cPz#3oy$>Ixe|LSmZ5GZ?bGAk-s)BK=-VhjDna%liQwBq zE$9rfjjfwC75wY zfm^CGc<<7q``w#dxSbp=J??Yr*E4?XC&0>K$}8+R1abE^Pk^1kizkv8x^G`|vH5l> z)Ijd{^-C#c+ud1;-P`>{%sC>=4N(#9bhC58kzH;C{hfHs4wo|-=-P)5xK;x3B3G9xr zwlah{0mjNgmpx@5YC!+>Y=c_dJXs8|otyZHM`dM!5eNM28z8iQt}`5`oFd;k3<) zKq7tL$Pi7sZVUoFNA-9)kAC9qI^nvP^SC?CHbY-KSPp`t)h}?e{)PTmhQO7avX_?` zeEnSE>+c3XlCQrjd}!at&xKw)6FA$AhAlZ_3zJ{oSeT5wWu!lBq-HBtrdN*<0 zS5TVp6;vmE12yGup`rQ%ba~mii7t$c^)PYLcubr)0s4lz(AC%NF)}u~si&v=tPiGt zEW5$h)}}cmH2lvA-g!ki4%^o_-K zPFMzI;d(jrz}+!;Uk+tXXJfJZZ6_$OqiV*j%WH7D-VMiU$dwWxw=6dzh-yRMK#yF2 z53;7DL0d-~V@50H@xCvfTnh;zpv|6+veI=}ykI6g-0V>}%?gKhazS)1l;ec%_Eq3U zkGvS-`o&E+e&2=x?hL@04g6?a ze_$O-H-=$hfgxg|oC&Dj=&djp+D|x8oz?>7~cK{&er+}3i8FgSz)N( z>5t~R0Gw)wMR&(W0bMRk!xL9xIWIfdhs^{#(rxaNK@OH4{olMgFFDs|tpcjtx|?J8 zPajLA9r>EKFX_6MZFu*VLp)u0`-)$0j?wevX_p8Yw6?54$$SR_AiXJdw1hldjj+Gm zpPYB8STG@~m2sU0`gugR+dIc`=k7^dzi|ZI_U2s2ejGVkg}wVWqiWY`tlPK<@k!AF zl3e6Sk}mZ1q-{Mt?Oy5XvgrHLs6*eo?+q@!>HCVcu++s;SLt)r3C4zq2=^j~NY2pH z3VzpuG$lIe4K~G_Ev91K%Fah3P(UW3IS_~56 z=_VGUE`#q#__z#%hr38sR6OsVz3U7ig!`Iu_nQl~u zu(2EoQ^TKOpz{N?)W3tO(l<~h;40Do8iQAPB7>LCX^o*L0!M$_S zr`K6W6r1ALv+uR;uTRH%1$e{$q~I+q%yw9_#O~(0Vk2x_8%wYp0J;j=RkmW_gnN0Iqr7c zE+*)D-kifbdNcRXn_hCg3|)pRkL-@+@n3FF#QW@g=~|IXEOn@O^YS#FKWV|8t7~z# zkqcRK5p+vzUS?>%m`uH)K`~j$v-MZW z1#@kN?u*=mtxi;>I^0-{${jhFJ7+TTbLnw5C!8KzT`)P)4$1V`nU&;$j6_ewgxDiK z+zAD_v2;_&Ms@jow4YpyOXs)Z>cw)Ap&(rCeJNM=sSvqaF47}g^uXKfR^PtvB#5>N zkiL766>Ad}#u7 zv?ujGNthU`tik^3<=C{k0BcHSVD0i**uG%_O6kp0vM?J<=4D~^vV4?p zSwN4#yXg(wN`O5@;B2MsGk8bPd`*t)4Y@0Zum~l9;mq*mCYwBR8z2rhNZ{oz#6lc$ zpz-x{PHAe!-D~U6amW*``|L&MfQofyhzQo9$4FfS209}lA(Gy7Y8X9gxPa{Y6Km26 zHU=*jLN6@Hz}5{#STH9U;XyW7I-Be9+M;!@JIVW~E?$Y)5ZtlVD>$T(pcj0PxH9Y~;Lf(x+fVgWf&a_sb`RHaGIUVFUIc5h1j!eDXMq!_7WUBxB;hIN^zlm7p`!b#;e?Bom0XZ#N-)In6YzxMvwQr zs_eznQ+WAIs+9JE#y79dk$deB&}GoRC5XNgj+g!(^m@L1MSmLxFF}{xtpG4VS2*66 zJh9d;9PtBkv!_q*#ya|&>*{Lahws0o*YjIZ>5MZ!cmV|G2BEx7!O|8FW8%yozqO z54`#WUN3iZM1(pcI?@A?;cf(6R~p?B8{>n?i9tw92^I0(X&l?lPa^0hqhMAl3JTKb ze<_%53I>=;?svh$=~%RQIuJ0XLMu8zvlY3V}D3z?+&DMbM2!MrND{W2B^p)3yF|bD*0-pfUWs=;wA*g@=m< zJyqzzgMJ4OPg{6-JCG#EN^+uoCjzb`JiHv??&$y*H#;~wTf^4Q80KagFwh?d9jy`2 zR38d;wc(`E1k;Jo)K;M_Ew%6?p{Vf3gGF9^bKxM0pdBWr7` z=8%v-DR>JCrZ~)-Wp#7WY`xzG?*RIk(^VA5fqCRuuw4E3Sv5OXkmIc-P@a^)%Ok`0 zExqYqo}xE3r>Kz&7SLsJXn`{xI1_^Rx#hep2F$5!0=(x$td~O#&!3*aqr2s}){%#c zr?b(~l8NSq6s%bmL{7vV*_rHOyy+iKlN|35g2Q(owEbcIGUz9Gx>=)SK@_&Gjv$3$ z=f((f^$9q4EDc?!vT(IyKDpU?0;|;8o%^YAS{4JCYca6Hy?d)3*SSvbiFkCMh(q^D z8cDq0)e?u!<8ipuHisNA0h2z5>-36Z=>+hbR|&+OHMn@L3g^$1p`B;(Tg${^jB}@V ziY30>3F1mu9j+0$Z(OMtE|(i{il2vEHD`LTv*pRJ7thY()eCwuV9*jUS?>f)$-QzY z;ni8Zd&`cuT|7Oo-qB5vLkoQTEuW`r+3~V7X1C1Q44h8J1#!-{*J91uJc6Dwy@mu{ zl97Q5_SMWn=Q;YD5NLUc^zEBmm*J4CC{8`PyPME){s7v}?nUdFI@C9oV$1dtl&qSE z!UZ!Bmlz@7Cb`{#;VXq1q!7dV;FX~JG4Sf?s*-b@fDk`@L=kjjqC62B?Jb;cVnP5? zQ$jE$D-zSE#S7@pnw5gtv(tp;%*`NRhSE(zpWqmanX}UAcm^HM!t6O&D43mzSq16H z&6|uVQ@DV5B$5fP2?-&HjSC{T94IM<+wk}!I>w)l2O=&$h!l*3B!aDo^M;CJd`(1z zH-dxR;OpxMPfr_oc-X*={!g7F87!=f zVPd8a14DYf2&$S|%23x(f|~jyQSX{Zbq!@`XsVEuXK}x_p!4j1qo*-w-3JN0^%8hb@4^0t9oW2WIe~XR3Kz~I@J7i(4H9gnQNisF0Nziz-S@$(3>TXb z2=>tuou%VqeFSim5(AMuIfz_p1UX#^y6kjk&rZkOxtW+-n1P~sQ;?hzCBBcjxe;s# zX0~<~u(Puiqm8XOtZmF-X=MU4GXs(D%M)?>^vJHKrwLt>7|WqjT_&mvE#;I%-GQwJ!T|E zjv7HA9f~1C2V*cf*7jfWRBw3tka!kV!GVD+h01s6h^13BLWoD~GRsuj4gDOr$5` zdj$%QbxX5D}IbNykT$W9AT_it?m~Ha0e{GDQ73KXPZxaBy*Vy_uXAi>>qzJzz$| z|B!aG~X!cs^9J-p2zCP4JG(>6P>^8~5AxPLAPciTL0 z@2ns0wg=#Ln?LS!#N+v+YI^iNOU{vCcw;SYbj`(;j@jrsJslm*DQIm7#hIgdIDKL} zcJ5e=rHiMLrlNRZHWtpyz>cggK=OebC2tducf1<(H8tVwVTOn> z7sNz)%fK6el;j{Wp_Y>!BT~nN?{rNto=jS`vJ38EqPm08rO^g2Lz&pT1UCquCbQ1XPpPh`mXOnTi zBNY!X(4+R%0zAK6j2Cy7;?0vPdUKy5M=X;J${Yvgw6UHy$ML8;8MjZn;&v-JMiN&n zyLC1U&mUHb*yHmjhjFuG3c8NC&?7!OOnaQ!Zzm?)I#1@3Bi(~bT?EPVyL;75y41VPDgl*OkI^=dyw4M5FSx?jlNOP; z%vl_~sDW3Ky?Dke$l66n;SI-dU$l{{<=2Zt0vtM!z$;~uaIBU_cC_>)!L62h_!>S( zH#ZSxpnVZXm&5oi!kU`L!LEz=sE{7V5=H+1Cylet* zIJr$DE|B@4_8fi zcv!%L!RzG&cLCq`!RzKOZHvh@Cv(_XtHZ){Buor`fsx)%(AW79dRjk1SL+w(YL6!1 zsz6s?24MoP7QvRo6Jy7Xg{BreW%V9iJ>A{nj|Q&k7whb~f1J>QP7B zB6!|C?MVP$DuMScOBQ}0^}IVxZ+;rzp1|X)({byR8*ZL-#`P1br1!P|c2iq+2Z8>DX zZk59l@5s$EKsjE^nFa!|92yX?l#4(qBo8OBvz3JrMC_cy3k*{!hg#%Hi}QS)G`T6j zE1=BbpDT3yvg{fubn%X${On;JuC|7YaLTE@b~sHpIT2oIa;Mk1OccN2hM0HmwBXwH zBj~<(09{@6=xIe2>^Ot9?(Z(o?g>Y$8m@Zvq5~UAGux5*$qKtgePGooqM|7x%rKuE zZ%Rsp1m2nHqA}@$`H3i)ZiyLFG%zDm4S5-y&#Q`@WM!nsPeMxcL?lH{Kw`vrB!rJg zeE38pMjH}X{Ryz_hGY9QB_3JXiAYNeL_)L?qJt-j#TLOnqX@hs3A`iVd_}vgaigI|faN@1Jw06lu#~3P_geok5qM7o2Z#Py!JFq`=V0Fl z-T{F4FVk;9eaBMNZcD_T&F-k#;EJ+UE+khRs&FUxIuLx_@bp$O0rw>En#AxW$IB^a zJ>-7hz2@wP#r|Tfx?uA2+ z=wu!7#l0Kl5->SVOX56SUQWx!V;IJ~eUFQkUvI#jYx{BUCWD#dwlrR&>Gp+KROpZN1a&wVkA}g7?_n^JG~qiMe?Y8{ zIu4YEay!N~w6^)5V-9hb#xrG19A1X-z82Iox6CpHL%jx#DKry?X-J3A~ps)#KttUKZShv+aA) z+RE+8D^XjwQRMJ0U0#5qg%Ws;jr)fh*zHQ-mAhTV9NrJW%i{;|l^m~^n-jr2D*~#^@N6o3S8+%$#LGIqHIw-okI%tK{kOmBViI!xsF4W0(iqD__Fim@Iz)6yIc-2NMQzsabk=KqC>_bGH@)y zWZ(^uf!CA4>%ib03MZQ(aAx>=SSo;*TrWuqH4t=N%wTUb9@gfA3A}?O@EZOMV|_Vz ze~^LqduXZiNbXlxSvX$?@0hWp#N?eiIato&9Y^k0LqqMu*ZKnue4N1>^rr=Ho&;V_ z%h}AKhJk?iKOtF4*_x7k%$uExIr&K_oRy5Cf@G{Nj>d&XJKSh?#nbBx(ev^cdR{c+ z9qIM67QA`hg167f@jc zt;>zDW|0~8?{GvzxfAMl`rz8dtx|(Vg6^YxQtO%rx4A_-=e~0IfMci(V~(pzHE3^L zJ4kM~2{*6t;s=H`$67gSfIjzLi*-sGCMN5x7rcE2L-%dYn+XDD!r7l#sL zj#swegu?<-&aDi-Z#hiBuw_@u@p1+vZ?p52L0C9ip2%bvGlAdybKAvx#?=}a+1}bPmWT19u=hgCNgj$fwmub zNr^Fru5v!&N>8NcDU?zW$|4%Te!H=|DdfBY%GSr+UyrtnGNo-HXruP(saaQeVrjM zG*o|trm6&83B2DyOYJ+E^Ch?vct?#MA+i&=!#8It4Eklz3w3qXw~8?RBl>fLH#g6* z7rYxe#ybEM{~3Mi>+re$=V`x+9PhT3F<3d*25aWoVAncla=&h9DtEz!23uS^?t)+G zP5bWo5xjkNRDkvg1L)x~ynb>NPv}vc7ayEFn1RCShH!H>gpHLMY^=@TN00KmD~oWx zy$0t_Z^W*xUi1dgKyZK!!h&7Is-)B;U$mdvAi&D5_g60FP0sT1{lfxy9A|yX6IG8| zgq!{K!C?VEcEvZZbD9`uFf`NgX1a#YbKfv2)X?3vrx(0?MS=8X*toF>OO{N-%o#~= zG@bz6e&C%PY=PqkmJoQ$aOFZRZd}?+j=X_>z9V9JEq8Wcrz`Y~SDKwB$Z}YrO=Lfa z+QkG#&QN$M%hi>#4R|7w)5931k}H)$4GdH{c=;GF+h!Nb;N^Y#S`1kcR$yTB;uS^k za>$`eOxFGS=roB__;})u^QgIY!*P*MEvl70=L%*#a)Zm(Uhv+(cS5xH>Fz$z3tmno zJK0)`<`Xrj+q;Dv?-CT3%)y*_(-D^tO5imRpzQLMXa#A4DQi72wYBEHMiM7m(NVpNS*zrb3`=MZVngDNMQH~gslIUkMH9+>% z$>fG(FfCnQ)M%KNrqYv>qWvHx-uzHZr2V$wK!>gFt`_^O&9$yMSWWB+^Ba#i0&ZOB zIK-0TBX!6<)Avv36>Cvqu8S`6Ktaiyu*eMfwJmE&VuMM zHZkO$YYMG@`a9eH`|lsKwy{1L6ddyB1n*P=udNKc@5OjO1L{@LIONJz9nkF#7GTVnsmq3QirpnDNY_+Ex;?l zCNc@Qq$C01Hb36e_Y;#<1dOMxp4N>)w5G#VvE7ZMPE2%aplrJ zw4JWR(ZkzCxy%XzFBjWhx-=iN3)104;FTP&BnEG4s3lG`u0mJaPF(KXg&WWEneBf~!ae6ENk8u5$#rv*bX@eext4164RyuIk321O~7y ztRO~qvV4rs$wLdB;&WfUx&SU-FTg97XmeKUa`G$#NJ3Oi6O5n=PO%fAph2(S@ymJY>ytsiYoK4B$YGqNFlA?>uL?!yaQ~xz8 z#Iz~NPiO!1Fzvc|Gn{HSZVcbMyd=0a#9!yNq1I2ZHT@CxWK!9((=o;AZ+A zTur`(D}7xL>#^{#Re`6CDm-kIXJhOJ;Bc` zEzzH4o|+h7k(xxB9AJ?$InXjWS<>X>AS=0&l7od3Q-ZB~l^SfFkQ!ngpBiE#6z8t4 z8D{b0;EyTX^5?;8iadU~aADndZD%+Av7BQ8UVFO_Lk<5wNGs!&Yu)F{@Zw$#p4_S= zRpI&F-FWq24_-aoi`S12;2l91uTBcb`|jB>^t_aX9G)D(gInC2tPZDIwqt%#I@HxC z_O6mrR~;|fejhu$1qbWNS+9>nM!Gx3j~gLd3j7_t87HCT$U2b?JR|<;q@9PK(e5*Iqb7;5{M(@6Me| zv3~tLkzzD^P9}kOq5^n7gC2o5J=_|n4y{4gSpx6*N^-q5xYoT-ggKr(I7(mtG`U-X zDSbaFrpw@!O>}WMLBN$K#29`IT?VEsR3PHF3{*bPkY#7f*Yj~{L5j4`MTlhJeRF|8 z$>5c{VZKfVUJ=v1D8MQ&q$5(*ILyHle)PElx&&=re*B7VSbPmHXnFdWZd&|gK{pew z)o}Y3-KZ`zcpG}bd#be>$D1p#yLJQCZ{!&7906VqHE@hqI9>tXk2qdgZ1)4`%Jd$1 zNm8gm9RXh2NQ!qSw;Lkr?q(Bod5JKG7Sz-TSOndvQ{#Ix8VU;;yxEvTf767-5EvQj zBXbH@D+@>1XX&q>KcD($#S#k)`{Cd5 z%h&%KL%#XnFrDxp+ykw*H(Ee%k2KoW=U!`ng}=dHdjbsp{yM#q5K;6dWi zP2)e{s{S8vR{IY)sdBHizrbGkFR)em3v4F+1(r&Gd#C%!o@=a+pEK4T_s(7C^Os&a ze}CaE^w|p^-9Gv1^~q0P68+3C{0;u`B0xcbhBPXO_MZnDe*Qer=o6Bi5Bh|HjlX!l ze!laQ2lv-qe)M?LlB?G?#mcby+aEd8a|L)~q3=<9+jZ zKf!koUfkc0*N++qxQ%%AxCw8b9LBrn3|a!>uSZCS1%Tf?J%Sexn{e;?K3ux63$4wY zuwZ`Ld*D@58H0_hr{HkII?)}=!}+y8b(UsO${}{@dFESzO@t=+jpX?y&7HTYH{;Qy~yEZNBxSNCI5^p z{#gVB33j|vPo#%2JlT!%QtRFvXcmK&AFtu?DNx&POrbu;$Ls zMQlPuFL>XRB6NkMifHeL8CV~Jm!ZotG|)y!pdBVB`t^c0D>DKC{?4K`6lXMec-SK# zzzy;7K~f%XVJ7Cxoq~ed>0)WGk&zzK(qoaG6N=KXP&jybc83gm7$T@UqkWXTuGD#3c{#wYf}W z$B|szZA--Mwlv&s&%xbuQ*rP7blmIA#iPsf2*7m&UxFY(_toP=0=lmW$j=G9cdze7 z_xW-h-j{>?Y-^}050^ppTc}JLg0)LRakz0E4mPgG_RUj}l4ygmV+M=!T$e#heKZd5 zokfrH`$Pd54jTy2ipeT@H7+SNOLBBlzAHOBhAzYJ4LMJC!VE-Stnlbg9d2}QL|5BN zoH()wjr-z#4=#cZg~DH16KjOug^%}<;Qz5k;b4U@Uo*7p#XNg9A=1&9uC&hRR_}V^b*~poA)@OX1gCYtO&%SB7ZDfHWe#Z z=3&`i;pWg+{ZD|5S~{@|4y@5fWg7`7Z{kb{?Fy#AgVNQ!e4lWLh6;mAk} zgM+;p)YX&(czHQ5S26SSbP$tkir|g!58hZUBocTd!fdyDI_T}qwEIWTrtrVxNcjNG zF27Ldxz-N=eIOX%IKf1S;UI&H{MdWIVJSdH5w`D%!7FR~BjC&6QvfgbTx0OM^n&;Q z^FiyMz9)?S`ncO=3Gi~yHTpjCzH9uwKY;HC;8lQczu!mtz3F$BZ;O4|F&R+h`{Feu z$wz5h{<_Or|1A6`d#;h=eLt%~5xoEHdcVNVuCk>#QXPTzJytkVXNk62&gHeig$6rx zAGE`blfiiTpbS0ac;7rZB01n^$As&B`S>6n+&X|OUGzA=Cjm1vIYy*JZxChiCb2fx z#O75oIDTX+!FMUPtaL$A)Fez8KUmgM{wL^ajl!YYOx&lh!zo)_gH~Epz%G&>-`VYv zc+tTtp2*_Wa|}9yFBgrG9ph{QcEcPGzSF%J=MVdc;_FS7j@Y%?2HRI#WBaCLtX)?~ zkEn4-i8p|&r83O5M#5Zkge2Ndjj+Pe{c~~g9ETZpGtD1?0bWp5nIM*ga^)%&+V=HzN8yYR9N1xl<25#-Oec4x zxX`vpR3+=Wu$REQPt<8R(^iKQCn|C5*iMnvuz~(hm+%6LqG^bY5A6ruKKKp{-hOZJ ze&AJrldHZ&H&zj|Z;2rek zzrkeOUu17|N!+fzPZ9*gdHuik(0NI^()b=+INb2wK1ueu@(@Iy+ZEeAz0;&)`s z@@AI|Kn7tictw}tzYuu;($De!CxQ3B&}Epw>!$g)9{PSgo?8E>$4f!p+I{ljpN+&n zBmb=L{p|cYe4xMf+a}TL_nzpOcrE#L)#p*ZEfbv&H2B-QjSC#!y?DOv#mkqQuHJvJ zu~CNA-~JGx1_kg|DMDAaT_rD^^REQ*0AEXFHLOm-#w9*jyT}_GmUyFdr5|=}@WeR+ z@YUu3JioU?I9|n2!`r74cpu+s!0l@_IMI-d!f84P@-v6OuM-0OosbaiNsf9J&T#*& zLkqBNxfN1kl;PxH0y|qvp#UFi9IBgw2e<3R0tJrSid9+!Rxw${F;p%P^M;%+LzW-s z8E^z+k*-CO9`iZIN#K1-;JvsI9S2=SpSr_U*4Vw-4BJ-$K!9{aW{4v2cTPh&gNG*<+sMV;9cxT^aQGXA>a+j^i?98JO}( zGT!FATL!4y)ylyubG2e3jUg?AwTSQX=kV9yYb5YW0GGhq({oi!l5rh~2lt!Mc`^fy z6*kzh#uQ5nP3bY+AAWvbm^fh^h79>dh-W@SHj1I=Tj5#weY|NRB#WrV-9FA+NKM;Ey$zLFYg3@ihM7eyIJpBjFC?8^awY zG|<=-Xg#{cQst{(jmQ5LW=aZD{u|6xz9fAE{qg^R-nh?Ttn@XENS0bd?i%Q-zfgR= z-`7Bnx9^ylp~izCJLUQ?2c^0&he>ZcBeZ{6@;p_x*L$RWecR_A6md_8y*}W2YpWWGx*H4b& z#iN5FuKS9B%OQv74;u07y#_qIy$2UgWY8Ph1Pk+Yv2>OJRu>v!$0}#E9$k#?&Kh)_ zDki7pfRZ`7^d_)GRH!AQL#>dPX@`@IQ}Ot2qX6&Ar!4|#ERNlZ2`qY?7yBGi5c|9$ ztb@* zAUMzoK>;MXQG^CLBRf3^2lp=^@K)pM#X4}CbSOUk)wEVzvUb3}L>8LkbLAnagFU3dbx>o=Gm6_xW=;lYyTC81S4*c3H%C zIUVdC-S|3BX5wI#t!P8PVu2YFpF38IXL)l6*?A>aHrk$2J zTy2lmBU5Evf@^WEeK*?A?nY}XcLLspnfi4ILaE8CXEBpgo;Ok=wcgK-%vmf@>%T@Veps(fjkU*#90lxOD9qn}Ys!sap ziR#2}psD%|wA8+Zj{0}x;zz^8SW6VmF*Vcelc^>Qb%#P<>w6gJ40`5ZtFtF4z;#|k zm~Wo1x8p)>%?Zbb4Eplru)&{U^oY+fX5{A>JL(IJAM*_+O&WzsO8oa7B(jJmDUIXG zXgy};CMS)J4e$27-hWKiR+g>d!Tw*T#035uE1AdGz<*1P3;wq>nbPA!{+A48|Nr%o zJ#D(94TCq~H^9pd^$%w{{C2HgMX}@Eu_hYjEA6ql*aj=+SYmaN74~d$Kxd;PuAc}c z@RpL(JxZW$60m*wsEHulglG2~@Z=uDcOR~uor1Rg1kv4AIK0yg4ckp{Vvh%|cCNu4 zdQ`vKu>x)N?r5pC#(`2xtevlm^$YZHV4EenTl4VrA%XnY<6<&Ra<*p#bl<+>%mD%~ z?aRT-PMEtAqtp9l93 z;c~}3oT~T7p&ED8mic2&K{#Tg-QnSC3}+`3dcrVboYuD?d@l4aJschEE#TYsT7WP!{%ZvW$@0=M|6BY@XFlo`;%)7URgTX zdvETKLzh=v>FaC5!_5j2Vcb_O5NWBQB6l}?iVVEuc<0W|618`w;y7HDEQee#IbPWU z3KLU9Or4gDf*B#0mac`VsVYKKCMzQ~R_S$oxbowuph=HHe8#@?bsgU0={QuZHgmJ* zrjsOxVN!$2KxYI6yCX2jjketp5adDdb%rNF+0|Ywl<0A=9{$Y6e8hb-!=aD#wSIi9 zsq!sBSCRm)#!qxJQI=IH(v=#%7boA82kOB z;X^)uH}sd!Fnq{o7&+`87{%}%^%cgCAB>5U#$p0#=&->UGj@zvHmt0o3=J*K`}Deh z!tu(b=zROOt*xz2`TGa{rwmnpt`7;kwtb-nIRq7e_;E2oPvJLm|9>=xI2hetW2I_Y@VCyPZ ztX$-TlKGCgwLQ zx>qbu<{A*9IL@P^o z-sfvMl)&d%^7H&TQm8>%XdywIyH9Yb%_mRW@bCe5a^8lE=hoskY-`y>I{@_NJq_%92{#Xq$iO@IMZB=_LC(z-?kB5optou?8k)*^#tL)INP>M z!1olvcmIJc*t&fQR<53hqD3+_A2X8fyQC^+Q)XWIe^HNb%n1mVGW|*F? z$_prvP2f$7n}npu@rVf?3vP57;4wn%hP!b{Qb-k9O8kHP){)i1(QO& z5E$$UUvF}~PGiODG&{>*U}^jlOn8Z}_7Bk0{7$%BUhJT){yp?{N5j}ehkhmlN#;E2 zi-PAYV-s$hG@iiwBUC1R4Q_5ZZuA!zHT)j}xa@X^5BUd12=IQ1abpLG5|L7=$g!fl zBNw>gS`FITS_EG%k}hxk^T$QtZS@cM6N6Xe@h0@o<7NF(hdZ!-PnQaoR2H%tuOHXr z`Q5#EPVV*PgL=GrM1XzRAl&UMa=Wj7Jw}ji6tHFJK7ZIqZns`I-Y56><91gOuAEB1 z<&&|vbb>_V)iW7*aH~udmU(b(1Ga+ZP|yi!b; z!OL)ygI7M8CY3|5=+Ro6UaYZ`j&!k80gdl{5`Xf9n0JCStsO7o+{eLYz4^2QB*((At!WOC6g;VID4c{@@Ph?@GmSkKLke7CTotSmhv=z{}_5;O*&=z$?X%`@qYY z9xq?C;l+#dc=5c0-0w+pzs-2`uvOI8?Y^)Fr%#sQRP%NmKfDP?o7SWG@J5_Gz7_3f zcH;cmDs*+!h>CERyZ4DzemuE$v8!Hc`_o>FGxS=vv{Z}E!j)C41bjK7B8$(rpIOrb3GAi$jXcoF`i{?gS=2Ua!rmK_dRYO*iI#OcP5ErhD$e>9G z@tpvF&#~}z9|LcSX|Nc&xI{=MK`i7TCzc=MQ`dv`aU-PtY6=iQ5E_el5m z$($}dYTwz9$G7+4$=w5D`{Av?gL^kBg&y3jru}N%zqyMZ(Hlgz!h;*z zaP@Q|uAGd-wNp`Iyvp0BWANZ=2|3B*BEI`tv zh~VYMJR^VT&~|KDKN(pm25@(?rpG!XnA00ECD9l4yK>OcwiA~KN|(7PI_Zi~o#-BM z;p{eackICROM678;yX7Q!7YEd`-CX@`0ELB)(m=SQcv6j-V%J}@mv8$hN*m_ObR2& zLj`?~l|jlO2>v|2hTz(}&#=BOu9srQe4am_Cloo9A%z+^olLa(dC36oz|&t(iUyZY zem#SS1mJ7r*gM;+==ZI_+18ynb8-h-Pn4pK+%O;O%pA%%}sSlS|m-eZ(^)N08%GVtHRsM4p|xDBDR~C$Iz9! zO^CX?^RlIiWb<;!?M^366VT;t1~0dUXYg{rwZ)6c5icNM&kDe-d_Uyp1|eq(w-EBC z8?!rNqMhl+Y>&`jTLcG@f}KPW9)@j5s7LR%0B?u{UUt76@AdY!g`2A(9PQO%Z8-tv zCSze{Jf40JC6We#RR?C|YR%|%GBY>qg>El+N$hwH2)tZzOj}18>gr=KY2sjv9rFW5 zkNTcOrSLJ>HJvb8xRC2RGZYaPv$SZk?Ti+wIx7 zMY?;T08egL;3-d{-P|Meh=F^P9>cHI;?C7N+`YaJcdpT+`IS91?jz_n;KA(%+`Vx? zO2xW+5RdQH6Ql{mw`=h9ex1;hd$nSG@#{gnBIt6_8F{#YW4ZDiUHQZsyG5Ag& z+}%Oy&dcq67!-TFjQ6mr?;f02}c{qEj6c^6zBGA;LyR!_J zyUGbt`$X%W^C#xx0y*Ftm+AMSpZo5O8a%qUpT0g9G^g+LxPgAAqvST*@%m{4p59qU zPXy&M*UK^9;{-+yJunog83=&Rv`qVh&=Ou|I zmYl)B6KU*p=grR|=w=dZbI8@^lBQuH!FS=}JdwZ4)ybx0$BW4}Q9Oqn^6a@;q6ZrT zIh)RLk@LjF5X8g=AYAlK^FUyro2Y&k5FkyY`TLW2B>B-ccdC#&P`JR$o9pY^!PV6o zPEK6F+z1wQQ!%HTiYeVtIJ{s?HxdS`yz7LK=s2MxWN54{fU9pvPX@9Qk6PNQP*Yce zlJYomu_Fa+M~`N4p>oog5g0R;>+g=jI07(_QX8P3$O#jSmB#br+F=u8zIb?T0|By$fJ;!l!QkB|z{R^c3#hIfB-cyu5WC)~uh8DN~c_G0y{s=T%STf z-6`Pv{O$rg>MJ@$|+F+&>>k*E3wt;)&P~AvfJb=TFnupN0or(e!&a()T-t zhnLcEuQQVNkI?Ub5O+J{=%$!VuLHl9yXk2njGi8%@bvKk+@mLm^M_njio)6E>EQl)H?AGTjjK{iB+-H5`axW~Qcn;*fGd~lartr+!M70?IuGE2Sjn~* zX9>c*sDgFkL=~DEH)BWXA}lQ?r#UZ!L~e9W3g#9hV8>P46y$On zeJ2#njl`njTr4imleA_n2~gIms;#_!J45%2ltA5rwI*_k5YOc zx9pL6stv*~zmRJsc>YYz^{1bH6n)gbC0Ks*&DW%_gueb-8l_`jd*N> z;B^v{Yw{THAC2q&D?ly#8k|nHVMQiZEC@sKoFL4f8Gr@!ShjJg4^G!w;(WaWZgtGX zuXpNkpB(J{8~gF#rZnEXv>V+7+HaQl{IZ6NvlU!jti`sQtBsI{ zyB&OeoDf9LV#}sN@fgpw7&teU7f!q+fXY{=adj=uRuGT%uX)h|uS_F23!N69!-Za+ zaczdDr*Zf8VVpiyf!f;DSh+kI8EKB<(Utp4@tYzx+K<4y45#UFyZuZB+FRG+*ltf8 z-|d2~v&(S#!bY4v;DMvH{y24fIc{{XLB}B#9|UYSYz zo;ckYiknxf@Z{D!TtDT5juX>ypJU%Qa&f)YALmZY#NAtUxZjn6D<^$%{`5jTd3+F$ zu4JRT*&m%}m(z`dZfciO(RtL5Zc-cRcWc7Eu0(Vk4#wq+Tj({~joTg3Xl)3@wM#qb z384zt&V=G*eK-Mh2i+96qPry!$M#0heg*DcCTHL1iUSn^IN!Dgm(MT5;awisR}qcN zbd!Ae-~=vS*oRXmDsbfz0r$#5Q6PugyR!rC?jl#rp%)H6Tx9qjKu1R%!M6tO=l00wV0Ohrj?7K#@nW6`{1%$u8nA_nnne#}qCjA;RwlBA8ycok&E zDI+6RSsG>H<2h*-D3}?KSud4DrN%eH4QB8D}C|;6_B}-?B z);>#?&IEUf;NE7@vB5|s_nVd;Bb1sJjmgQ}cP&(O5{`)QC6~)R*WBRa<1CgTbHy-c zXL7Lgzw78^2}ef@5{+V;NA3=64SNR**xGTAHB(qyo4~@tP{eCFR?8s+9hrNT#M>l- zyr!0FucS`FDxy=cXp||ci%IaGK<;(as9_jBVu&RAALdTN{lys#KMR8HS0}Tv zv#v`|&j_-$wb?d)+?ZEV&$VH)g*3y($TtYlZ;cFzyyu$IqzS)TSeQr45cTK$$jXt2 z8aSQo6OQ+PzzIv>%|`LuC=|_%!2DU^SWpm-HH!jpvc?ka`|QX`<>UUf8r;52j`d0% z?p|ZJyBC)TNT-f06M3(-RRvg37)NhHbBr2EcYeByejxfs89t2ukw|tnhG;#$1`luV z#;^DH;wg9arN`vw!%WkjRCZZTSpZXx*Y!0DEi1S5AG+2t%I*e;%1hg17Kv8lut zb7p7Kv0}6}`C!e`P%M~FFulGKUB`T}vN!^3R?Wf9^V87Y`Su-;T{M&J-D-(4)f>1a&n_yQ-piRNf zjUiaDAP@I%*WgBb0yZoU!>W~Yapy)UF1JRZcwPk7uPef}?sarS2*jM3k*KUF!R@PS z2*N?+5TogPuf?^_*{HAZB&QjRh68JH^}=$LZ}3O%v^cb$s>Fl)EvVVGmcI8if-gOh zbTyE>C8x`U(9dr{Yf~(Jy$GBf@24g(b}>aXU^21Y)2t%ZB4{P zj-IYMGLv1fXg0afTr(`3?T5t+*ac^Z!b$TA(=dk|>$DUNWG7BU4ryxAB;=5IUmQzP zLSB{y=FUl?*DMaX8Af!yGIG;Yke9BCd;)HMrYdF#sbNNzItpj|2=Ep!Ww)CzTK#Za zcMEd49EV=ItN_bOW?|X#0)ld$D2!f6KT`p@^4$CcQQJ2oBLc}O!H7@bcJ982jPgZ9 zq^}4+goS&Nyb(^~F*MwlMn5s>#&O<&Kv($rIl#-ylK$6>;pCtPJ3D%t##fHI_k}+q&!NGo%T^$|Esx!Z3pH2$Ix!n>GvvY6>3<~*w$WZm?`pA@nS1h3TM2z=;0K6P(I8+sjgFEc7dz}^bZ?+cOE!7S< zyT=;m_S@5AY##1jsm6_qmAKYbNp6t0t8x0s9Mo*_!sZeOtekIyY3T-VbDW3~!|8E~ z9%VkJ!6bd{(Wu_&jt&CS#S;lq+8OsSd&CvVxaRFCa(?7;UvOOnZWzh1<+{AQf~*C< za#gK+T=@JL9zQ&R+qaIQ?aVGTG;GB7jq#W>-3Zb2CJGAjMM$t8X67ejU(I|RJ+v7o zj&H|_BTLax;ew_LN1Se6Kn{2nj_!8Hszu(&o|1&-Lxnh2=YhqAfym2E$F&Pf(SFby z3+IMm;euRTI+KkPdp$6d9*NhjCAZr-6D@nakT)$F)s@A#)tQCHDj!VAj7ItPIoMy} zhgFN6k)ED}!-v-3;;Cemt@lHAb_&j&-HIz`7_@2bLi>{7! zXl)F^%-m2cT9i+Yd=d7R(<6Ik7&dNPfJ>drakMTF>8X4ZSc3Kwxv1FSg5>0AaU<&P zD8cr%{zy-Y5tZ6*-#$XuEyuKJ>1a7#MlP74%Z|4mUF~boyvLQE25dzR^x0mJRhe|S7TRYK72fl$lYHAPVx zm^a6VfXa@Spv&N0GD9?^w6K)G%S)V>mdwQB;!JYjL71KILeAR`)23KsO1dS|C!1k% zoH61e4GS5>$=j)9Zy zaM)Q6g|*o*SeT52x#=Xj0qDR=fR{TDOWlWAa`-ZMdE!lS%bIip8xL*Gp-@-(0ZJ3T z!T7OXW84_lcNjPB7mOc2vJbo>#ye8Hm&S}4E&8Y_DJzkKR)3(St@(`mt@VkWwc`Fj z5?LiZR#sLm{sBRM&dIgR?5VP>hKNstSEl!t6#t7=Q@$MMPnO_8_fp(CzlfaH0^ICa zjJsXMxZajWkH=XAk>$8|m0TEu_d*4(chRFRjm`VBux*(Ume1D0+-y}OMT~=^HQiB% zNpO{GAo%KO4#$q=MmVwC250uW;M)0OF$wqNA$NG-@B=T;Jtds)n^zs=e9s8CD>+_v zxh(`;ZlTWLZNa@e$3?#|c60}7GO=}q8S=A?ksPguj06MB%eBI;?P)mFunxx#Z$v|F z7Its4MBP?99BrD5=A+B7cZV~%HaAS39EFW*lCXZMCGv8-$weiStDlZNrH;s(>Q5j} z!`{khRBf_Hc4i>v&!2{URq-fYZ6}twZrm^jhw7rSw%7ralfno*X(*Xzi`*Y9i0?IX zW+wL3%s}Zn7m;qolS_^JW?UTQf_@Vit zTx9*;JS;0DaK-2#Jzg8LvNQ!e*`-d;w8!jONhq3|hDGx;u&g+Xo}^q*kflme5t=W2ym?{#ZxT75Q@c;n-^hrcPRDBNt zey$%m+8M&tE?vfrEenv56(@nWfWS}37A%~M*?HEY=UP6&JD1$^RQegS5|uhu^h_(Ryr0{U_p=!`?v=1{a9PRE6l({S_h zcF~qyl!knAiX1LU0GQ$1E{ckCNk$GaaOp^PzFc#c9q&UDcbs6?#uGuu4;G+yn=Q&# z8)L&FJ*-=xgAEJyQMn}v_4`($seUzf?}$M;o!`068vANzVE^8E*s{_F3+H$vFE5SU zB|VyF=wN1EC}z)@PH*x+6ihY1jJzn?&%xY$C(M~KQ{((5n70gHpAS)d@Nr+o!pl_IWJetnM;q#i_-~=R+vHGv#@Xm zR+OY;Ht<7`D&4r>c-1n9U5l0$}#A>$M>ZvFxGNPZu5~0C%aCV@_WUV34R{w=u z+i18rb1e*dEvLnb8_$AS&X_|tXNGLyR7vcR7v{6bE$3;XxX=k}R_D>pVJa5RvO?iB za?mny{;id{5{wKc33aZLLJjPALuvH)(U!UiI}H=yb+woJ ztI5G@Va(v=MHMs>d@U`>`3m^5oYO0T z_X~^}NgDkvx!+*~;8DGfckI~FP*I))?!7i<%qZbt`vdj&%F3F+`)AGL6^@s)8sstF z0f0E5*!c?mYZh6s!~%-W3Mr5GP7R*i-i4=kcGI{U4{ubH(_KbG3e;D4 zpk|XPcC0kS<|TUAw9EpPrPEMbvmASBOHi>T5&&L7p}w1!8Paic?AVrt&6}ptqpl&Q zX1XIgCj|+yP6!X2gtQbt@%TSE-VRa0D)cxXf*d+8H9S-kZN@V)5)d73gs2b=Ovy?> z^5jqi`)ME|SRXl4Q|R&4oo+~D5f*HOY16Y173GaUUv>H(c62_2_C07{1&Q%)m`eNc z@tz0^R7c8WKXRp$5fkNv$Y6D3W<-ha6%lHU&_E3WYaH#z6VUAu8KR3R1k;R+Sj0t{ zBRW(UY3WI#Ok!lXHKHS|keZr+gt!2)tTsI}3Awph*tEWg9QIb6IlT+#+Uszxbq$Wy zy5dN+wSev+f^JiVHR=hx`*t{>Y2R!dI$VmX@+ow)HAGgLExf$kp|7ti{;q?5mST>E zhWhaIbfcR|5*8LE)3vSwx<%6%xa3yzG_ZJvCYH?7!jb|l6wlJe@`bM0uzn`i(f?EN zTpKLN*CJ`s(~72et<6o95fR9b_R7%JnS`m?a_};AXNs7v-0|km$iTe$shBaULOYUNYS`5z()fip>6`W(jp3P5n>1q zc7(Uvc+u37)Z^hi>bbkq*!vFFqaK+X4Sj8Dz>6ukVWqU1&4l*N%~c3!vXBFTm)))i zHJIzc*l>)jjr$MW%KeRj&frJ-I>T$9i%pOBQCr z%fp5qc{If2*>8bYS8F7;mRQjn+?5_}eb9Agu_#D$_hzGj>Jy$c6C(JMc;r~_4L5Klpj75PY>noYmjY32p@55Pv;_Un2Z` z9S9y15fW&M!~{NX4-e-F1ZEooWh8ujtl;j%HDp~79UTfUPg8Pu6A@3)jEV||i<2%q zTqYtmHi#aH{ov-J2RA2W`dX2QjP!?(r#5^&)ad7orfUM}>sS$(O_2~Ef#k$M%$$*k z>C=*to|cHk3#Oo=Y!MDNZbI|%a-3?}f@Axlaiqo#hj+Q*&@NXTq`wiz!}pbWqH*tB zG!dwGmgS>pwkLfJ@AtsV&>j5CAOT)4FE`AdnL^(q9mVrP2)MdfKrVL?x!lDw3AzN_ zWwW)hYz|8YtBT#RW%C?t+>nowd3IP#FlH^Bp@o7RO-xJGAh)UxPZt$(y-LWN?uQjC zXJPpYX%dYcFLwpDurx;A46f;rfZQxYf~_ijt}3!7>)eiywyp~gby*u6=(5_=-MYfc zTS64V*3B1zenyIN8xm}*`_<;aDa>q^r?+#pSmjHb7$T|Y|0&HBHk0pyT;qGQd zZ$J(;{0{JH4#%d&dT1&$$I)s#be<|C@b2ve@2?Eo$K-l{Z57!L0=y57i;7&oK5mtT z7n*SEMkB6YYsBU5{pcX@a=z)QQ`>QHDh?bR!7Feh3M&KnOiL$3%yai)Qd9ASXKklapdFBQFUn zmgS;y=MvG0`C!u)96!1NXHKj|+ey|soFSb!whBj^mgDfj4Fulp*j2Lt41Hv$s30>*^Fd6IX?>!H((yFkiN{Lj+8x_n6Mej5XY{$) zNZr?(lfHqz+E*}8{|b&q-@woMX9UvUD2Uv(T!9V~>G&Y{SbPgV%b%VG*^fIJ;xMU^ z)W8aMn0U~|aA>!w@>lQdw7!Is9_tG@>3d;^^c-}IPk4Zmrir}8iOt%2jh6X>GKd)*2yqq17?&+N)wbgjU9S=*YDq*0Wd3<5*t0LXnQ+ zW1?M@(}GRDwhlJ=Mke_-kCH-YKh*3y>$US-tu9p`h z5AGf&$V&ad7{1)Rk|)qa3wVO>qldg;g1Zbih!6u$4qd#k2kmXuV#b{l{10=VwSDBs zcdbM@x%%y;#n`xMzL<=eLeNQ?>`#yH+6eMfM@Wc+m@x76R3pe4!o}5rpkWFpyGi6O zP2l3<2ull1SeuW7lcO0Noor!dszm>!<3xU^y}dQeOq9fOQ70!G*xH)G)Mx@M=@HZ2 z-HG;1>D)NjSgFz1b%u?N30*${Ru&rc`F7-n^kHH+7B<#;aHj8NZLJS;lku>#HG+eK zEzHfd#pgRZSip|HmywYgT|bV_S;5-I9EJueFw`GUU(1#rXH98;BDt)I^mE$7*3JS} zmRcnKUIch&OL%+R)6Yflr|;$G>w<84gieSL5*5Jm@_1=(Cg#t}!ln&#aiXP6^sN&O zOSz!^p{)YW`{}iDaG;~;AkE!@7cb1lI(i~nzQ7B` z1YH4Ka=9gQ3A%+kSW%>lm82C#dRSNDNjJs$*uIruy4VrR2*^uk>j?NRnyHQX1n!(< z4RZ6U1bSs;W%?6%=aLG^`OfJDFE5(N%}>Luf>>my>LD{x8Szo3MZ>*+nKODr+$`+vvJU;Z0@`Rd%(1rfmC#e8BZ}*Vi3hDm!t*=a6fV{5=`hUoJu1OszoK*h; z2bF(^z4E`qR_WhiJ?YGW5zt3mzt}n^NlDVN+R1ku>xdE6x z%@3>TjdHTu0;g+j(A7K@*DjO`w|k+jOzK5;b|*RB)#P|*V#6wWlw1&xv}A93V;lDa z@6QU`ec!F>_WbJ^ngC zRZSTaCQcx6vU)%9F>#L6yDwAkHL`O9?Tc;s=h7(GK>Lcr}1XZK1GGq2iNj4d1I zU}ecPa<|h-Q?YzW4oa3z!|Ij!*t}sTRu}sU;4UZNt{~ttY*)?G#p?NbSS8bjA$2(gFUSmwlO~K5W z(a1{HMOwTPB0}v-BRviFrC5L7Q{ehH94eEy{>klY{quQW>mLDD1t|ho-kL@_C$;!_ zPrc_A;oDF2xeA>pWZNWJ`y9odYus|@J^0GN%RSc|-|M;dzX#~K_A%%VEU5#$xT$x$O^0-u9=j^$-8tG|GPulKgj7-2OoP8Y#T4^4GTS9PjtN=A!4?LVLV<{ZF+1 zNfY3;y%iH5My}!y6hi+4&Ujb3!u}^dk3$Uy%A(M;-5Pc4&9Qr(IreR`L`#(&+Ujh{ z@!I2J%XD1p0oipv=QmPfgmFI9efZb}0w%|0eMMFZ}$)z&+O(406!+!9aG5z}X92`N-GF;Ub5~ zd;1b_d0P=yQlm?TnGC!#*!6+8ujiToFX@A3mm2-SJJ2|gH2Q&8g0CWU<=~a~UGwb) zuMEEZejk?ncYOc%@3*b6-}f5IV61SR9K5eztrg&X_iocW8CHM$gTZS<;QhntWPbp> zzgIOom!qR)IqqCoitA?=;d=XG+&sSow`u=c+iYAqIUUzKR^n!NrI=j1c(xSX?L3mR ztjoaWVk0b}M@Y`&O^F&02P;_~FTHscU9O_|4X&#>0-F{aqG5*>4p-XaT=N_P?;hN` z-h_L1juCLl*^=Ysumdk~eQ>W?0Qt56?{QgI+u(7R}8S^e9}4`uZ){ zS+SC!TZH+G@-TDu6lCR0hKrjm#*P_AKig0E`KKQ~5YG-Pj=yz$pmRJbs{gSM_kVnE z|Gz~)%A~k0-~Y%pJYng@En;y#!u*n&5Fy-D>QqU5(u}D^X2P z7Zv48NK3^cjvd<yXXVS31|NGaCx!=7#TyFaI#q+ecFJDf5yOIpR@E`tN^jrJo z>wkmE_`kr9!wUx7%Kh)4M_(a-Av(^m6@9?OBk&tZe-|S?Ucd9zQE;%mj#e?eAdS8} z(mBx%o<5Jh{%b#$-rq=nf9<3Dx7XbF%v}JNoo-*4!CCb`2)Z0<_zOXoTf0l41}mk% zzS9%!-TPqrK3qR74mG%I|AW5oUtfD^|Mj)E_TMDwNb-@3el}m3{Pq6+N=RQO+NRe- zZ1Wgk@EJ+At_fAj%qj#U*?S^g|3*AVgXktHH;WOxYt3+LE9g^`Z^P^b7Lf08ZvR} zUNNT|-(+ zP+m>0cR4C|E~D#8gerC}6%b~SR#mP<6`g18+O?XVM%IXN*REC4HmRz56`dzl^Y&`7 z$fKNqT~5ZJth@x9mD=Rb1 zqMPl)g^8Fs)e!laYM7p`^&~mU>{xb?M)T6iYDY@u+8wE^h&;Y!bI8TmaE*65%3ncS z=?my8e+heouiH&{w8nkiW2QCYhBUeM$ABwI17=3rcY>X@w}rcEua9_N>muEB zou#`b+Cy)3jE62sZ&i$^-pW`Zeb$OtFZ~s9LI%r8C1Uh8SjLJMGL+;aw3N0b(RPBQ zB|^SNG#V{Q^fg+va;}Hz>DCpRM~|)gW0PxXS=q8s1IKv(8+xw&0cTvZa|JGU?7++W z)p&BV9FK35&8XkA6jfz~^k_Ll zEEI5Y=2{KIFpMi9iONTP<8ZFkFnoxJ0dtMk+NwopKTYnrqZ*gHYH_7|kJS0$dL!=M zIzrC&s2K0vCAUlCjjO!Es*&985nQ?4g!3JBQj3}sJ8|r2DGnaoioN?b(HnIoN>-6Vo;9Jmr37dII@dZ-M%KYjp7MJXOvJm3F#|LuX)|9t1#e!zml6qIf$B!{{{#B+C7FGCHhY8h&GmC!yJ0RnSnc`?Dan66>xTP##n zu@uz=U%7TwuMn!PCJ=LKpV(d@YED$_BoT1s&@CgkTvoOeJ4g)Pty>q77Gn!()20Ok z-1%b3G=q2Dh6Px?mcTnL3D(wTm^~*O#l@+Zn`erG91W5>ax=7lO^!7=5fx^$Gc4Gq zJiy23ptJ3yJ1#cEd%T>6!OLkVyq$-Mjue4Ds)z`8MHJU=kS!bLw6dT8bNIN9hPTV` zx4!O^t_S*>)&%<5Zt(T8+GcC1eoRg2=jU3g--$kI`kLQ~t`x?GqhW5YO)`L)8JCUZ zl9AdlGE@@<({(lITJ4`++FGd}_Vu=39u(+4*WJx}mAdNKw!wqGd_CkBsT0MpAyONl z5ktSg$WenyL+S7I9e()XJB%1Pl=eBDOuyC0$nf64VEt`bSy`U(_4WI6rjw;*O5l|y z*JR-RBVmM(ETDKVuKPQ+i~hk+9mvGxqoL?J7>u(A0?|(DIuwixq^@HLxOri{1YUBw zT=r1{Zzay0*oK1#R-X9cXIYhWY~=$u+Ge7qkQmi)UbZek#&36A+&ijfj{K*xH*bfcJd> zD()*DSJXhq<@^1|{!%>tv1^26;QOS0>ze-O1ytYHkNrkzTLxa)wgleqF?UuxHm#e9 z?OW!eyp;Z539>?!O9{XP-d*&6L=a}kR#h&eL-jIGaREv4-*S0#*Q5;YBfw! z;wopV&j_Gz`e3T)d==xo13O{@@994+cvIg4?;lJj`^2@oelw$CAYd=W-t94{-)fKA z^){$jWrgb1)@ayfgVq{LoZaVwYiAeY_T?I}YOVX+PLWo|XNy^r%@wPG!eJ z6fc~D$pl_MA3J!u@$z9~IN2K#aE;;SYzkj5Yl5yT(vyQwwzUu^j&4EcIr_R6_u<-Q zP7P}mlWVtc926623||4>JI$g94%ZXlYp#>yy?m(&9ql#bb}IDX@G=Cr>x1mM+TiFpfh zv3kuMEGv$}yqSh5B>2uI*UM!krz9yMHD&_h!^R>qU^GH~Mk3gIq*%2U!L*9&F{>%!P*0y*BFMV~fJm2aS~^fgo_euar+dDYtIqPsA+0vbKy z3;O^45#z^=5G&WXSUT7CRZ&%jo}MnWv@{vKqMgz}Q2iKe6=g}__3`!nvxD~|dAuKk ztNgg)`Hx+zsDZBMkyKS$f;A<%SVWJLMYEDHuVAtmONv5qtil|pciZ67$voWZX4rBn z*$x74xtL&UYuSjVeaq>QlibMWLQx>b*hm{=Msu0DVHhRqehv|3B3WZb4ac~#BQa^> z7zFw`qH+HkT<8zp>j%l*9uX61x2`wPHbMB#adGU147}H_^28cB-u7CYZmq=eW93qq zVedNZpf_mA$|B61Jr&v0Qjn4^g&9I414a40G4y!WKgO#FI>mkYu}>WzNCREh|5*P~ z@w$Pw|0yw0d$;@CZ13?8_P_53-ha@~@GVl4{4l>T8OxVsW9z25Vx=309N6*hCMUa_ zT`Y~e$o*bKc)@=-5&e2{dV!ktGX28zgO0)r5yM8{_t}DQj#o+{BGt8N; zgPBt_Ff~OL>2XR(ikKh@d z$eQ4*3=gN_aJ3r(ZVzuSgRhk_0oY_HJ?SZlTx>ggGa)XcX=7tdj@*bqY$zbivasN` zM@j_WUqqu!Mfgq{_a!EbA&vb86UGk~Sviv?jS-qi@1tSEevxW5s7#`BoC-MZpXj;P zCreAqGd@0lR`6y_ak93xxz$@1^7p`#^?R@TloY>)0PiwvTQwQ0=X+w=9CwtERu*}n zbcHKgDtQ5g11`7D#`UfWf^Hcuv`H)1F0_^6=)P$vU+a#ID}u0MaVWAgT;Srw#mA+| zHTgtZ|H(BL*J`NRo{rPUig51KVsxM1fh*kyaFqaj^ZFqnj_I;)-8d||CS1L=A6G6N zAn0=a*aJ9wwhpbQs?gG0POf*Gn3S0_cPdiS;*gp#8JRh01m8^f2Kd0u(+#@1n)H}9 zvwfT&x@7<9(5k5QMmR2Clz=E=xFH8F)GT5Xtp= zL){SIZwYS?ZMZwDz{Oz_ob6TMqz0MP3BAbCH&}88T&REz* z?p1QMoWVe%8>8Ie@;-+aINZSD1@2>U~ZH-XKogqOGD1o1f-`&iGo4# z@iLf3`jR-F%k_6X5gO_tjU;Y-84|)Z8@v!4>@Iq<`TIM=*VhqVUUqPEvx19@Ih>sc zwvG%~Q*yfuSaP|->6#E=rBH(;12J04;=bIc&BTPkt0k7*^8yiVZ6#=FDv^Vo2z9jy zP*acu-tl6>dgRClrq5 z$Sq@I6Bkb}?>}cD^b`SJg;0YcApfY|gXkwDzee#|+TOKuIWC-DhsW18;C}aN-0dQD zuf_e#>u~4d8re^=srjAYu}0Hruo>i%nl24wJ;-H4KcyvU~M|I7rb)F zifvhvz9M)x6`P`=%pQlT+z7lyq9+@>S_Z9fxiZIlleW9hZ$N8fBu+KO;mon=IC*#) zjyFxkk@~4<+?$PkHJRA4B_1{ z$|P^yBWvHoZF@9Spst}z5LA-d_9%~+dbUj(hlvx%(j)&EQ8RbkIJrh)>{!;wUU9EB zNh8RqO5wSYBZp!HxBDTWvYTZWJ9H?$Z@8@Lke}(jBZ(KdNCx5u`d*_%te6~hkDs4= zH8VzATQgKuRq3>{^2GLu6UVntoG`9^5{=|?XY- zb59(ai?-%Pc**@Vk}%8hr`@t2rR92U_);>?%?_{@X95JAdiYbe1BV7^q_dG z@7(*>C?1n<_y0WkvHr(<#W1Atqvt;+8AN-5s(Ack*N9Py^?v!q=lJ&Pzr)t_X9RnW zKy1($B!`bhR_p{6<)~r#99?WE@kZs&#UhQ2B_`cC-YX{G`eMG)vA$4)NGVeYHE?Q~ zJgb4l@!fJ>j3LGn?BMurX)!@}snE7*%sn2=453 zCy`kow@VUESCyUa1QBB3<=je2W1*@t0Y-)zB9`pzWYH5C=q14We?JEJNKVgkw(1Qv zEJBqWjsxls!uJn~!F#EFE1use!{h7Q@aXDRa=+W~kaYLb7ToUMirbeeas6Ty0e3sj zpWZ5#3wNI0j^;z_=x3jYb*rXheqoBpX5dF9zFW(ku3U29_JUVu0?IbT;&}Zu5$Cx1G}QIZCxNT zQ>+mYVuY9|J0!$ABQDMdwsz!jgyU5q@Jcb>Uhv2?5d1#2J<$Hgj&avmK0ffd_w{?O z`KP1+*Io^Hj>8O+7{UU)-+T^hvq|uD)f1u9Qx;LV|4>$9JW1dnxDgF6kY& z5_q?4;mI{=l5NxG1tQMNnGWoHIm=L8j^OY^P!P9< zcj*m3czW6r$XRx9W0hBo0y7acIH_Hr9r)79k0J zSX$_bNjP@4W@b9QVF@!+UAoSIKF=5~&IH~7&;JYFk9{zBImRn$HEdi+@ER!1>wiYO z=%2b}UnV*lg3-1=5FL%d=sXyL3x`6b@klJLom-CUUDf1rcL?xyp4o=;ty|H2kRB1s zim-OYG|ZoyOm|!}ao1+>$^ommbXXC*To!V}A|veIZjGaLAvoW*85hqJcnQ9o&ntoV zfB-Lp_)^zybhd9oN84JopI(F0Cs*NQ^9r;aTaM2e!>wm4HK6dDRqp)3)R)Uy@r6hN`x0U&daG}9M>%?Uyd>{t`Kouj`40U<*`JB z78tTyWnl&euYfIy>+&vGn2Y%f=>KxTR20q2#_ZV{BJP`?pMvSrlQ3mU9MaMw3AEt? zv~dhm1}V4s;h1iShk$7aNrI}IXmA-6Bx`c%?+iabj`2Fd+uK3rlo_nn0;Z0RJeg)H z#d6|0<3 zw!(o%M^vqG#Jaj_W=>~O%*JrU?UyMNR)31#Ddw5NS|yfih)~OsgP4phavsr8XD<~7#xQh z6v3+qzE43=ey!r?C|<9)t+=l^%B8q3zrMddb*@(o%Ylxw20GUZ*xwdA-Y-O`;WOBp zk4Aup3gW^Hk&$458JV`2k!6X394nM8io{N_N=XQ zEMRME0UHu8sNiy$T(!*1+z6(o1~4+#gMpzAK}?G8>gZ@laa>JRdc;>2^8p;cl}nYS zDoI6kl4!-QtSo5~{a;O-I1b$Dcl`Jk=gQ-_qeqVr8pRUv-1j9~t&_O*I*V6$ zN^xG!R**6lSn?KH@;EQYebv;)!-~LdXKUQ!>np{0BO@cf3JeT%_xJbr@?-h=dHE{J z_k9Hf1eppr{h2?K)2BFd9&g+~TdU!B0r(S=eSQ_Wh)U8LdIXz4I}Nkxv1?Xtg3z+U zP_$H8ptZ&Z7n`T!x+n`-h6^IAp^~9RFxN!3z~|>^HUKM?MZiV1MyFz2-^PQ z6{nydtxK9PV`i-h)C{yLY3tDFKJ8Y(yKH#&RjXyKg%; ztF*xGEf%QRWRC4Cjj?pD9%kieAU1pgob86eKz9(m$y5ovx+3pU5xl=wa!4v_pz{MA z>wmoedHHt#^B;(TIM8v{r_RYFkKcYud<{EYY5RM8@%caS^;ds|t;tUa^&F1qfKf;a z9fOSMaVW@8!J<4(tX}LPmJ(NpaKmD7O^50#Y4sXQp3ln=mR7FOHisUn>Hm+9$zr@x z8X2dP$ycsP>13QrCPEF{i$z>_yO>au(#f`LEf$WK;k#ukx!x^{MPYVcGMq(@wxA#b z1+%j-iQJ>vU8G+Kp|qm zlEdYgFlRMLONlwNLB5=r9IgS!fYs^7AURwe9hKhrue$mq5$|P4j~hEeIAn6pJzice zy8;7)zO}HlsMFBYc&e_h_ChW-b=4QDYN{{PSYn?<+v@7-FLboE9@*R5S42cae=Eb( zpYLOG8aZADFBd`=dAz?f)bM++>n}x658!xrtck^%B6}>GWsMCB?aBE%Vee)qoFd2D zx|{3qPQ%sneBNXAMJQbxjFNe7m^0lTiP1)|w^0(4YjVKK%N8m^ zm!+pO4yEhDaCCnV3d_ELivtj5pt-MWj9EY#dOK_R zBUhY(!lE>Saxz_?i0Qd;1mh@VW^w<#NTj7jA~`vXpd2E?5Q&MwNTC0tgv1a5X^!#6 z#Q2FgZ)BtgLPP8k=x+{xUlaKGTENH0nt*I4ChI&|p7wC};NtVPa3eswx$&f(Rj)Ya z%Q0Rl1&!mnTCg-%g}JE`%uLltngnHSDXwcwPj3Weo{-~-xY47B3-P|8p;nK*z0ENT z3yW$M73G%`Cr!e{NfUb|uirdj(gfOP@p1V$kwC8c%-Y&I)5pj6|0zS&pX=iT@G64v z_vpXscooF88jkEv#o-EXH16<3>mEOxYY0T=!C;(k3PR_hNL)R;M6`3~$+b?NTx*lY zgEeW`w8#L9a@8>-O&ReaV_h$FU=8v3=VdgoS#+ z#nldxQJlw{L=Gqymey7`VMVUY-NhPt)6y|-?o`amPsilMaCm#zB841dS?S`wI4`+XX>o)s z#@icOASvYWiVy?GeHHU~D>C)gOgt^{5e0bEH=PVA5k>2>C=CgffX27!CF8S4DV#dE}pHhtaEFwo~V z?(!@MPHUt8=g}iDNogYOYk?dtw|9S`rKR~sON&D%e_WQ97JuHAYjW_$Cq-h*AL+R! z*KdKB&y#r4uIdAaE0b)0H~oWOK3|TP4|e0ptx7z)UV+CqtMK?%H6C26z`ZM#xO;WC z)N}2;w0iC0xpH*Tcx+!Twk@|u$sA+MovMe)QL1pT=0f9g$J@7nqQ7*tMq%?ZJJj!V zM`O7I&K#YM?oRq1-3M@uvl=e%C*bZEG2W|}_M!d6T%4$nLi2%e9Nim+!*!u(stG~E zu3*$x2V;L_Aj&s+W9d9c#{a%Tqpx?27#AXu1&-0Rrx5M=SjfT7PT7YPSe2b zsaz~a9r+omn3|%3tVF5Jdvf$d(ds=uoD`)?!1X~g!B;q6&T?San;0q-6XSufKy3th zjV9=hfUnzdQ8dSs+r2vsg$pkswiyCv+fi_Hp_`VNcW0;9k$5x>A zXc5kzUQgiVx(x)|s|N|V4Pr3`!}s#V8nhlv!qFN>9Ikf2!76(+?6kxFGF$B3ZiBk5 z)~MNRg{>>huwaHBre|m(F`Ar+*LYZ(jTA9nU41Q#A3v%$#w!P)A_x_MsCZm)zrWhW^Q*xGgTkein#isTf{n~J5y@hHkSB;ZQW z;OOdA(hIdmDg(o*6NpsOo`uIBfmVwtu&0ax`~ zsH=PfHD%V11l+OYZk5U1P7)Jxqec$Lgz;ku!XxRuHw?T&^L?NyRwa{<{R`$u`<7Og zXT1Ns;LTK6GOPgJf!yhP`~Uj1Gwwjqb!H8oTwjd`-OF*es|5Eh(nz}1xePZtSK`*C za@^pRYwUDoizhh7+j@K>>g$#fK<8uI#scI|i-D7a8B~JQHV*=i$_m zT(lgVhNBHRIJ7?-4Rx8=Q=NuQYoqB6V~0RLQ^du%lWXx4@j4rN^b|2(dL$bt#;Yj# zam90r$NEe0a}}>2=(wWf*Yy87zvpxRkQ87l^s(b4`NW!ho0kl8jMv6O4PLGW$Vv^w z?7VOkOb^DCR8Pc&nqm5sKoR5JSyn8v8|3wOrF>q_<0Y3XE0801ytTsdO5q1y#a2W6 zQjr`^FXNSK9BN>v+ZW?yx63VlqN4)^AoTRKF=uWz)^Avdb)o~sT&!9>o18G$<2A?Z zIa9Epkbd5&+M*sW19x_g=DYkX?I$@Yde_q8^{&Q;Ydnk&R(_ipF_E6uCLl3_z#B&3 z4H=8r2t6bw`XgyFxm>Q@5Ele)l^-4Df?(f?2qfqRc#eJ(;5G4%zn5yar;E}Rd#lk; ztj&h>FmM^X_LjfE&XOSPpdsb!I$Mj$x8B+fcE+$W9|u#zpShA*kE!91CsyWTyKO8c zo;5ZYb%h}NQhDOHP*akit2*f$sIZiNCg@HOE9Qm{8!Y~w!$hry!5BAg%pH1to_`3| z_W}E{^90_uKRI}9dyC}!Rvz!C7g+q)R6~y9)V@S?*1Ms#)(NL;ozb?}8Rz!9kX&*8 zU`SuBhIVO!t*dRji1VI4z5$JUml3=dpmcKq7R^sXGX1mqdRf8E*#wSu25_*|hm*a5 zC=u!HZjR7Ed!!_Iqipjm9Bo=n;H9rg(B+!E9BN?jUg_rCU2?qg$u-jDZtkyEj?Rwl z=s3F-ZKpTk z$f@N_NyglQDVUj;g0$oa`1{x)H6`@D7%$gs5DO?O7NK(ITp9}r#6^;-=1breWg%A) zd`oDb{s(L5bE+BC^!YSal3U(M02g_@vKTLi7ZpQR-_P|V0u@5xRvxDp#-Qym`cygDSvbya|$L#c~{!8sSZ ziSNSwCE&&ck3n=0DMSNtv7Shf70cn$kkQdT2oE-pL-%E{pKeQNu+z%05Rdu60q%?3 zoUOKNtBt*_r#Yy{)@%^$%m;x-Tg%Y|UjsNg@-1ruw_ajQIK2F(bYr=zcAv!kS3iDjZ@MFD)w`@-vi_cs1Mj z9y2rJlg7q|cL##%?~$dY#aSE!p#}nPoMIlYJoeh(<@VR_alOCwHQp2b z!*5AN=?WjLUFd-gi#@PqsV8=>c0)_0InLBM;_~St-0ZHwr4EkqmV;~ZUL>`(Y(e9` z71*_NA-0g?O->9DN#Dwo#t2QCFiJRG9@*`xDA6O5+5{NrsbNZb2o5)_!MQW^wL15R z5X0r}{Q|nzE_0lhC)Ri&1-o9(r#jV^&EeS$2}O*SYWQY_;~cG3J=FN~KcOH~-n^7`>x1*9c``uBYOZA^>%NQ$G(C~yHRow}*1V@%S6M&3aXsT()R|s zYX2M#s)NOj_ifi}W}xIf~@9U53-(jJy<~@ESq`PLT%<<4Yips6lNHE<{E=no~uE?ksPWVR*Jxs zgK_AXT#AnwdYpXUyYy?1`$aJ%hZ|?fVLIHlyia<2ey;>y1}`VbnLPeO*qcp*ljRJ! z5r7gy7Ne9vR+Xbc(xlIc8@6`WqPM4koNuFu^K#CH?sehlTwzEu!1|ReLu_bw#rD2N z5lYzBTaEQ?PFPFFtX)pWH5o}-X@qr6X4upji>>6Od9eiFIE#r5hMBoBQqrOk6zl_C zT`go}L=%uJ(Xp-ptJc(_wXGakIdL$Tm3J>Ik3qJqyn9T9`SD0E!(-(hqkleCJnqf8 z9cFKS{AbpipMEOB+IB0ulad5nX?s9shKta< zhHsSl;M{>=+`7C{>@Wg_uZtxVai3BHRs$iT=pSiifQ|PbV`K$)bmb8is?Q;+VWYpm(Q)9IBzu zskp5;Hndfg7?VSB$UY(YxZ*L2$G&U7f&_eJ;|yGRD}nb@x>VMLyR#8;)BVuV5P*(a zFXX1UAUx1q%#%uK9k%o|3IK0h9g20026PprFVxYfkJSxkSl^L_j& zCO4XsN+-%}Bb1OzbI3vG8l$$@7;Uu%SiQmtUF*vUx^-x6Ero-lmAG4PWUMa$p`xNJ z7D`lBWf63%g(GfiE=5LWi~w|QK{ARQszGT&FPYHI4>{n z{k9Sy#G@w@2;g--hHUvhOOeZ0I%jp0`d%dQQn<@zr3V7OZK|> z^|7RK^s@5qaw+^htU>R?p!ed}iXX@2-9M6*ckdMC-B~iM{_>9;yn{;r{2K5McZ_`O z*F1h0@jTv(2ea_tR4DG92*$;|0l0D?P~>U2ciay*54n-!E$IjE-D{ggzJ|M3H{rz2 zIIM5bMMHraic^<~l}(l=v&iwj4O*7m^>W|TU@p3w^l_xy94Gs1aQ$or9^T#6e{=2m zGoHVz7~?&Rhxht$|4ujV+}bQ+yjNv0-ZQ6HrfWMYvA(m0KGStrw>k;U)h1}F z&_hd=9#&T9pdwET#RY-L&W%M_xF;MrO{2XP9Ax5@js9LH$WKv6U5Odm+w!nxO$C~p zi;D0FBEF(7w8g+-@aSHkTkhLk8ab6an7MWL>1j(G^gr z^{yaS!=uG+4BoLI$EyHdYXROVBNf0)KvV>-TnqrkKEoi8ATpc=;3`Raj06z@TbA7U z$|VDs9K5XI!0RR)?|;CF!0RA$ytXpOtFOu6eV@C1mlVPKhqu7n4_`&-viiX*lO9Xq zZz2tPFZg{>>?=tA9tDc`Ns_$JtpIQ1An?ACVfB}P64SC=tZZ$5IakBGK>HrZ?ipt6 zed6-&Pw(%*KfXPPA71Xlcc1UV_b>P0yD#?Ot7m<9`KSjkA8(g(HQe3~&eg!nhVN5* z{#Z47JHyaY=Y`5bCnQ9h!q!Sfgc>B+@;u%F*Q*F#3zKD{H2k^4skm}75BF~HbTVGG zc7T8@kL~h2UJf}N#O;fvxO6xW=MVbh%zi(d+~bR5JAH6?yEpc4^`z%=!{#+kXsonA zPMQG%{ZwFKItQBSGoh}r1nQcqV(q*XY8Y^>Z)@;AIh5o#*5qTuAM^H@;=Z9{|38r; zaNi-x^%8hRjQ2y>nodK2+gwEYEkr`dV&o9W$}`o`P^g2p24Ae}C`C(CJ{lXcQD2{p zlG0QpB?ZFQ#}?jR*6{bWK}@J2f_)YtJj?+hVcziYw1bVcIV>$q2Fb%&A4%a#~H>@%JBo$p2^S3Ukbv^dFc$_J3l=xc>>$ zB?JzGj}c(_>D!`le*=Q00bLRse)^9P zp?xer{ZD=hFdXqW(qDxPM*P)J|I@#DX@B^WJGoCc4M{HQe}uEzAK^rDRQ)4C_YbgB z{sU~5{Q=fWe}I+p$3N+7E5CUcScmTq$V6w!&z`!Y{^qUs>0f_%%uLr`IPJ zzurK@k<^al_Ah}(0}2|@pCyf=KFL_Ly#423V`_~@{yCWY@@-i=R3WBg{@hvb{QXy7 zuDSBn*PSaaUs)Y5!|E^pFnHx@A^Yd?%0mM~!7J0C(7}7a`)&;%YS>HQefDqF~)m34d?bc zP1tP|)t*a^K z@y?$s#dzf)RD`7>TnG2xKDHlZ!)Unuzw{Wn{@usDrC~rTG-N-+chtyFFn08Zup#jJ zxy(hB{}QA|Dx-)TX=S!1YV)|NK-^r*OI81ST)6S2C?A9U zg)zoEin5%x*VhN`$!MG6eRwFkfNWH$BZj)Ky>@t8k-B<4*U38ncHux!DkHzvAD_l*p7za4<-uW`Bq zvM@7z>TS8m#NTY1YJkvGsWqRb8b}I~%VL^pu*GyqmeW;3EN2LXTFy`jwW8Kav?^hW zvYsi)YNkrKtk3N`Wy6|9{aGpz)UqP&W~;PTdM-P4s%e4@r@#IuF_pk;Yx8Q5{Na_tA|GeE)nEzI@n%SNEIo`T@11&+j(l#ho^M{;(G>9_++} z8+4g}WfSgP-7IweQiIj4d8n&Oft#z8os8!b&X_JaT}3H^*wkP?dRi@UbgLsy z?exHn^9^`-{{S98JS=Xo4a9hl;~DiI+}Vg*muqqDTnR3pDUwy6;CZ~cIB_rshxTM* zLj28ZP0 zEd{8mOhrykw8&{266OOd8&i>`Ywq0HqU95yQ0pFD?iwVBvqzd718N@BE<1AI&mx;SWFw=kany|w9dI9gAKlg)HE zlXwoUtK(8SN!au!!}0cZf|s`=Jlu`oWIG2ARx{o>+RXpf%}M*Tmxpt%y@hN?VCt>=GDHuO~EGABzAQmmn zoj2!=uAc5~BO`;ahlA?yVlc}kO(*-^)?5?deOFq@VKnqc*<1QGQ_S9>J=u~d02d-USjmziTap7#M(3w-s=-pC^*ql{L=Fb+Ajy=5dE6pE7T9v_p5(~13hK{ydz*^sRKVR zD}rG(axx>3lM#lD)Ih{Wx*KX@%oP*R#n&Nv$t#r7!4Qb$pynsC0E3CoZixdf4c3lZo!7rw5%%y%Z- z>}SBmj%3U2OnA7e!`IgVzJAW4I)#sq6TE$#MS^n|hb3ZFn!V+8SeZ_Rx#5&I#(I;) z@?K4`&|xf87^X|cKt*W+)YTS>GC?c}ymE1dvH1ku2~b)*21^!lIrmXmIDgcexwA)L z=JZc6Z3=;Q^2hXl;g-NVvs=c z8#}vK|NpRLcsFN&>deB%mJoEV3_@G2Kboq1v8lzAK+O4go$&Z-4PHFlg@?ELaPLO1 zi0^WH>CAfU>TAH-RYj<)PKCFptw`V@9Ip(pilGKY$ICI^?HfXI=0FlIoye0Cp^F4L z2MM;a7_Uf@!_N00Ze6UvrK90Ee=rbd_XptAUOyb)<%=UbIL_;XgMHrEy3Q5Lt1OY9 zVTkY`HQ3uMgn|A%Xz9=gTth{wZ8dlLpiqNc@@;O11DZVaFnDb6F~3EFA1gWK;rIO; zqyW^n`if&h1G5?gct?E%8`D_`^I3w}AQi*}DI+;T4W*g-SYB?6HLa;=YbiomNs@58 zDJfwH4Dz7MeM8KiJ+mLY=BC=Pw$Ol?nN&4_LsB|QZ#!N)Q&qZZ@jzyJDDucb7Z)X< zygZGZZzefd4m%WJ#mW*HcuPdgx4E@KIAGr9bdL;PP6N4uwrgu5P?l#X;9HQcimb$C zVwGBK$RdRK&PRa99C*ueEV$bVVGWV;o45}(~ptNK>7R$i9 zVBSc~n==BlXMT#A(+IRvKNbLVmIAEj-|FN2DPOzXsl#KV@+caF7B|z)x9=&aG?+{?n|j4 z?-OvPn`?czbh;fodh)TlB@s0h;fRTJAZMc~n@&b>OboRrPuJ<@B7gIjDwoOl0b&edRs z`VxKQrD-BQN}XJq60FP@i5M?0px}aoBF6ik1r)4)U=0}?dW>RUzOC3-+#YWK(0zj* zBZuN}QrtJpasAW7Sln0CkTE{??YX>z!E0$a4gRk45aq9g#4u&#C90!5Qwuc(hG<(E zhxXPYRF z;fC~-AY^BTqaZ&Pr3Cega&o>^8K|$%70J$5G?kKyh3nADQQ-X?U_zz&S&8!*hen(;E%n9_}nkv3u z^1_!~A(+ECOJunksQ*Soo%8l8h7blq32$rgJ_7GeA0MCJEqGl8c*O#W-&o%L->u#j z^sNoUh6W>auQbN7ZY!MbwZXYQYh2kQEui3eywCcllXc_Xb!x9}#>u_u=vrxshGKn` zq-!B2SPACFbLfMi0NP=o%Q7=ufSxvM9PM?%sa@Wk^W=Wdl;ix#5}Y|!jMGPpaQsjKHg_f?EW}B~nxmovkd_{W($YNG z+S$O&+`K<6Uw-U6^{!)NAnn(1 zW5VT1b=DZT@^PuW`$%%CdT@8KKtWy-N()&DNJ$7JKv^L*IT)+jipg1~qo^<*d3mvj ziw}UCn}xWsW@Tv(8*2+V+3CQD9HD{UVo}1z#F)P9%Lc%^l)$S*;I%bYLRbK2mvccz zS}=06qr~$H_*SIR@5vImc9*XxM&t5Aa=%3axB|qoP=g|P`KDV_OBp>T1J%`W^gLn6 z%cajosuvRC-4Gq+gwPOM1O-|nFu;~T>qw4W0xs82V+C*>HGfz56L>ihy04#$$hGU? zVGS2&Lpa!~(R;K6<|d0^VzdZGhD%{!penBZ^n^5_t4A)Bvx;#dbIvTr&R6Dm)zr!L zs&O@oMNm@WnD|sITrdd>=1;`@d6O`2?i2#*bj%^sFni8)%o5dy>H9Qunkd`Oao%au zCJQZIvgo;*n##)s3+BIJ5dRj@3G$7psmWP#ydTI=_51pfLJhW3s6jrDcMuGRY!B71 zal(qnyz6)x-`m%Q>nBU`OuME11p$2IluMv)PTZ$O(wKJ7?aF-qL zAv_Z|)Q%H)rS{oVE_S(B)LgrBgY!GA#-x{K(`>Q7%5 z2ZWL9iiq?>OiUO|&5U7aWGG97F3V1)08u&k6eS;5+%KS|u&pS?ee(XV)w>?^o1cq; z`L1!fh8q)-;QLmnVGPH3wZ+Y~th6wc=0~BdC<-|lfk=w?KyhIl)^${%X=OfYs?$+j znMQC+L~OJp0Z9)wR=V_fT~Q+5RDUu#UL}#x+tiqxpwd(cy3<(_c&+Jk;qSTt(LowW zOYtKY9f`sMuAP^Ja&o;j4Bm!(G|Ircd@@5?7rF5cdMO%7j!qjf+%rMF~z`ZZGPn$>q+ubVX`M2Qg2aD-Cm% zVXmjfwbZzpgqfKxjE$u#!VFvqv}#gGc!Dj*bvdILJ6r);Q9fu1mMJfW(y~QZsKvPy>VaSKJ)?HL(2`B+^1Y z*olAs=@9<%YA=3xxd%T``~Azk`0Ckqyn3_+FCXs^)5)HSTn*dtkmvK>>chnob=bZk z5*;gj(NN)rj3g^K+Np~VhybqK?G96g!opMqyL%FF@pwM2oh=tJUWV?|$5Li8DYnZ? zh{^pvK7d;nN^t3L5Y8X)!RbBTIKI;pNBTT)u-6@XyIrwkgEKa-wnt-yIWm)V5bUoE zC;J7^)tOCSfMw9oQk7!7a_|y--X%Glh8rI`CfB?6DUQpZcQ_4q%r8CWSBt@_*vk8Z zqzGO~!tsv&2-YUk;p03H;l7KJ8mWT(Bn?#N=wd~=IaaL*MptJg)~qT+3tiT;npWna zqR0(N5#(Nd7Qo+aE_|G3!P$BSY^^n6ZDR~eb8>>Jv!FU}0#r!cs*%I9H(iVXw|R&P zR2JaP&51&BQ6kF9Qczi$j=H)W3AhB=<>YY14YuY|tZbHMHe_bUle^R=2=YxlGcn(n zWocz9rkRRM7`VA6hbp&< zfPGj0-zX^`?>_wa!%6(@tHUBE?_a+@iXUDd!MC3u#8)qPF7E++@nj!?cc&~t&Q5~w z4qU&m5l8knV_Q!R)_0VkxF8y?&KBYyDj+K>%qP#!Fq<@oK9qd3g)d!?9caVt>wV;O z_u=uwLwNFt=j`(QU1<)l$WkVY@m@cbf^&NvaAuc1PHgA+t_=?MSYzL2D=AmQT61)@ zn4mmY2Pv_thzVCkNPsfzte21jQ5ExeImRm-uR@HsA4EeW?H@dkcVOS}NV-z3z zTc6`!mLg>3+e60{Bpff7{$cPM^8yNjVSo}6LZujQRkjwYbG6V^<$_J?E5zzGUbVKN ztCspzXlw8zIIE)|Wf^i3mLfTVZ)Pn(fUg-m$xS-Z=fsL&XlZT&3v*+cOyKNb0)O{K z0=(&|e#py>AqSl-yTK-p@p6cP%e0pec%>U`D+#_F=grDago%kEqNBNrM3h*`mXR4p zZ7hrNH*tMKAxC7$1`!x!XwKYO@KR{DqQuJwp; z!_{-^ag@Njv$qbLyUI~nnt+Hfclz=eiz!G}=31~c(}J~yHf-sV)5*?Iq=t+Lb;71~ z#W;6jEpA@jiu-r=;Nks)c*Ln89~>ai9u!N2xf+E$#{2N@7TmeE5;rf`~0fQ_vUeK}0Q6=E06A8@>bz(i7n zp`wN!H}sg{_Os-G7BCarzwUAWb`625{PoE9Dc)R@V!ZOSkX&n(YL}5W3N=uVbQo{AoGEgfVFUNR` zNOJfVV+G%EBL|#GkhQcl6-6)E3AePCp|y?Y`xc{dMILHuGf`fVBI>N==0+2c!;q95 zgt$1apXMV%4-DlHS$TI++MN`{#VG^cu0R-TWgOJRB5?E!T zD>n{BFl_n%#4cJ?GhQ_Rje(*54Fc$OB_*Ywmn>OK&U^_;)-GK_pkGV|WDz~5f)*_j zV@sDV{mI7Gc7IS%$RA~>`hETMhZ=@1pcn$hw=`Tx;y(@J798k~!M;vw9O$ya#a)iL zvd0OR_c-F(K0Dk#>Wk-h+6lb7@$hD^0IrDfUhBpc0`HN1&Dg%R78^UuP?#45A1_x8-X{(8LOJJarSrzZe80Z94}8L<0Ltplb4VsyMV% znGk$+QCFygsyr=}Woy&PIan;V$j$OXkdF#1jpqtE+b)2+<0AOEE+%Ka04Y%#D98;H z^Mg6WP+p!vz|2HlJmSJ%9YuutMWy4xhpD5 zoKc!@i-K$`({-KzOh^oa`4uU2Q74i6zj~Rv!p8C^%k4 zKn@-2cdW8)#a1r)v5I5wlKj}AlJ6UOoP7J=CWfkFUr{tR)cH!Ke?Eql@eH`y@O;<# zNR3iONxBZ|3ysiLV@;o(DD-YwE)%DQT#jwMD+$8oSid>}9j%dA-4cQJm0@UI9*(w_ z9IRedh9>%qm1b!mHh2Ld{CKLGr1%hmZp0#FC2EtyjzM*GhKTF(O*OtLmYEqX+ALC4 zRhATD5Yxuwvly#^ME|c_9UT zUPp?lW%K8b!h8bo!i6(Aq`>i9%wI5D#E(@}q-{?h zuapR#!22&1yZj~n1{gDVH>{#BLt`YGYr@b_7L59`Ago*NgNr*YaCNUO9*DG%oS$JU zx!qm?U7pW-;dmXkZ;Zv7rXVy_dLt#?n%t49LXw<;n`(-EmUMG19v6@0;Nsyp+`hDe zT&*;f?8Wob5_ow=gFME2IvwZtx!~Mh7o6PbgkyaUIJDIs`+DrKd!sG-)>&iiN^|6; z=^-{;1JU8^V6@@pq60H?cD%ZDDYbAAc;BtJ7fSF#0L5bz_YLhU9wYUo=No$L(Cy*+ z|J$Sh*#U8wLF!APhEFkeG=rB;lynjc_tQj1tUij^l|IN;C)22qOTa!&EdRvs`7@#0c7nuo~NRQP-R)Q9C zlC)8fX^!fuBs6eLm)vb>St<+-bqOvE6>^Mv+DJ`{6mxmSJYLy?3Qm&4VGB-#-ncvu z6(w#cA;9wj3SK%~l)-r$RFExdttlZfVhN&y<=~aqP$K~Q84`5K@rHT{=gaY6hHd~k zUr#r6xZ2Ma1uYf9%d6NdjHil<618a_v9qZif>u89vq$4L1c(3lU!M$^NcyfD- zn7eyhOu)K&1JoC2pfE)Rk^T$mLpKYG^LU2>R}Nt_gSqHwF~-p?Ryf&b zha2arWh>WsCIbWa7@m;(We3a)DIVS3io4faar^2@T))_ei)ZR^_CyU%9jn6eLlro< zuN0jf>G1V+6gNM@BZBBln1ITv5;!2wkRpeM16H0%8S#Gk`xAS z4{K5CY0KssZ0)H>FS%U-Uut=~XLB94baP9v-B>HdfH&2nn_$e_9c%K?ydnh+wehH~ zh(<+e1j@OlTX_^gH(n&j;n*!N1U;Uc4v|1{N2q->503G#uXO_)tgpk^S?6EoBD=}RvOEz z1?!UYHCjs0)q#--IbI{l@k(x26YRco@XlqRW%G7A-6$^8<6MDJ}Z!B3f z@rQY{N4=4QcRqnvg70{8ytBo0vnf+1idhYO!)@C1DQ}i6S^SLL?+?R4bwKh(6K^}= z-#K_Q2hVC428h3`|4gzRxmJmrYq!o+;lIZ-4{$iT|?kKD3auGY?rH1aHcX*mE!3M(Z7F(pnr26Zql)rFSOzOnHHQm*@TnF zR^Z5?dTicQh_qBc`m#77G|U6Oew^6ESyUL-rAslM8ni$mJDH;7U>a_F=(xPEIQC1& z4?RXviu)9$xbJ<(2{AB-8<$HC)#1iuQd~eGg&ID^xUnPPV8gi@%#oJphr(Q51r~;~ z!cgR7_@TBc1zWp0zFsFn4GiAxy-mUaZx!JOZdVY18-)Yj(z9H|fV-*BGax!vm!Y+} z04o}E&`_6wx|(!qv#`7|m!O-E=B6T%k0CZTNPySR-<|p)C?c>jXhoieW`-`om%*D6 zEAsIc6s4k~G9LMvhR97(MNW$9Pbskm_hUk=cE*L-cg01!u1`#G>kSDszwYk1qu z+30_!cb2I20DwN zqc#!Rs$<`n=*@cR?`7Q?6Yf(Q7v*0N73y7XZ*ADOaPFjU=FJ>|CG#XLmTAetsaU*l zCT30>kLgp!Vd4DgShQf~8)HN5>&C_gUkwH7fE0oIHh3*9&F%%dn=c4=)0+_Cu0J6{ z)<%+|SRO0`*7#^omf`pqFT?S%UPja!iIx@TZ7j)$Wimd_cR=xS`LRsLC-|9;ds}Ax zN))ZBXp;iW$JLcYjO|)m_GQq#?u-5S_Vays{d5<;c(e_lJ=%$94|a=OymzkklDOT9bH|#nbwfH@mq($pBml8d zcCfVITn(}%!(tHyftO(`2d@mmmS&pRx4jTo&#l0%E35H<=LoaoC5J0wyHAganGMgM z9T#DT2e;Sa^3h0~+wX(ZyS;IIhbIni^T2^EZrHQg72CUD!%QZ-SX$H~pDv3^a46yNP>5H5FH?+R@1YeC<(X6ke0;Z{+q zo!dUTy4tb5UG#ei&^?TA+`&~R zxX2}!{oy&frRAAoWm-$Cl&NfGQyDp4PKsoV{K8a`k2fbxA6ZGtNQu*V5$S7sqS$-Z z%k8YPu_Uyehe?YPvEKdG3gU{>5qn&!5Dbz zlk`TzgQYtX?m8c{-uM`f`61Y1>hoaBsn3EeNajTf#rae&#> zM**fJY6E2oVwq24Jq)&BO@A0-Ns_lRg|e(>kfuMNc96p4vS!V^uc+{MNWL$^cGmsX zHJ&$LJYQ9D@zSc0t-UKJ%dq;(Ka%6+7_S_>3RA`YGx}A}p#WexcpvV;kKdobUtS-? z53df84&hH<9K@H;_TuG}J!0_$XD7RNeG9qWZgQv8UhTp8lk2d3Ydu!C6{5N_1s?9! z;*PC6AFm>4hsxY|DYmZ$NbyGa8>LNBdPSy$FMb)Cw5k6pm=4MADD9{bTLDEcs@Gx(zYA+K2?j;Az?T#G;-tDWf zWot9J-WAxiX*oJOYlX9oiw%IMCr{Dh<+u*;^>sm2b+)LhR#=oGs!-I{6(A)wnogt| zbXDUc=I*w(SIhD;l*_3Gl?V^f$1ERH2amZkc57 z+rWFNC~2Sky&S563KZ+`(@z_I{_9`6evo1Hmw)0@G6p%`UrhV>Z`EMu%lUY3o@>Mx zw=3}MS}7i1DZ#VrrFed$3{S3>;PKUJJiWUSk8k(k_T^2uad87~UfL+yGe=jUcXJim zn{!cBo+#2n>gcEn$18;wWUhAzbXihbNPUqO@_4TeuAVN({X4tG>NSz4f!r>;U+y!A zA3xfUd$&4q>uL+GUuwc-a?0mVHQ>yNdYm{?gM<4k(6ugGeCeH?Z4nt6N|&99bh%jy zQQqCu3~I7m4IJZT;0y;kIV6YflWz~*C!hH+-0{PW57jU2AFAJaypSBG!)?p^{Tgt+ zQt2P5yt_BSu(l!veQT4@*${?|L_ZPtjVD-gxS+8<2M!JvFgDVGm8B7^tc>93U@qq2 z)>LPpqC5pvm1(H2%SJW9l&6PPRAivKDpRC>%+8L1x0fS5&R9GT!`hp(eQ%Jf z(a|DT0&l5e&9x#~&9(oDDWl#EUWURzUjjova0w>d_Cr=CIe3Sc1YD_=i=ZT+B?GU3 zuLL>~;5RFmzdi{&s#3 zMPC7~Vtk+tqddHPr{v(VilAs;8$T^bNG3MIWl6vlqCc3b*HHNLVAspF8>S8f?wY zQWXlG*&spM#Egc*U%Sgk*(zyc{O@SHlhei7>^kt*z*2DL_L-9I8vAQC=8{(!4OV*3xBtuQ@L6 zvctU#W0zNH$gT60lbm4uLB7m@N$0x#EF8y>n0Wsw$g zTRtwIX(Wg@R+!ho#a#PdUDO8ZTa)6fs`T$9s0KCr<5l$Fc2hINa-k z{XNduv&jiNx*V{1l`WcU%ut?hh`2~KINHvImilCkl0pIzC)GbWBli?;kw9?O%}q>d) z^QCaGTm}a#Wg$CDRalzq!o$r9ndxCLH#Zbh##XJWLP0??%q>jF>GG5;eRz5~p|-w2 z)LUy`RYCBTa`JMn26F;0&uXZwj6*@D0diASk(QwU$lulQM2h`{@Au_T{o(LtiyvOU zP9x>~WqFO+o4Hf|DBwGL;{SpfU9S5Xe2M_0Q3y01jR3i5+u!h0Sv|H-exiMU4m2L~ zom@dAU%e53^B{0}X@3ZB9Z6m~AHiGq6L{-=Iw0Ei;y5tv^Wqw91|$9+Xfp0w(l>!7 zV}<;U#{9`$`{RE)tA7BNsIx|LQ2it9RsIM&l@GwR)~vYJ8p&emA7Q03;-3cEDnAc~ z>-#j=`I_n}{pe*l;afk$v0wWc4VFL4c-+?kG6k|s#(f>cG9CXFEBGA>F`FQ1p#SB& z6sjQFel2Uoc9_MaFFR`8zIgPo{qn;{9XV&twmZwP`pZ8FsRUko3B3PX=JEa}wW4o* z20B;xqP5x+tLwe7roju{ZSFX;jljFp8h6g-%VsrfA>j510N=f~6=x2YqkBytnrhq# zc6NvjH-LrNQiYpq4BFvC4Hl-#*tt0d=Z|FJ^2q{v&Q4M6^2x&k0=l2^A_{W4(qak* zZwG-l4CnTF;q-1#9NXcJL%nV|u*DU7HoIVZmlM{v*r6c9l%T7JxF~Z(g_|SL-wMXY zsv^eAYvl)~lMQyO1CWzJNc5#+sx>vDe0x=OE^^7q78a#~6XmoMka?e|GTdG% zZnR}(C&(&LaOs~!l;j$TMH7V?8b2n-7~PHvFx#6NVbznC;M|jy<-IdJ)as_0;k=*p zH73AZeGX0k*{;51#utlbj(nrGXaqEujDXhCk1 zltzi|#7O|hZwb@AbzRnZ~t4Ng}2I~U9x_w9^{A7b9L4>5oGfELUeMH-J8 zlSg9uq!E};{ROipzA@5OxovE$|BWI{B@G{17%EE(lSh$(Zcz!L9=-`-a(N0RO7ckz z7jg@=p8H{_jifN!c|zesWhW`ZZvJ4|D@bfF5dBD@1@BappcjF+nnOBu>IM}x>vM%zyw?GrKH+t=H1<8liwpKrqXQ_FGYL<3G9t;691 z)#&QX6*qMp9IX%*9z<>_9%W@kQjFKk4C)%HSU7(GymIKg4~7F8e7xdu!%6oab!c_!acD$7X;LVAbz+0Ay`uY@<7nq_nN1aX<>U2`p_(yuY&Wo6E z!z)3)2A7=e)E}7}&ikvS@pN+G)5(oXaaiW_OTJ^BK`cFWECi!;pJ(>^LOEF zJL8S3{k$LComFqUI%=P`vQWREsW$h;g1O^-z#FF9PZv_gO<9(U%uY&jA7!#I~ zD_I3aFbWAZ4oQj?q2J`>HS&g zZnZ{Rl@V$S^^g*!3Tv}@3gDHXs~B>S_st9!qIb1DPVDd`7aNG%msZNkyK_l*Sz5@) zhe#ZD;H2mW3CtUD_r_}6yxNW{7g})P%u1X+xf~~tHQ>m>8f@EAgtF3bgokq#TT@tC z8NkWO5_BxMxf&?T(Liyg8gi4RrNVJxOWts{G=H}_@N$xBuDNo(H4>Nq@gRrq z%X4@AT}aNd)>SMQc6VAV>ar1h;XuH)G@1Idk?!O-dYTiUB`^E4lz_Wr43w3|Lrra- zNO-QHAtgTVhcD;kRh~`I9fu_gM@eOW=8k$Zf6l0%XU+H&(`EJ6RHL#As!4UXiVA z2q6D=Ny^8&8~^;%QGEZ!K79MxUT~#}qx+ih`NJLfjKmIi-;R|yy1z}7{CRSpoax}ddzapNoE(-z`$NV1hVGY-4bs4@29YFZ^hdBYorWm?1xOBCg1DeXhzVSX zk~B4}EYm}4ojcl^^O2hq4SNSmx>PlQfzB_0mmn)?FnnFiCd$C8gS6BjR99z-`MDBQ z39ba%)g5)DT5`UXq-ugN_1DM%Ol~+gKZ)RBhKi~ja=_(isE`FDs7Mhcnb6c!>aRG#_0~k8O9rqE!Ya#VVdi0Q7RkZB3%37h2urgUcxJ=f`()s~zYG8P<}kkdd=EL#E^-O+NKFjDliTEM z3A!~E$%v2kMRbH00k#%T@9h+i;e3a79fs}b9OL=ExAp;QDR}L zBU)<Y)l18cZ3`S|;ek@tt&r+Cc!_WxVOfK}`(NQ&`tcCt@l zW4;7|URuaWc0fjg4Km_wkezHrtszQs-NZcZveHC2yIRB4L>Jnc3*lxy{w?qhz*mCq z+u$X~tFe$iBLv=*AXHUmfHRKC9WOgv2Jf1+brN{V{YoHa080?&7%(rcsH({oFm7!t zMni1~DvQiSvYet!{yVttnhN5>l@Q5w*L)U=ncj!F1T*FS)Q^$|7rbN$tEn%A z^0GNtvS@6dR-z*02(|bGc z*Vp^;`Ga0m6vZGUz!|Xw*+)0Kab(X5#6}WuyQ@)@7lp!{DBQokg&wmVk8W=hp@%!y zdc=Z?%jX!tYjONw8@b>H?ATh1ZQWJav84vvd#XjdtG5n^_B7$jxh~wkwiOTW5X2wt zC-5?S4@ux9(6aaj+h@mTHACTtp z`ue)j7tazAQQ`C@%s^FjC9G_0U}j-KE<+6q7t9(A-u_t&1EB?J`?vSGeb+IH`{m<` zefjp_@n4QZ|EDE~ue_D_Ng_Mh*wJvXH;0d>6Us~TP*t9TiqdSPro@Q3y@~NbSkqpD z;=*`Q3dhV;7rI)D;7;HTAn>x@?R*D|!K=;Sr4w~Bo%p%HWn*I=nwpCGr;TxpcQxNo zTU8;zD&Q*|FH7cl3A|kPr)?GOr?J-dax7n-j=I`df_Vf=i-VDujErUJd*%QLAAcj0oPd@ zhdHyylJgx$SBVn|u2Vz^kCUUzrC4)~-S4z%Q{F6Fw&a1Dn#$9;b7ud{$#Xc-IVaEI zz6{JlVxMe(e?s)RbAB>0F+NO=_xG8PH#H;PrLxHUWn+aN)~|{Y8N&MED+BPZZA0R? zaxni!K+D4x+$u`GfA98Hcyebuet5YTFCT5g$%D=4Y|lqrls6vU=*G59m52`a#OWjL zSW%yj_!wW2ui@GK9e8qgJ06qR0YAOJ6ORet+~+D44B|^?Hxd{(5M(zB&|bT+0XHvq zpXxX0-wZ_{%;*o)5yx}QHgjL)A-(0%>#EM9(ohJef9mGtx>SH0-KgPRg~Z(MG| z<@3wMB8rnoYjA|XyS=vnwKY*lPWC`lG?(JGp)}yTn&!48u0TpKpX+8DBBbD z6+u{D9fHQ1a5NLpRug!+ygSz+g3rQjPHi&0l!fSTGoal@{lkjv3W zBT-g+Eh5ra)aeW5JiMF~C(s1}0WST;E+uiY91qdwxGz^5=Gttou2yiMt2{efBiPs& z!O~J6CMG&k-rXSy&j%c@B+2n|*&$hFilqy%SXOgw-uzjR*ISbpxa1i_ip4G&y5lDh zpheBKS#QkDjE@Ed`WG!;wD1vqe%^3BHBnnli29S{wbrD1Yf@-wBBo89{FCxBr7O-( zPIF|K`u+W+W+V`J&0f`)>0*65gLjDImG>3L-mAf3ggpf9Z5!*+(L$G5bh%bnkuKVX zsthz%XJSQ77FO0~)0Za`Ee*N2d2u8D^7;V2dbSg<9&g9iu5!c^cpu%|g1*gFBE)d^ z*lMh-&qQ*30J+?)_~P*%ym+)5pFP@xFP@NFezK3Y38Ihp;)|#I@$A7K+`O_4S1)WK z&`LRc?{j&00`B9xocm!9ozrEPM(FOCz8IplBv zx6fzc(m^*|*zba~dz^84motuUcf{dd2khNshwYs<*w|`;x>7@ACTSunR0Tfni(qUp z8wTV)v>|%2;YUsiC0Edwk8@1b+EF`0IjtiXlp4zZf-2>WHDYNJteqXPC%dncn3jv zD12oAcI6na#v)i-@~nnHl$WQVrY0Bl4V>`27_F_P0<>%7G2S)R)UP8+E|^0Nc?Bu- z|JH-OgB1ahpy=iR7gq;5DcHfu*@j%XwTMMqS)0Ptj9#meF1b=I36P=$I{{LQoTw(p zWCx@nT6UTF zC5!$xe;$|mA%L^!^@tj5^qRPxNBg+m8cRia={L^KP7yLh{XT!v2)xxL<}Vq%oo#aP z%HgZvbb0$%!*@V?IUz|`B^t{U5g+b`s9{fb3$_tC2$CVW4CH*N(5vsj=8A6w%TG*9FuFS zaRmvfe2=`EFc+(2*E)+J&2Z-UtrR}st1|k3OyP1&vQWb?0A=k`&~W>Q(}5lBIJ&b5TRKWmnIDO~ z)F9-ihoX$2Syz^f>cVK0W{09UGZd8tQMhz+6~6mo4_*;;U)2r;C(^v_xVG1#`_4i2k`9S z0cshx$MBNe>=)!_UwtM)_nR-z6M#>X(>*D*dZk%h&LRa?Gcv{i-MwDR8?1q7_X_B8B|r3F?TjO40aa;8#&~L zsvkxQp@f0)w?hSr$0&{ur}rKEOOJowKKbkVPe~45S)ai>e%u(?+nT}0%TdI5YbvEU zZ+dDBd}%B$#vdz}XCo&&N}AO`uww9f5_p4T(Crri_kAw7AH0^jNJ|M2;9aqz04;Ro z#$g5tyaZWtyc}xaSq~CqhF#MENKVKd{2Wyb&HT5R%~i!NIQZ^|ghE zyD8jUjN#&93MVHs*xND04GH1~^x4zzPlC>n);Hkl6Y9{_m14izIufkaHF$0>*IZjb z4tfq5g*gQ4IastV##-Q$6RxbD;;yqH9b9@dqzfv_m?eG`gy6+Qc-J- z>#Rw2*WT7rC3fp1I#yX_*-!TN_J>14Lw}z!-t3%2*Hw+yuhusiVM}Km!BQUMm5E(1 zwQ?sc<#Lc(sn2oRf$gC>uwxa@99V^eDE-6iIr8fT@ot*TwfZG z3*>lTKiPrL2)fVjZNsfg8*u7y8=l?k!;1&fbh5*HnsEBaDm=ZrT|k$C%X&qi{p#~0 zq+|H+>?l5adYE8)6t6$0{RCKUzaq$f`_*{@?^)q| zza*#2&iBjL7x40nvjV&?8N75-xPP;iUP}XRU9QLV3w5}Bwi*{sRpR6kso3TAtyySU z8HM~@Z^Xnn!NbFZKIrQ7fmVjLo|LO$KBtA0#dsMoim;RShm#ym!;Opna3O{v{rBxx z+#dQk#s1L8{HG;{tsJ-tV+`I2<3_^KRu#S;I*19gL|&Q`s!P1EqS_zL_2Fn)kxB14 zPbXvWT9D&q@Gk8K?_2Oy6aiNe#O@ZnfP%nlu7>nvPt;VWqlr^Pwv`ICuPP^pTZ@i$ zbp+rl;dDEM(NN}E@kT8+`Y+5hq)c_BFxt^%;Eg>Lj(N@TafN;@dCJ;A;*cygEhWrv;2(e|8jK zeQ^xm&@rs9`S>qS@#^Yp!`{&WF>!GOV)a3g z6Jl`6r7$jzp|L^7DoAl$Kue)N+_>VlG&bN=<@<*oqqu*#aUn%;zDvU$BZKT9$;O4_ z9s4nCO{c@nb{2e`<{>e3DT>q7vAkFh?X{Lz+m?j3mLlYHsKJrJYXC!byjBws>_FgU z4FT@EVC-Qz3HsWLVP~n1tTb;l)Mp9cu31xw)vGz@ZZRsWb5KrhwyCK^0C?T{My#cl zfy`luJlU*3lZ$I z7(xEJ2n%%)@a-4Dmfdbdq#r@o1%bYL@O57VAJ@6?a-I!$hnZsWg_HFR*jrAAt@#XC zn=gQkm9~Jd6ry1G>PqmHRT~!Ne{_~XU2P^*myO4=C1b^Ewk$~7E_CH=0!n@iyBY_fgT-ENGH1mE>5jnL6x zfc6@FtSHk#b)E)FGgavWt}06EjdPP`KGQVdXD94V%Cg@?Gn*V_jEK6WBQen@~L zLINET9_&nKZ+AM2dkQ7Qc+pwi7imfU1Z0155&_7`2tj^!7>e^Ev0+UiZd~jVE7Mpn z?lX9I2{C-ReMPW+C3CnO%l+!}!}$7(!&3Y5Fur+t5MO_`3txYJ5Z}H!j_ zzfyv$NBwc}pcl^W^}xwp9N%>niE{RCcEa}c4p_6o4v8`3Lc9%-p5`ZNc5&7$zL8>V zYK-LcOl;k?kG5_4f!7b(e&7xthLD4b_bZMKf6UoM;-UQxpyqX^UYUdC%QH|>XeO2m^U5`bF87PG)ZP@NslLfhR7Psd zQpAUI!AmaxGhbHzhX5R4BAl)qx}h9i2=fuGpSKRV+<64uIYQnpbKZD5&3?lx-ki7w z8-bS>Ralu!g{9eiSX=3d`wZs&VFxY&q)o1uZ|afTRi6npnOW6&YC5l8yDN^RcJm*?==^TT-Zuon;RY`~qHow#we1D7wX!uhjpICZ=UhYvMkeP;oD z{oG+=YmKbzY^+|piX2lbtZi&Wu7-@<0&L%RSZw!$?p-c-i25O=FgA4GFO3Zym-iLN z5>NvPbk&tb{W0Fm^mzFDx*#z=7%j~OC@6@9 zgOg?dbTW3lAqv2iYw+0E{(cbky{x%T*-|*!YN0SU5G_slSldD1T~~$F)Nr~i*A_R+ zxaOM3KvtAW&}~5H`Z`(oL2|r2os6qf)YYe=G|!YkE4kd_ERCP@QuSV@#+zJDi8Z;D z9Ha9rF=E+26T+o}m*HIS(ucu2j~uNgLPFgHd^yf5)n4-?_&dPUWf43?si1j(_xDo2 z7vQaT*3V1llDpHASB};*-Z%)yD=U6!G96YHs<5;)6d?z`VP`_%mBJ0`(9xO;4b|~b zS0499PkZKTYYVmG4z@Zw%}tcgC@W3+ZXrRJ!7I7mAvM<)%oejCcoBt|DKTT(8&%b1 z4-E`-Ww{#UfE@~1#WBTwny?}82Kf8`P91MvitG9|&sSU5I$}!)r!%xeSBnkSuCPLT zojIB+O;A^4fXY0&M9R`3_p6QK3~f4NTcDPU0M?|Uu{IUU>r%0zJ`K%{>1bP-h1Jd3 zSl6D1&FhNMyQv&Iwp3wnUmXq;aE~7#;2vh+uEM2LYjEYvT3kK54mU1z;m(y!xPQGz zEERrqyBE*yZ5PlLEdls5cEAK*o+|d@!Ft?2?uQ!(?QrX`J;@HYkJ#bg9O? z?*Tl#y^3CI4X$6P#HBOkICr81r;irn*nxcP+m(&YT}cFo0Ay#nlS{FIgS|HN=!>kT zz6hGyYDh>)Mc>{-1YX;I$jKq4xc#q4dX51%EFY6==-ANx|Ed&271H+L{r{3=ARZ%b zu8n|;gBqejjFB2=joegQR290StswwwnxnC9O#xQ56(c7nO3V!4Tn!xK^|B`LI*vgo ziQBg|RzO&B%-d!XO!SrD=467h;u!I~o$IQxW_2Zed|X66UQUKyRh5mJnrw8et;NPo zE6}x}0qZ*J#Z9-o{6qoXVmhw6CILm+M#!ft$J|u)ACsbuuSfZt@5qd@-jb2z+EY~M z+n1Tk`A4y2*l{L2>}SB&X$At_79qsX450zG)LJ9R#|i=7mhg2|gNN;Oc-qbS zYk<4X=@1|54WYia>q#4ey)3ud7%h5XZ7}(bgXtvLn@og_5y^NaY|K^21#7_CObwPM zDzGqG1~Y?&Fw&d|1NE_Qtc~V;78U5wo*d;>o)Ya{niS<(;qPX?QFZa;FPF~!6e0_a^a2k{rO@Cu%sD9gI*z9COH5A5@tSwC+hI?C@ z#rm46lQg)E^EFeC^CQXHct3Lzw`S@I{^sh50TybB{uXM~S4#}ABw45>QJWMfDLK$e zYJ;o>6l|rM9Bi$Y5^SxS5@gMNRnZT&k+t%^jcTgYs-%Y43e}ZFD|N0e{y$|n{q;Wu z#YL{Yy$!GT?QOu`J=NH=vl2V{%CNPk2%9(Np=(_hR<$OhsWFz^Y!rbuf}CwQDH08} z$yi>WPQcB;%7zR&CKIg$-BkqLH7&X5T$PWWu2S@MS7F!I8tf;hd;CB%x!g7Z-HRvJ z;3~P?>jd2E7uMtEr41tM7(3pFH@A}G-A1tG`0g%(>`rpLyF`5V3wFCt_7RZjv4_2J zb)Pk^AFv?++Y0zTz8Fhxcb@?6pT8p)OJb0I|1CrHvT(M4`uYNa_pFHLGH`$R_8jfI zfWQ548Gj}Hnc&L+=Er_dkNNg%a=u?(BKV%i)B9_2?lV?c`{sFZG_|HI4y%W)JXzwC_~n1?0Xm&;N)ZjLqk1LU4-Z8a@c{B=Jaf7MR)f~Y}mM*;M;)wLMhZxA^^?B zE)9^Atb&v{{fEIGhNrTe#(#IBY})q+H(PxF10!aQe?r-=B=jG*myg!h>6Ec$IXE5?_-nt*dSN|hPdfd{s z!3fewN%|w;!xDLUKPG(yKZ6l}3o;q=b&$ze(wML5_kHbeH0B$3?N9!}xp-YPK7cce z`XVQ<+J~@L{SY?Fe}t71Y1s#`R3fR2_=mo>@=wD-b+Cp9uc@BWKfMjcf8%R7<|{v$ z{0H=}jkCWRyy%yKccj4y64I;M7)q?L`>k-gp_%e83 zJmB~)ftPQvJ>oC}hZuNq#6H@;4wv?O;nX$@?B8IC1DmXIyw?sl&!pk&mj`9wy&}ZW z<*>r{9JeLM`_1dq;-;DeUfw4`_HTc=F7($QuHrAGzy9S0{`~!Qa=%yb%~zMn`Ch=& z2ODthWHc`9_r~cxo;be414p*G;ow#`?AhdkzD`H9H`*aC$`XNoCdkSNMr}<7N=s73 zv>sD46C|Z)VpH!C8(wek8-U{A@c|8ee#O3`erf;zBa%5?`S!GlBQbU2 z2sm16!pGg1+@n7_n}X0%;f10M7bHbnqognr>(^C^Tn$dnR$|F8hZ?-CCraQIBIx$_ z-#z9_;I%MTr4y!=$mOxIs~X*#S76PW8aO&y!^lWqWFO1PO{D*)k!TsbTYFouxx0y+ z?+O$Zr^4FWT!b1Jym=W0$V^m0bcEHxKv#nk`HmyrT&Wq4GuvgQf8G?+Rido)k3t0s z#ky$yl@eqvSDcXAfl3MTw!fMJX;3u^`9Asc$tq3on7mR$zqp!%j;!nti7P*d3KW_H z6)0Q>RiGFs{lfs3Do`kf6Mnt=D^Sqy;osR`fkIY=LSBJFNTCYFTQ%2Yl_=zrzbB$E ze-HY_W70U6{E^mbv!r?0mIn&kA&Rcw&9C3D&JJ#+n90wAUG6Ww|bj(lwDDtBI5-4J1aW zBY~6>rH<@)6>=TQC?Z!^T^fMpb?Ins%s}gkOoDGF*0$$i6Nef$a;Tvi`*$>mxb7(t zW@yKyQyn6%d;R=+AqFsq8rb#TyDkA(3NdgZoE<{!dY==Fc@f0DYpZc&s|z|CjS&@Q zkFX#IM20${zB(39?(f7`FL_qONpio`|GXDpeb$TD&%5#b?s7c2Q7K}?yg-6)oW1;P z7hb>EOu*iPZ(nYu$85#7uX^#P*S+}m^)7t<=D3r?SG#<3$Su%W9Mk&yxL@^(d9dI~CQ%IV8jNtd3MFfulVz9BE9Fu}a}^ZMZ; z2iQzwmvtCI!7f<4esoq^5da937F zAulr=QQQa<*k{lNTuZaX+9~pSV2(aYGWO>t{DbfY;B+)g zZ7a#qHp17}6?XQPV&3jra={J+;>f5#0o-ldS_r_+*tEF`rKRbxwY5NHRSxRvl2Dj! zC@N4yh1+irb~QYa?=;MMwr5SRbq z-!Iot=njBadfkfP<-d`OUiSaJL&fij{5@2Bf8^UT3GmWBe!msL`&P}hoT3V!){d^H zE8EumJvAfeP-;fDRd!z9qO6?UMVZ+-i}H(#k~eK``?{y625Xu;(OPSYrYd7BFE>OT zT`Cu4=+K8x8@4w3u(p!K8NO_-_2KEFg_HljecrV*l&V}Oc=|J2(>WUjj zJ@M#f3qE_!NzM=B{`GoXKOTTvC;f5vOd#%^B~g3lbO0V-%fPG8_7Zf@h%}Lp?rtV` z-iWK`t8wvkCC;5F$LXV`IB}>LM-LR?;NAkdVo1aChHw<+`ye{f4z4b|!bl6+x@u6@ zR1+(B`t#3{R&cnc=i28;?v@~a+y4V!uc^XKGw>}o^M&KpKd%kiUPWL!7GQZ0584Pe(1{o4$`2%dpOD8iy`mZ!23I}Eq`z2;QjmG*8TjC ze{A^6ci*l5OorY6@jvp4s}>el)}ILq3;)U8+vo4;nVGM13-Vv)=HUduA$q5Bm?E3n`{avm*K?E*M9=ycDUndjKRz0-R;a~BG_{w zlEPF_OjlZU`FdDcW{5TQHrTi}9c$NAptK}eBtqvHFRxtlCGdt5T*DQBD{V_-l6ZUo zy#6xq2KZQu%GF#Be(&B6?BCys_3P{5O`mf+J5ESr4KMoK^D4I8d)8w2?lsuCYc;m- zSS^y^I62#j#S`n+<)f+A5-TcnP*rI1Jj&1Hbf(MH*LwdR+OQ@(ogIP*`{ zWu`wbn(+}9&-?&OXMF%$jZYA4POr;qGQzB<_A8XOL(E4b*lYx8)Q>@C6TS^HoA^4& zbmEsJ(fSyS`LmnmC-Bny1b&7x8GVWXjuV?skcqx8)cTu@7BOSqA80z}&mk65UXY%% zf=Pj9lRkIT9{D$pa{$LiBoX1}e1lciyDG`)07&BuVCzZiXnzV)D&U zi%BwZUnWbb4U_f5ET>SP#bfeTjNcfn$wJ|z2tIDt| z{Y1tl+u1p~-LZ9a{jsFH3U$j@ptfN-Y8o0*UEd&7UR8~f@(L6bmmniM3(09|NJ>pb zLQ)bEl2Z_ykbs!Dctpp=AvT`c*jPlx#2}Ky3jv~HV-Ox0iSVdMF~-|bvSV1$v>lre zFPD(@BoIeryxUm7t z>jKF=nUXv8Mnsq=B6)QXFU=(7WrgCx$yQMg=+V7hxO%Dpr}y~c*bZ+T-sXjaTRpL_ z$AiG@hV5Oh*w*QS_6A2phugx>+ni1?0m#mdL}6h%tZXb`VrB|8byblNgxA0`d=!Bu z-xd;6%m!|v4LwG_{nq2;lEHfD{^1`pG*0~X&9q}hS_LA8-s{4=NOW~pqoO#qW5>&2jc^%&tRip+ zBp;K&Yh_B{^|i*T);w(QYbNNf!@)xvaNxjtbaywQp|J=J_5qI6qPL9K?+IqT6(9vXzjz$BlX*B$~s?hvVQl#zfgb1gu_-Oa8xES|7A5Zh! z=7vjuaWinq)_4lsY^K7U^0h^dU4=U3nhn&7O?eGbTc5$!yY`H_tWpOtlDp*~HvHyBM zv5A@gXINCCcT8e>?W)d=f8Eg2hmBkMuz|F`yBA$O+t9grE7or8#@Y?tSk>8uwvJA; zu92x@J(^dorT#j!ka%AUZMUpmi{|zY(Qj&BgB7i-v9gUsW8Cs%n)w)RWykPy@Z;Op zu19;vIvhF3AqJ^L`>o5HMHwH?tIJ~eKEAU}O8I!FPZISX-tNP_o7)MT-PpOk33<6O zqMC#N@1zOv^|r-@(;IO6`VQQ>){R5k{Ls1F7`4S*6~Y#cWp?B~e6X&gKqNfL%}+pV zj4iy~l;Q8|PLFpZxsr3|)(vS%!8m?kIc{9xxb7}$Ip6PUTsYH)bEjHy`b0C1A6bdR z2bbdz9d}?~1G>6OkdzdT;1D0gC&VBrC5|pf(_vw00YhUWsH&+5@NykEIe>=hw~Pxw z4H^K^@mEnZ>Zk4@3)ArRyeKT*fCPJD=AIjz`J7N47c)HslicX64H3euQ z@GY;)M{z+4lHvoYO+e?`N|cwU3h-K47(icVF@bl20BeLCto;CH$$%@y2H-1!S4{$M zOD=l1uEgFw9XLpzR|fCFgIzduXd{8Ri-6og!0p5V+P8oITI}1$@a@F%6-97!bHKXJ zI`s8cVMDtk);AfVb0sMMT_jfeJ@D$k5`7JP4@ zIsJ{D`E~1Z%0?5u5=aZBC2tRl0t&WB)Bhux6>?mIn8?G>$>3k zKrgj>ejeJFtW1_Y(o&uE7ma0;-{@;jgudo@QQ1OMWh^w5CqP4eA=K2ChGRP_A>(mz3(NE4h63wjE9G^t&R1~prFA2n)7&*GxGnB)XaiW899ZcD{JZv z+t+k_zjl2W)^&BEbHheR{S9J!?fUgtN826iIO4r@9)rB8ufs9=;4*Y?UL@Dc`Ejpp#l0K7 zLL7471m}-Q+zJtVAKcnT`}=U|>{|40&PQ^hJ7&+CPG8iC0tDWk7C3iuErGcQ`*yFu zsz!TcCThXU!wPP$c0wWap(`$orVlegH$Dh~0Vc4wm;)=lg)mj01yeN=x1{87I~>|s zD`0;0;#Pw0I-EIHiIazlaQt8)j_xbKp*?xnzcUy6cI1+a&qmM2RJufsK~;Gml9Qa^ z?`H~odp&ZydLq=YXz>DYnmh)tBH-RB1?S3A+&6Ulw@Ut;ijt2Hcg*`9_b-Y5ZxaM` zM`85nkz$n^!&iikWXJH>lu4rz7jA-z0vD{T_N9}jADT(4R|KQ8EgI|BHM&?{s{N)i zSL00~&+koKhOGFd$cSBn)ab=XiIS9&Xh!BDLd34~a-)%x!-^sJh9WiIl;FFBz`GDp zfeR4kJ0Ah=bK&DMTa*y;CKtBlx?` zhp!6(njXslW-+*(tftfVV=8P-r@-8RSM^OG0273D=0aaz6}mbq;Br=6?nj?H>ujwDFr#}5&@w-^{ z^|j)8>KnKsL+aVH{Upmu_ zO>NG|PUMn4`Y<&yAQ>Vt&WFI;fs1Fmv9+ffRfU#xDYY2Ol;(m{)3J;V)d<)=)|+$fIA5~^FCG32qcGC5O`~F?sz9bcQei$F2(*$4%ofk3_I7EVf$J$Y+GZB zE$t@Q+-8Ce&Bj<=Z-9nU9kC`qo2L+kED`my931swX>BUZP6x0fM%f?Ca$H_I^*igOi80q&6zwdqG6;GUbjH}c#a5=poi?3kh zA&1eUMq=8O5lD|*gz9V+)a9w7p+F5Qiqz3uris=HU9{J`VNH863i9JcvTt)!T{zkr zz{7SCJZ)wRd05X9@{(;VVb+MWcYYQC&``e48`)=f*>+14w^yns; zHskp59#S^}Sc34eW8FA*bR+dQ;_%^(XlW^fr>7G(ZCXw+?m*v`RQkM{)91qoohuBm zs!k6p%e7Hgq=BkjHI!tiAU}B-auSq~8OH!7#SxG*-BDB+M~X*bL7Z^Dd3n^*- zipbkA08>Q(zYoNc?Cfl=hlB+E*97mn&D)AjUA+F!BS#LRZ)+!NYRX9!1ixyb#>QF+ zo&?6)+DiIo=AyEyOa|3jaZGJp6@BQc38u2X0BMalzD{h@bMf)?9R2%foLiQ7EQy~_ z{2tl9%F1G_tn$YCMoaAMu)^^k3!L5QfjgI)MY3`RF9TPa#UO!~Z>&AJw-XNuzPB&8 z<6yTlR+Q=@GT0Jff!2r$u|Z{VD7n*hxO%A7vq6= zx1rtSUxDc?t}Tw8hET#nBv2_NK72 zHiWH}zL1p}ov2A%*2kK}EpJcGO3Ktkf0eD*fR2qkCOv^)=PF1GY}&%-eSEyMQ2 zi5{Fh)r*rSx8V4(jndf3tu!v}=i}PiE5wbr&6`&ch&eXgj=r8GY+B`j_08s3(`bU` zDnmL!>!PNRPSQDAC`#8rekxZWRzps*F7k8S$-&2w5`~J35(In;@<{~=)FvP|Ck$!H zj);%cL3Hpkg6|@7z6%lJ!-;m537Ce3+7nqm8U)t@<0jwE$i`^(ZM+1gtD*9C9)_WkA8?mhqU$kD^tym2*sD2q@FpH)#& zg4k$30;U}*a;lPS*ZaKY`1D{=3}HW6xgc&k^07#@mHgUtPs>t*oXy|x;scDQ5r zI%8~DZh(y|46$jY5%zD5!0l_@xN~zi4j)`Aa;S0|J6E%^n0@Zj%Y-2e;SZ)J-$|iG0q%s!|7u!ICZQQ#}BW>{v8F_-J5}( zTeGlzTRD1qs<3{2Dcalf>AgxrK~XHyGb0d}5C&g=cX9&ivYTt~bG+{cF-tm5;TUqX z0#yC`1~hbAaa?hqe0%8eisSE+;&H$BF+v1Z{=dkf%VH3-6PE91@Xnbv8MS3$SlgP6 zb#19wzd9WoIdiX=I~fzAX^7rMlDpp&mXBE#H-LO3fP zU1~>#yCWvTLnL|%4RWS^oYcvi#(B&Q>8T-D)m933I$74&=gXigf%nvDIe0gSv6H8^ z&^9??hA-`3wW?Cge(3IAj>Cu6lM^QR9$Z6apb|Zsvaqo;1#4F&psgtyO^p#~s0l@N zMIg$H{ZLlqkFt_*l$Rx;tTdURn;1hE-NpwYgj16KVEfEuG zOYaBQaq}Q~2{CL1cuDM1{=@iW$->A05g2$ z;N_C;4{mng;(kw@-EM(Xz2-RGXF;;W)e}j0e1AJ0-9LbHXSxZ1)rgJ>7zADob-Fa8 z4_i#MugLPmiAT7um4zaBWl9Mp@b=XZcw0o-A%^eS6YFvI)JD=~oT4w=(ZiiMbg%;l z>5_8Ko(?gmb5nN{I8|U%3%$>kImj(YK}uRQLc)CLJ=PMThUwEJ@G@ZJkQ0){bQSjv z9P>7i1)yYl*S?|0y-UCLIM&c(f6HSPB~P$2e*8F0oG^X>x~zWiPDNd1B05(WqN}5r zz*UCsu1cYeofRl8iieK28eR745O_6UXs8Vra%1esT%6315bH}&i$`S{sWe`M5Skj( zv7%1OH`1~q8|zjVV@-PzvNOUF66{W&5nnOwkrzTVHs<5xiOrJee}0<4d-^oN_QWQf zBIt_kQv~3XJ>-73VD;)M;ds}tuf^`&tFUMHYV0Cy>uaSG^Ga;o)QHYbE*-?VdW*4Q zc|Lt#vgt}Noq(G{z)d08CMkp$_~u$Pva_QIw2|TlTUKTyGSVZEmKH(Z&oCq=1|u%c zAF(mM;BJO4Z6uwPA_%bIAq3$NK4}re zBisn+?ud=@KwPw^5ci`a++l604?7z}WTpj?Q;&R8R+75I(cWg9mZsW~`SWJ~ZSI_z z|Cl{%`afooX3w4>iTkr={Db!qc*VYXb7%e8KwoE{uaDPQ8OHwW{cP?d@RH*_dg2&1 zb*&PPx3ZF8OTaBDDMDs;7OLy&aqZewG}PB&=B!ylbe6*Wxl;%Z)5T=}*|X*n0=%~`HpxN_ zy&}XQkMVNL^LTkm*|UedWVjPo4}0U%9xGhhO``VlK3m*9pN7w#?8fsaM{w;*4|=*% zkeuiMHPyxR_skVCGE}DzjR$=|{RDWqT5I52;N_6R2m#*1J8E!-SKP7VJ+Y2lZzs;5 z*@z2gx8UrVEjU50=g5&x962oA_1>{_4Yu|&d|R+)Z9N)Sln{KgkYAXB_{4A+8S4wj zJNV|B!u(g+n7kdVq2L_|5y+oI@fi8@DL$9t*ssxWH}~Z2zw&&;iU2D#%sAKdnmlP7 zLIRw`O0rD^-JT7V*t)3-JsT^qnc&;jTp;3>u~Ci)4KReATqhgu`hbS^9b!(9`7#6Kc@aQKb_TR~6>itBUB$x4G5TQKMrAq_3wg z6Zh3%Kz&04b#k^EbaK;#sfjksWHL3@g0|)|xVc!6TaP8@p8Tf1CTBY{D8S!qoV%-| zm$Rd-uYXrG<6A8q@&xjK17goTU~0Q;}{v$1zi`Ndn0 zf84!y7dqFrptK|(<>kdFBjx7h(4{Xqh^~$J{`>E+X3c5>>QVyjTv1DD%&0$N?C1|L zitjX!9)ppiMq|XtQTTMkNOB~T$wfwrkOM=O;i?#BPz10%7A(eO;1%OER#KFWg1i(o z*97&48tziW+H;?rq1u9zPVO>x+dR&Q7-Eer)0EZI8rwZ^Xw1AS}#7#DIN0wP3C> zO#!@;l7ftIsILfTjJro0E??Y+ix;+$>)k|`oLwT`$2V8@?(4*M zhVQmj=-Rjf?R43>Vr4OE>kE-zlqL!ta`I@7@yg*f6lVQn?EVzQQ?0mSt6aQ2RPWla zIL>vm`1zz(zAd%9UvW$>`C|re%lfkC98UeOfvd}k3bO;6DBqUvdu#uAanp@&z^N)P zCimq=uD6JwD+e#R-VFrb4OLjvmX5}9I}t186pH~q`tbI06e$o@RThdX9R`GpqcIX= zJea?jI=_S{(p?N(g4 zxC0k2?!@_Xy|_Toy>w|eZA&m_@$3h#(^gcJg2KWiDiD1Z-1s=_atTHiEU4k;oBZX=y;9))y=K%t@TRjm3SQ^K3=?g$U->bUZ)S z*2V}nRywdYUj`csCD>UlgM*DSoa|KK>YxTUM>V)Rsl(GnLsSMyiMK~(ksqo{1K-qF z#S8HMxBOwpd-?9uANTIxi}mYT>Cz<+#l`etC@w&HMj9fb>5RW|6aMm-AFyt1hXC*V z1q;NNWi)|z^e6`JD2yI6R=`&d-YHY3B0fG=0xmgTjt9&8{hCkic=_T0UVVNNpFO27!=YgGt};bso+&cpjpz%hkBmecRFuXL z^yBFDdBfjJ89uHHV68g`MoN=ms5D8Y$pX9ww&vpW;WnH&)PWNO-*czd0MzCG>?071M7RSktCW z!ZdP}Lflu-)Tw;OpW~jRL_2=`7<}~62l(KFKa&0+Yk#fycW_}-CRkow+b6Oxvj*OP1WdHoruO#eH5fBBPMte++DQc;o%H@eH{@` zXK|8lV`Brl1ouZvwIjNg>tS=V0YTRg-EBtL-W7m@``bw!1m86T-!(XLs8gI=+1;LH z*L%80!1cm~?F8bj!tpYM`6PV)e4p4p!&gElHsLTm_JEk*%g?tO+qbu3>(-U%>0XYF z8|y`m-_@(j&?f4!70~x6o2~{kgeoi2M2xq%C=o@43CPcnlcti1a6=R_Goz4^!J&pQ zq^5=;DJht)A_M6AMs7XESKKh;n`a!)WrHygZs6%;lBBSMG_8zhJa8Kk?v5yW9LIel zLo5;Mvj}0n3lQbM2ywxSkr=iVDUnJ@i&jEr>@wsgD5D@*9VO{nD9g}5d6w3jnj)9~ zzTn-oZI6iY?%B6Ta=fMaC@Co*Am$-0JryD05n?Xy4?ld5wFKTpi|EM$kQh*96{|FZSZrsc>A}V}q01EU~-O7#mjTp=XUdcJ@_c)5bdba3>-z zLJL8@Dxzqjx4VKo9FUq2fc@J_apveMoIAlc*E(_Gbe9ag8*%Pf36Avnle2cip3R=v zzdeb*Y%6i-@CLEkY3I&%v3`Hc)>iavZAN$Z3UqbV(HAC?E)#X>GEWK0OJ`v5f+<)q zZ@QR$F>A&|%$+@zwr3HL$7A9Io=!CZGiOY}sF5GzVL||{(-jnBszk&KfN)ael(^`;+XCj5lR?8ZX~(eG4%INz>Mkq_fNs% zg)^~;q_3+2UAi1L)Yn9AW&qwmA-{xhx;wVkqPM$_9B(bQ_0(ZUZv(nJlhIaffSP=D zI>{>0|5J|~q6=Mi>-K|}t0Wj38xmXsu(Hw-oejF!)U1ylg6@`fV{G3*;N91T1N#`d ztFd#(D(t8J(Ie}n8)?UR7Q<$oI<-~Ab{VeRo;|xwIN`Hrdr1;_Ip%xpXqSNR!2|0A ze0T0_L*KS$0bfqK)74c=-#soVRF0PBA}nvrLp{N_t~Lub0=}uT8*GUvDBzoE4BlvD zu?W8WIZ98D=m#&ycsafs5#dD+nt&^tKE`kj;v0pPRvCIvYY zjGgH*uHxofc#sJ~ym>X^lBR@;jAf|GQbtXV z%A5KUhdvpG{`>uG=2;C7KL7E^@nh&(-!4K8rKN?WB4p=e!apz&`GrOJ;)~DdAHNC< z7cIuj*|Q0((=c(;WQ?CM5#z>BAoz~Ms4?=UOqcW&^>~0xZc|9v-tXz)PD2o5FVV5!u3OTxV+B> z7j|3I@36wz{UPL3JLuAp7g;PvQ?)g@U|ss)dD4eaQh>jtwB!(iX$8(6@4!U@E<=~a z3pB1=SdSCCLvgsr0*AWIv2UXp_HK5@@x!&^%g8rkcy8yR!#uZh18Kdu!+rQrmssJ% z*{s%eOxs#8G17vD%5i>~Hu`d!muXTwvv3}9=a3~RF`;<*C-?2!=bDW+_> zx!52k+zpw@ekd=D7B{@suPzXkOSX`Dx+<``wSb&%F?RJW$NpVSIJl=7hxWEmOQQDB zzIN>CE5@c)8&O52wOR)`Dg1lv=(TEM>EfACUbYabDvRjSS{Gr#&R9`qg^ep2x`uRB zWQ^X`CfKnt5Qn%x>w&cdTz09e2)?btsq&oMjim0LW^5*L-iGybHM3<)3;GDqJ9n+Z zE`l}B^W__GeB9heg=%kBmOE{eVd%f#&!)aTguqyv+b9iOt!W*1WYT~*jUp) z*O|_|*%D;g;V$Pz6B2;M++GrcH!UquWOAA_XAXGMw4tHC$YsiogFze<6^z`hM69Uv zlWwjF@U{$!@$$Ug`!{#s{w?a?XYlS9iO|1z#z}Bai7LUbUPw-tt3`bK6&I_N+Hb!+ zf`=EPaqFl(ZXCA5mHoED{a!mBiAVRg;?ezsxO#Ct_IG=TIA2|nIr38sk(HoNtpUoi zjL=kJgTuQ@aQ@^vTsX54=TB|G*^^xa?QWbu(}5$~g9y470=|cPEOE5Y73WSZ7xBIe z;?k3yP@jke@}=k{jsu?CCcc!14tA3Bu0%_f8H&=#rKP$cI?@r&wsYX-s0|-4CsNCW#HuSr7HD?mk`FGRbM6Z|Q zgif}q@b}@VNUlhXrAuKhTOQ1sevPZPR&T*#3t^Qwz&eSPVM7T@GbNeM@LTRFj7a=QBoxP0}qXU`h!Ab?BYZSDuJ zsBS^v<${_`D+}q0F^|4WdGtNXL3LF|KX`fiSawc~fNpA91bu(QkeC#L_=I5k9(&XO z+l0PXdN4886R(4To01TO1cGvShzI<p4FMd4Aj<>T-fR`O_MP;d2C{a;SCNBMR zax&oS=Y#nR7s1Zn9>p|PQCTLYoK?$JBdMyoT!`bk!sW_B3v!7VF2k4F!h&oB1$fg3 zlc)IT!pzi|Kx_`!@$oYQ$^Z;IccAT8<@d3yCiW8hmj+g7Ief#BMJh_&Jdndhc`x|IbW`J$&`q;7B5PR2K;PkRO2RhmRDcm~1JhG3{m z4s`;w)MmrS(~(@NhH%6NI*SOjwlFqSrpJ=IHdY~++QG;`3A!3nU~i)fH)m^@kPFvV zn+#`rW4I7}jrAAzL*LHYh(J3J+UnEkSSzszf!((@f!Ni>mY%~9MtTbg@=M@OCk&of z>+fR&FLzr6kpru*Ocn)CyVncQ@Ji3nl z4|MW7y@^hKtZsTgx00xTstM;#*3ti~k*-i0aprg}jvc5VcU(o#ZpVId%6qn#(Q_8# z*#2@H*^`X}+oEu=FOpi)jx4$&;i-XZv3Ktp^lWKFTYD*T^5USRw5UI1@s_4ZE#EXv zPV_~4YaVuPUyfZnSCGqHK~A_0J9e~-OlMoRtRU#Fz-AF@sKeT|Ric6&`n4TL0o(gV&j6ud~_=UFVAc+HlpvEnE}C;i_8X) zi}j(Cn>+k`7`z?`4)&odxp0)^#S0bF^A;0?6~#c7`rOL+AKf zX}Qju4NdO7G7SCq`{A2w?063yJ&X-q5uj3qf{mKC{Z8~Oq| z!o%H>E?FFLq{j(ocL(9-#dg^OimhT=*{!P*cyC_m!=3BAYHc^3Kjea!`|$F`F><@d z$^9M_uJ>yJ-ZS``#E$p7uTSCYmwkBocr~8gEXDI%75Mz|Iy$~rR1D@KmR~&GiMyvm zge&Iskr($^i#fq3dd+dHhqToW=jqGKp@j=)dvNN+Mlo${KYb~?I#N(uY)CG^15xzh zj;71Ce7Y1oeY^vAZ|}ps+k0{6)*jM+v3>szjom$f+c)>(=CvIJ;64IK3%0DW!@A|B z*t9MgYgeTqCrK0G0eWJF&Aa-^zCQzHh%49B#b!U+SHmA!@C)iocgTB@*1bW*bz}o^Q`mG@{D+s%YzM$URJz4oaDVl()9S<=Zu1s28&#dbu9Gr`xEUb7WKg50pWB@er{)e~^* z$m!M*a97~)zE%Qm8;t`TJ-WhEto$OIjI(Cu5my|lN&l)-LYYH0Jip&qOXts*92XT?Xos) z;!s76056w~?+-O_oR`2`Q=3HwC>49AFCcLjVFn*h2l_nNBfy_iwR#bFBT!n9fHG2PzN8Xz)bCU2JH?NW zM`L*?_O3M{8NS)R)_bcAL;wALy2U)+7e5|5c^sQJt|9Oil8S|66|2(-pe%Wx7e&+% zP+8)JnGCG#Y6V~gcxBVaS-D6c=V8COVX$YXN(Lt)rto9G%GR5RBRJ zdU`mcI6o4XPB!4yr8X%aFW+3d)hlAV_ipSE(7jEdx(!TqXdY!Joc7L1SFhl8ark8$JtB%<|PiJiVHMM;F5I=zJLN zoe9B>V*$8)&=2SL`r_h|L;`;ofpVvqK6d)lW*j+0myP6LRy8LeJ6RjC93G&*i4`3c zgrf&rafiO}5AN<23ppM?JdCH04&%ksqj>)G1Rgy&MEeNDclYDQ6}lYV;)0!>);P4g z5PNr&p}Eo+2@(1PCP%S~$;EaqU8buLXf5f|&jmit^I&bJ3U5zq+Urskf(eHDl-&L3sj^*_kNKOcZzppd8yQ;|1uEz0$ zt4KU`Zxv1->maQo*mmLqU2$AFzZq9AbmQ8^9^Aazi`&DC>PEf_xqg+k8&@uG7mIHACK|6a+q-84*0#8z zrbq_~kt$fcXvVOxW$~PBZs*UNfwX8<)a0pSMLAt|SLt9?qZPV0iGa7o9ixq8~ zH%pFJ9^-9mFGEvPA(k)Cr|%lCddwlmn}O1@RC2sY$jXi*V-zV1GlU~iz&AuFAu*KR z%Mkh>1|f-*oDhtx)CgqLv6*yidQvFTNSQR2l@>{kHXh~loaF>`R#^dy04jrVzr?<` z$K;PwR8v(rj&3v~8UMVe%V&!WL;wALqy-c&!~zPA@s^eph{Y4^Xa#(Q6dAC^Ox_xHClC|6aM5O}i@7aIXLSDu6DEN)zdh4>>b zCXCL!-thKvCAh@n%IRj@xza%{cPl}6yI8TtH`Jco+l9OI#kzNMCmz$6=<_EB@Wqq; zcuBDR>WkB)Q+Q2o_bUP~1D6Y1e#aGs39x_p{wn^$1uF@-T+s3_1Y#bOst=zNg)RT` z{Uv<&B^XU~s|DQ>S{o)wiZok^dB zke3~S&1>V(Nc+9WdGqS9&8ve@mZ=L*cU#ogq+rYXcob!rlKZvCy45Avx2pw}1eM5e z`a5?t;}SVh&WFJvor`BS()I?@|IOZCM%R@r`@Z0}*Zrl(=y%V(xBK0D&faG;*DfYk zm6@3tWtN#_%OZ=(VwNmsW@eTwW@gDUGu!p=h{!c1*}LkT^ZKi|#)y$QbIt`?Yt3K& zGcqzVMq;MhxbtOLl68}@n(gn&r_V1>I=A70V)>j$*@pS^uE5wxg|rRPIko}n0QoWf zy#*K?pwGUqh(;pW=xEDAM>}vuAuxznky^vc+wvd4 zYiVVG%f@G5aOpTM3V4qZc=ZLiYz$;4J43i%HJ)KcaC0<*tHWiu*c-x`&F+$zlkG)Z z)tRG>0UWK_2*f($`p=rp1zepngDLZOIfk;h#=Y!om$(AXh zWb9%X7w{JAq8bQjqlLIVULq=%;mg~(GkhQ4uft7IAv>mo|v(%NCO13nUi#tg{nxU@vA~M6* z;^MhI)G?T$D(5Joeb?a3i9Lu2HbvaEO|UdvMBl-FBt%(BD4d_udYnFWklwc~^5S;D z$zlU3CVdp=I3X)~E3Aw+!Q#p}l;t}jD{3it<7PuIx5w zs!K#`V=|32l1SY$bdvVP^JE*V#N2xv#>GcZGBxD|;WJ0!%rBRQGF3VB~PU&JT)%9ijP8KHcR)Cyaw!QU>`3j*t4W^S@AM>T?nwA&L≷bbxe zVF9q?Wd&geLj__D!a5LZFxKi*X7}!~GabKc{5%&C;C2F)i7QZw!RIg6u@}!xjUZ-HJEBQJFS7&(~U(4q-w}Zs->Y&Tl zSXr9E@X~plJ9i2P2(Wwi?Sh`(9vnQVhl7Xq- zkerdMhZj;P0Q02UI4NF^;hmsiJ5R3N94i(d?=1o^`*$DQR#6QP?oxP7BcR=@ELJ=mLz&h|`+MyRad zp=cEH2^6uUSX|vLv7eN?2Hqu$=OQ)HgTO(`y(<$V0|oLNya(K!$qL+~j^UoX$7-Fc zBMW`C2hdZw3pYo?WMj_mirpwo+D9OC!a#=~T8noeJ#rtC;+)Xc;Dq{|O-KsckE}Fz z^fubzdiG|-2JS~;t}nW-o1ijn1EPbDqrAu$Z55|c7{4A70jE$|;*0#m-3WAD249ae zs44SDL$N-=bdw~VX{-%EeZc`FhipPjxH&o+gHW5Z7jc1GkrHo9$G)h^-idIZtw@cx zLwmhDDl@hr#A_#V(w)#+>xAN@&G2{Ig_1l^v{ag)AZ{%J-1nfe*b|)%E(G!|2=+dV zy6OmV9pz;OBRawzjifXgtX-{X;tmjH+rcA^G*Y-}bS{HNAM{z#XUe;Q4E5z=WRR6E zb!;5hJzPZ4EtU@M#yE|FsDrzG^SS_dV!T>`c)UtR9^-Tk@1Hk5T7_YPZ+~wg0XQE$ z-34fA&XNTZ9DkdYZjZ>oUGQ>VPaWAJeD>*|eiF7bjhBLR_Aid54GyxGhy_-)oTV&D zpzDXYcpv)hc*|Ds5s@AU4Rd`5yb{qs;B_K++7l$LNoAT_oP&w!X#uQ&*FXneb~UgY z;qnOrs}Vd2)?&_@X%IFRn^M6VgbBd!+9fd!%G$9qb>5ZU(>q4(T!#1L|$IBCIqIL`<*vHGR zhSB~U$<4s4)^3ax%Y+)o@J@n`Y5WuSikhgAB6F7@7*q4v?)@(F#m{@Hh z%F1F9AMb&yjz_SEhV`>%eU0yCeS=LKS0E$FQD8CBpGP2|_c~5Wcd|-U_>)J?1b2E* z^qMc8lG1)a;AlLIq58decq@iFiwq3Z?nVFgL!{#4aCa;My;Zwq^UcZ8WQ_NEqoZUC zx~ui+I1!^=&T`yYc^H$Vo(G!D&{ntsJ$098B#?^!h6`vb+JwFaGa4-EX3#_jYdXv@T8JqIyphG zrO%ib&)mFGNgZ50?%!*|-8&5g;5yv7T~DJ8hA+Dy%H?|A!1M+InH4dQO4$9-(UC7< zfV@&IE9DA;J(t48`Ujjl{v|&94}848|NZZzWbht6yj7CZ1P3`FGQtJXQSS6x@j((R zUQ)a4+vOxVylqeJ!eYby$ov_##>ljfa#U9qt(1EuK@zFuBu`!>KolNKBWw6pQ1C?RSbxqZ3pw+-D z&?U%frKnxqb(-pBAFu+i@)a|j)$=RUK+Wx0nW-2Z?nZgO7b>%k<9hxXNeju*47_4( zbb#FoyhON=$|4oTKq_>SVMgkP-3zxT*h(dYj3?F}-mN8QRtk98t?=wgtGEyZwlBKy z`eheEw-aw(cH-^Jc2T+a=%!>CzIo9`*K|nRlLxBp{@n(GZzXQfYx0n`rz;1oExa~A z9hqqkaJOF$6T{s&cwn#Ck{h=7^ z3r1_n4pHQzy}=mn@}YBEscko%k3?USm258BTD+ak2hnTzQk^=9s$=xoWDqDxi4q7W zScOvOHcD{iNRYm+Y*Dde1X}ikv$0?N#u$AM1X~8~P#TZM%OV!MHM^i+WE0M6V*$`u;pV-6|-rN zodPnK1Y>qb@ayxn85zkK8t6oAMI4%IgV5PT>aHyby*#;CnRsxz`}d z_rd)p0x-KCs;INCAZQb;X+(4TR=vRYCaGoi2@edEqNOEMaxRpU>P<^?BPD81VAIDJ zGkm;%_!;nWy3flO_u#7iDTD-GK}47pq9SY&7wal&mvb~kk;)AXa}(G`kRs-i-3>v( zyn4+JKH}#k@Dj}IXc%v8a}gHS7hz<)4+iJf;Pj~#q^OtU*wJNTCyy`3#S5F^?sOTx z?&dnPm{C{uk3cqi&rC@%>+HRAK0jl=^gNoyhB=_7$QKt*?fTKh;qnKpcnQ310^VAr zr9?@T0fSd5U9}s9fR{lkP*o6~2~P$j`*Yu zq6@j!3F+xcG{oyfMS%w@GY+G^@Ep3DLeSezL*!2O>*ipDhMyclHcG>G1zZB4_9feE$DKxBXoK4`$>Q>Y+`)=uT zqVHLJxb(dw)NK-V~MH46XuU-i?@}8vHqy*VhJK-d3b|3A_$Q zu(rDlOPfnHnp%f5`d?tjmQS&0;b&O9=yNPt{5h5`{Q}!IFOUf?KM#waF>^5nu-|(? zW@s{qry%M+v(DG(+TJsM9(i6}86WPbzZex2q=F-c`36colr7+qH93*XTg4V601qF8*JodbO2p85v0!>TgGBwjGLM zmJ_r#psm_TRBwMrs!XVj_R+Ajj~7kkh{|Q-I9^VW!#69(^4_EyR#vVNbng@FWbp*u zc?tn@;@rn$ErKpyMurASuYU zQy8e(PQ&|+q!c%j`rCrRHfy?3D+xxS7`VQh6ehLv0*s=yXe-))k#>8DqF}!O~6=_9wyrK z@#1kl9^DMXa2+Yk)>C+LFAH~uy)Zx^9&0%vpuJ6i9jqmg_FTd9M@5+IGA2-O!|efk z>Ue0h&~}a#@K)R&bfpnNA;#M;5~#P)^Z1Y=&c<-_DFXQx+#L@mMVx_w`lINn+=1I8 zVYodOgWj6`=%UZy=5Pcihr-cSu}h5W6a4`M*&U>c_t9u14#VwsvM7bm-xwlL5AgYI zq^eI+$CN`*tS10o7XWK6f|~?WhU#qs@@)bk`(c&;mVwDWcZPK}UCTarE-R&@y-y(i&Dh&7XpT;1uyrtjwXFdR z&o9Pl{m-#^!>9P>+fVT2mmiCL^X;cty=uNhCj@v|QAc4pWdWp|XCAZpu@Q{@bx_ty zse3BZ+NVs{9>C>{@C|-iD z7WVa1YM0^35LR&2fIEF|3br!O_<4DFDXM3zNP(9W58rs&0t$}NeNHNu zk9oMyQ4Q?JW!3rP>t6i$;~?nl3fWe+eFp=_@;-Rznh+)UI)6@`;m^R z{`S>%-0i!7+ubMe`e_as!Ls!rso-OH@hFQd6O#nyTiqA%`dJyC+>XL%1A(mljDYpQ zjZjj=2MDl6c=@yf_eR_?(y$kIhn?m4W{)wwzn#+l;%PN0;L8}gz5{nh{itK8z+|^6 zfqFZg_rtS?G@PgB8E)7|N;{bpasesg^BAZ*K%$(8YS6+{P-F0n5N;W57Os*q}g5_VjTZo;_)&wniCoJb&7SXV1Fv zjI%{rS|C!%IG#5pHBge}$He)Fk2fUL zS@Je(;Pvvcg{ueMJI>~?b2NbsgZJD*oIUnAj_Q4aEgSxdWs81~B@2FswJZOG1AD%M z`_+rM=50O0tfq~CEJk&PvoZx{W$OI&x#?@P$Nht8?Yc54${7u1*KqO7p0^(~cx7^} zZ~S#-O%*BL2sk@&3@<5Of-HkjQ>4?zU{!7eR=iWnRtH@^R*#uhxijI*b$%WOZ*+7x ze0|)pZrv)$&A>~M`J8e&FxVA%2m9MlmgkO&^uwsjKTE^+pea|wP%lH5T@5+P)iB6m zWQ7K7~UrjYDs;v+GQUv`&ipZ@ph8pCDqBW z71i6L;P_*os8LqMub#Ez(VbM8)N0JzgyN))$ctN#($p;&?y#rlXu^|QF_>uHhq3yt zWLpSun=x{I8}5>td`*BC6)h^4q0Y}wufw2c0Ke@b@G|^+@QQ%@>PaSD$4a~r_lNB9 zV8of8qn6%JGhRGM!OO>4^d371#6`GGYWDuHJH5|F`k$)s_;#GQA=p3t{80%W-HN8` zis^h4?h{~d^_b%ssbh9;+#B&1_rv4cY4lmN;K4)~COb{=_*N2~Z>HzTrgO3M|JSR| zg|53d5lx?C6)ECUjCI;!xW$Cja4~gqq(nz!1i1HamlG^$*iTCM=4dP(Q>QqRfPqE> z47Xa*cT<2n6X_Uix+F`t@82#X05;NdFkq>3q>{nQfMxjJyRBd>;HB^N&Sa&y6K>t0 zQ4ZBvEkBeAGXgIuUv}v{eo#-($%>bwM_Neb5>&a3ef^|(pFJhjOTcCD^7$tO=0^`( z1-Pt)AKq`m9fCbiw2hBd3V{3j@<{z=p|m6tmo6TWWZ@jEy?D_NSTO%Pu|*5N7h6d6 z70c$~!r47=cRq)RU?WnxHb_ixLu!gIf%lp$8%|9j5*+k|gt zeT&UoHcR3i<>O_geU*NE38Z*CP+K02#wuU5*OMY@jYm&gs)Q7ALLBz*4)x|rXqFb; zz@Fg6yQu zPUGQtpw6|x?hATuR?<4~io%`(FRNaLZ?^y#7^1QdZ=TnZGOrU?1a}7F0-^WGodml< zUOuiQSYM~-@0JdPA^)1%*?qz#1C?K&CktObsU-+k%Qf8g;&BbZwUi#;K*yZ~SW<%z z`T6SUn4hPO9^WeG*d-&e&opx2&x4m=GjQ+T$QO9AN_=ov#U!gmE42hd>h#3j!$9N( zF1fgKgOvH5YINs2xpZB*4x$7;R=+Yi#v>GlG5cg0#3~EjIDv3t zv|J!85iA5uetn)uW#B6CQv1C+JmCc~1YVvrRp4!>V;y*@O@WyeF@u*?Fugv2*hjOJ(y^PM&XY{vghs(WBqPKAa)rO)uMwhq1&~O_rUfc$Q3tMo3?ELx7)V>G49#;@d;GQyHE(yTCHd5zO+06QX zY{BoD*7knMuag?%iuy7J?}zSc$l`Fa32`;V$A-Ys(MA?fh~g!9s?}!7-zxCc0aoD4 zbpfn`?E7%lToE#frfcI;b0s7t#nBHg4#)HlVd=7EShryV92{+@z{{`8=h@XzRpf)J zoYQD1F-CWDgf0X97D=erjgc%&3`S$DF9h9n zmT0RoMQgnuu2*v=v2fXzhvRRX>Z8%x6ou}N1cGx4UOddiOB&L@epV!kll`#INg1;b zaC9IBnK4^%?9f~+TriJpE-9Wx2o1O>3h(vvdQz$-^!P$5iwRx~v=VA(XcABfoD5R1 zO9KR7v0)v28MN$r;A0%Z(k9p*~Rgiebsb5`?Fcq(=kU=a3lvqRyu_@%IB;)3BI02qzM5U=tKN=*Iz3Xt z=LyCM0>Z}+3G4(z{@fY3k4Sw!VkOE^3EX+oYfOxB_?dz_FLYsdf+$*EAVZx4PhdWw z^2x&nJm;{z=bdy7Uq_>c=UsU5qDNG(#C1QV(E+syjOls!nx~K1FU*s0JTb=#oa29a zAqKlQYA`lZiuTrYNv2a>5rxvCFcjs7qA))Ug?Yiq%LznQdH^yAu*!Uqn(Qs9AhWVU zWCx1$bk0&nmJuilI6lD#QS9dpcST^Z6Z`@k;pJ;b;I)RUy9JzFu85!4{;C2bYMmXHR1N#tqoCWvgUHhv|piCPAC+hsU>Xcv~y(D1WQ zKf>pqe}peS|10Lr`5L^hRiMXi^w;dcSkr#oAF(6&vi;q_v3W)R|upO+*m0R-~_Y`O!nb2Fb4#V0$WkDYy?+=DL_h=fcoY&fsfU! zfOm}AM#%Vi7|J6$W5vwROYLvjKiy7XW^gNrD@EKXz}6-R59&yc^G+k+OeAoeP!Eo^}$5>9skQn;PnD z1t2cYLsqY4WQ8I<^BUE?2)r%`3A>7GLH6+RHG{j`dANC)kXehn;i`)T9L3jbDiIFm zRu^GvVE{8SQ;YLt7hq*`8P|Ml5EfuB7W!W?e>S@rbzOS^wQ0v%n|9sQ`S*<4G7>z{ zS{)3-^ZVXxh3{*K* z%2(VD?w8zta6FQ35W3YM)?)G0HfHsrDYnPjxLyLw6GEq|G zfrAIvPi?;Vx4#m2JucwxB&k~(roW}({0q9VpFC`%o0@^8`EHd`mB}=Mt|}RD3}LR5 znk48xryHG>83S9cqw@?%1z&y~D`0kqunUA2cd#3P)hff9UV}oar(ysW@GC5HGZDNA;#sMlaHGuY{R9n`raQ4@dz@_Y|&1Y@{iKRU{Hpn$$3dy92A zbZ`ge%>Ei*e(`tN+2M=N|AJM^=YY2ckM^VQAY~P5GS`UJ7am1lXDqrJtWcM`0rk1- z&|I({JyitWiAZq=JR#sRWZBQkiyc_)GJLs>jTNaVTAnN;Ao9f7bB497Ol0u#A{hl; zPJSe@(l5G2`EooquUKRlKY!Lq$E@HP)C#uTCV(cB4uIVfq=@-78N3hKeL?W$*x(yu zWh52~>9NX9$4cV(vnz$UX zehYB%lmhRpZ@-dVa1}g%fsgnf9eB+MI8Ai3GI;A{CVhCgTsAa3escc| z@ct1#o+c8f%ae6HA;l3441(9M2)a{l1BNDpmra3JDN6-jR-11LZVZFh>>3d8a+C$B zVgauLtF&>X1%a1e<0%b=r`!ahcDt#wAYkxhk#>$1FGH7M%gR?K4*8hgn<#W$=$yPC zc6&^NmmklQaIAd!@w~|6{=_v5)NVyX{#wNNFT(lLE3lJ3SMI>Hoq_rDo%6#i=57;LLpa-PBXDnqi|uw4B<+@vv%9z0XUoHT72&{sT|O3f z!+nAuftOY2GwR?NhEEv6x&%jDGJF}h3|@vagO|bjl2q*rfodC_n*mztz|I_~v=28Rk44ZBvfQr4_ zu1f9PKbrQunMs~H#jE#WgExi1%PZHasw-syg(D|HziKbA)Z%yrgu48>({&wKXB=zr zoe5qAY6WY)RzX#%+2G&+T)XCrGiOiZ%(*j?uR+wX?ztGg85t?EfTFH4M$$sIHw2@n zEm7y=<>WXjs(~ljcydi8$6+6@ifUjN1LthuVEd7tFr|2NNo8fMLU!a**qP43;r;8d zcJ(~WoBK6pfByw$ef=jaTlg_f9$kxIw+#}1J6J>D9k@cUnc-@xe8Mq8thAxAZT?ER#pxgzTt6@y)3douYW-#*O z=sKONL7*v+<~DW{kg{cUE52Nv8-dQTT4k8Nc}>t{UoWdx_AfKE={YoivGNtOYl0!m z3RrV{kiwSt$jX<8<_hj_3GDp8aQSeO6mR`@w3lo^YS>b`u~t!swv|4MzfE;!zy8&~ zV>W?zAA#4+Y7xRb<{-jr9s*tFz{7D3b>uWWHah`*{ev`u*oza#4E0M}133q$;FqZ(@A^?3!odr)IawjOU)4B;q zUMTaDl<#ZZ#N*57YGm^I6^%Gvc8L;Z2+Q%S9tCH5K3-m~Tou$2i#vngLnBoF4$gkY zS(sm<0a4`%{&%?%ztMKKQp9^q*@e5@PUXJ$Jw_`Rg zp8OnEm%o9n$t>8A*;_7yhnET5z3fQwS_^!gTrFT_!QlNy;&{LN?sLqZ{Uv74`4ZoM z|0PzgSO8BKGei<-BZJ9)s?^yuoTu&Ga|F_}1n!23Dv7QHJ1*#SLuYR?xW=xUN*KI*A^D;R3HPmyd z$MUrdTZTFNhPB6WNe~A^lmXAzGR$>AC*xz)M$b(U7au68Lhb)y|L~LBVVG#zf!?Z3 zD51~P-EIxepW1{qE55}1d8ED;%)-)zpJCUQ**JG{BfM-E5_so|dD;H}bECyDG&+o< z$99lXn@6A^rADRi)lI0*IfDMK6dA#AXDSJaIC1=7DL8*I1Nq+VO57au!cfCL3^(k- zNaG%iHgc@8BVIjkBxA_7i$9vbI~A3|Q67BUP5@>9`v7$!eKMk9<2tu-R0uzwJFT~G z`ssOk=riDJ2-;jHXg_0RO)zE`2QNeBiMCred0|Ht#zreJLL(!U@3$Czy+vqm2}fo2 zUSvfthppLSY~Q+yMqQuFPSL;r-M`~^zxy@*`qw{U<;o>Eu=@uXpZyXx#!B_F;&rrM z1y65tc=*`s+zkw03s{1z&d)f~*sw$fOL> zneO;qBdGqv@lTir;F-rW+h5?`4kTc(#R>zB#u#Wa z!9cSKhFVOi?Ft4ugD}{Wh2g$*bkz*rv>FH*zM3ND^9(;WuJbiBpGP~Uy0{RUbkQ%W+k>&j?dY!9g8IBoC{13E^vKP~NVY*f?_-v59BHA; zksh{!$|Xpm&Mnq|q3rf+du17nO^@R6(H*4xK9lsBUwr;CoGjO&I8`5Q4Ke8LNSAbv zyg^WLvfF{5hkpa?>*Yy2&Fygi4ln2+WiG4i zINn!*cX+S_Lu9OeyV@dAlc$H`q*aLWTL#k$^RR#CXV|>vPuRBcJ8avsTug8G0-V+V z8kUA%!=9jPe}&BKJ6sj;UV(=S79Wf?LRvAo-ue^YeHG^zV&i7`+!{y*@X^m z12v=rL6jqdM^>(p@_U$x!G=R9PhEq|h?OXaU4_cj_2|BCh$r_e2~Zqm zz>`+&8eo;mKvYmvb#CJ!zNS94x&~SWU8PnTbjlr|8An;Xdd%T&Y4koz#TD}7+ZM7` z9XwgFl0tu)g(u@z@p#mRN_)I~5QW#zv*|igUUr4>>#*-wo4ixU>b14^rE^8l z{~;=zR5U-=)0?h%GUC+BI)V3{#S%II%cK}VQ-dy>#PrU9uTr@>=;~B2 zpVQn6tbAopHagGYW&+*}dlbfPL}ey#b{T}uW>UN@2~;Mdy^&NeDc^xEQoKB=Ho)M` zlcIvMI^jopD4qY;iM@< zK2|=|*UxfsyXzRn8@9@-wBE`M;AO$%Ek|W#m>SwMV6~w=gH$P2nY0oxa)_9wRN1s^ zCUiC^lWcEav%7$who6tGr^mf{UX2I+XK=4;KOXd*#N)9mcsy=_=eIrRz1P!q>}u%6 zvs<3H)3FD4+INuc#N94EJRCBh=d7k{=zWL+=I7^*fPt-3zoLp6zTBq0H-4|$|HAK& zkJ(MZk5~R^fwd@OrH;k7`lJ$1?&adnIOo`irSB#ht&L$QF7QM|xQ(PaJa^$3zWMq~ z{N*oy!dG8@4sQ=rRF#IHp*CKk0@|9>Rdhf@GMXDxBs{CIFbY|jL5K{uz{Lv(arX3H zTrxO-xKMqxSI~%MJX8GfJ)J4YPd$Tz)FbGn5zmu{rAo2#WE;Vk-3jb+7#%J^ake4y z61JkR;Vhm%$`REoZV7ff=t9h1z2u3{ZhAbs7+MI%T@vxY(G7PAzMRnhuBhMZDy`&1 z6($J6qa&Plk~cPurH&+m{+|$3lzJm0)dA@#_Vk-~LrSVYVq)CrbFoBtm>EJsOc4}h zf`9-c`1%^c$JZD>oR`y9G$Kp zJje+#VJ`0)f%l#I3}Yy3<@<1+Zr7b-(9XO@gYS&C+%#VjPGK-I*#Fks?aGI(cw74> zURTvrAuTyd(n4yk29=piftKN_Ef3ZfPcV43bE0w?wgO!RVu7uwWd&jlt{lg!L79)` z8Zv&IItnKco7hCtR*W}p#m%kTmlF@_mGzjn+efsK^$Yr4r_ zz2GQ^8Q`UBSn)m_G9;+(#BGA=ZG!5pwjBzpuWHma1i;5PTyV2>7rn>rRBo4RAM~H3 zYZ$!zoD5cmCf8^Bf%&zx_s_?g>g76@e5`dW{Qq!AqCJL7ZsSQgR?!N=9M;7v1vx4C z*hrbo@@HiQBP`64)Y?Am-n|W5wrs%OJv$KSbqoc`r*XY9Ty_j*rQ2AqLbB@WI4xrW zQc?mD9O5F|oA2Gb16ww4!0uh!;A+1g@d3-xP~|5vwf?@AShscw_Uv4W?8GDV8_1XM zUoFm1alX9LEiTT7o?{hu?_7@j~HIxo0Tkq!)Ab~{L1 z@4dRI1r~R2*XvSCa+38Dj11-wcni?mTY!$vTuCum!yQO*GzyAhkY5mq+`KSk=Y}FJ z{TkvDybu-Rj_^n~1QQ&u(U3hL&>4Q$T;T2RC@a`_mlGEc8m$t19e4?`qcMS(fvd8X zamfoU!s)RwVXi-81X;0}_4kY*J5~Oy5tQG%hM~(PgSWFj9L5F*e)MrS|FFT!alE{8 zjdL|PIjOXeT10~eQ3j{LR4WOh+@?axG;k_-Dkv-Cc7`ZFhL6?aiD?jX%&@t+2`ns3 zapj6JOiT=ESag|&NSCGVLDytuCL$%)4wbo=QCDP!)>?mbG{uRlfn#}jl1=ttBM1-n zWXtklj(Fgly*;FQdB+0w-;NA$&Q`Tu52qUBl}^0=o`;7#BP~Jn?8_tIzIw)4%9?5D zt^li)91pPxCJa-K1fb(L&+~A%=NN9b5YSo_d?#CW;9mblym>+36IH9hOcymU1uC92 zWAJJ!lF#dg?>exG(Q~lN;ti=T^*;FhD9F8i(}sJ)mKdquj)B^3=&9U-uJX;e(Rr3S zl2U?0FF~O}lJ>OI(7Q5o3#!O?SBRm;8Mx*cgc{RSCet*6%WaIN9F4Tp8RZQ_Ck(}rOBSU@6UoaPI*33tA&^`i4%R*3OV69EB^Sg~RmHf~sk z%s4$fzMDqsR!y+6Yl1_|BuqbbW}cwK(1-WO;bh|DZKy*^QUrlerG-=x3j|9l zMX53{8LR|P%~%1;cJDeRETE-p8LSLgfh|8?Agf@j!C5Pfj4oo|p6%GPYYTR4+klPh zS7FnJ)!49ZC6+9jhdHxnQ8@?aj?PC;_+pu0t1GfVTU|6d8e?UGjg>D?w)M0o32=D> zNuG%5CKxl2x$J69p`m6LczYh+LPj=1BoK2tL7stTV+b%1o;~8E=+$`sxCU=tHVG_v zD6T@d2r}%im2fRmps$MYV9^-VS?1M@MV1z_ z6h%pTs3+i7=ANheW&-ghWJYg5YQzRa`LBkH-8xuWoy9Q%^%q}!CKH~?Ou-K z2fv4@(SA5xHN>e?`w6-$v31J|c)M&zRrxj4lXB)&WoxOu8fWwtiEWO8lyj;}Fi?kvom{~hMd{~ik#{y-{z zwJaHqi*VPO+s|9L&Zr)%)yY)dRqP*t%|QOSHXW?<(*4kWJ(R)wqt6HJYRD>ZXz3k) zUBP><#fIp18Mal5SEqIrOciw5Js_pdrNCLn*cif^aXVkH!B_xH#^)4-$=rCN%^7yK z?3X)5K-f=1yUhgP%{ZvH6Ne7$!v1|b2*4|_bjduNJvtBBVG9YoD^Oo-f%b+Nbdu_2 z*!Gg*?WU6byu6H<6>d*^Dya%P)a2;X&3ptES;tYHXNv4}J0!*1Au-wtRiWnS3U@?r zlnZ(yozWBJfZk|JbcCHjbrM;@Wi(fq;_i?ep5KeZ%g1S?fO&$A{jD8%NH^n4p6Py8 zf|n0d@#IbtsqHv4HpHQ$JstP%HQ~)0R)}nxnpA36)w!MF%gUC)%RpryE5)nYC&}1P zs{xN8%#Rr)i1p#_-75OO&cX2f3T)iC8tVxdn>Mb2kIP=P)CZ!uF#|Q#afk}h$Km}y zVD6mnFncy<%=(^g;?0;GPLkXVvJ#Ct3iUeLYw`PG1j*N&UNC;enAoqE)^2_uJ{f17ei8%%@FWlI;VI{$4 zIW}xqE)d~v_S93S;e8L^hC2^;oI{I8R zm+hmDV>#^2=hORICE(>)XNK-Hco$*U_9ZYm`vsgVz7zPexsrLi?U%f~fgvvNyXFKh zUq^{c;Ky%#|Nx<({hR&TKdLbmsOM@E;>l^@p7&PP3bCis+oeX zz*H2gIzI*28OK}-WOXKwqvvFk=h7W>_?nrC0jV%jBdb>sG}dG9-kmsl^dL^2IE?LE z*JIU+g#_OD1YVAtURbMf_8U*g+uzb4pxhi|_57@vLqcYOBQ$N2PKd5gq>> zUw*-f!ati~pORw!l+JxZ*Zf_s`% zinYbqyK@Q54Zebl)pw+J3A}7}bK&oE0wLk<2oCc=K#(hZ{2k%RlWg901m4{+A@Fie z-ottyWB1m-V(W%KVbj__NN$=qwpghy2V5~E0 z%g^vfXPx+X-}-u3e7NA1s0LoSR#PpCcPbG&saS@i23&?Px7pZ`BIcEC0$E)i22#P( ze%opPtwc2FuA4f?z||SoIf}xRz`K9{9_-w`8%K_vz=>05aOS)L&R#fA!@><%v1}nO zoLGax!~>|vIEKb@SG3i~km`+<$Od*dbTw1S?goNycWVmTn-Wl4XoLc~Q8NkH;U05g zdGTwkTlFOtE}Vl^v%f?#{m}dW`@e|w{EvS@HBnFBYP1U>4}#wI&q)W(B;b~VSeSjZ2g^?5r}hVjvzff5HCpG zDIY2i-*vEg!%K-dQ&|xn--^MFes{Fid7{4B7qvCfsI5&wb#(%PJqE2!@zk;S&(4dcnYFcxn*k|APU{ zu+>1UKs^m_T_^L-^?VIqtK1Um9J?fX@ajnpZg(A($;qMG&FC)QfL4NUYxzku)6JS0 zuMeNAt4XPEgzc4eFf&|99n23fJU17{#)onK+;;gLZQs5H+sGC#noXa{|CeC)3-SB% zD!OUoR6s_y=AUcY~*oQoMGydtrKME{%Y`!-dn|;@rt^ zaOT+8IC11FI$ngZYt~3$xJD`Xay>y;|7lau{aGWJP8%Q3Y*TdxuGUtdftM7opNB=f z4nrT_AG;bjs-ax+@rL56E-j>!liFceR4PX}keQeoVbz*7IClKl4BxJbY|uc;aFq!( z4YmSYWeViez-D8`d*S>^Y~QgBr_W!6@f9nWSP+aYZDDL~gSXwm^6ex5w>HL!s~|6W88Si@c+Jj#fdzAZLqo4GvHJTj zkV@bkB+w52kN=Kt0&fr1yU3atyldvs(0o0DT~?whWjQ*E*I~5rkVGnQ3~xtkIu0M& zjc~dFUeZvR{gj56PT_C3}D*7>QBL%cU-ruZmzreTOe1`A8{~Wt_ZGff8E?m#rC|mH1G#$a65pRNh4Jqm} zl$S@*cd}cyl~LgRHEhiFQCSj<;=%}IXNMw`hI#w;Z^v&*@$xl)B2{(O{=6iNe?&uK z-hzntlM_F-Kv(&A#YMoOY-DN@O@k<(`>S?Q3CpY8H&n&w-igA%fLf?A^T_YgWy} zvZb@}-M4?kU;q3rcoj_Fg{#)~{yDAW?_$@EwFJd=s49=e@IawN&Tu{kPKeHXzTIFD zvmf^+?`o`;G;099MWZ8LLd;POlN0&qsy%^*f-R_|@3SCrEz-kRApY8N`TtUqJdu{_ zOHez55YHtDbX$ZVkHrXdUxWbHMeuiDgV0b5goL>wIK&zL*Bl7Ew(umi%YNRg&KF^8 zdkoe#M`2}s1QwQuVQzj1SIF$_P9iGQNkIFPMxg!4b~1*r0Q(&n|5w2LZds5KfcEQQ zI>l@L;et1n!^vcO_evxsgv;cb0GI{cXlw=>M;9?`U1?}&fYT=q z;;OYCN>cPtn}30T8-n)6cs02uiZ@9qUS7%8o-(C)YY4pgI`D?M&w+&j0eAVwm^be` ztR}^q`Wpq_A+kO)QNCoY1YX}Qi%Icrf`#EalqIf2XURH@G#C!1t!lzFif~SWi`ua#AODL5#K}SlDAolED491&xqqm9_b=qo#doRKX z{VmwAVeJ$^6-0l7RV$Z~TG@`0gth1>Sua}*O>|ws{X1nC8L2>VNh}T@-6M}<|KRWG zF*cSbQB@YMQ@o)Fk95NRgWK@uKPz{{-#_{bob1mMc=JW^zIf93p5o=tFvY+0G1TNNr;>AI?`#!NPbYP96Fb8&>`S3ugZc-+%K9eD(Ri z(*OJK;`7y@Iuoul0Xx&wHR>^QW`BcYhqqzdmNk-Jx34P`1Dqpdut*ZGb26Oq(NX~~ z?}ow9W!UmIM4Zq^P2ARy;w5!_tAa)uVHoNTKz}ExzZP#a*0|z&r88=){7_eyjLM35 z>M*^Kn`woNlq*O{FhOFRG2&v35EEsBm{=D?5Dd99<@~(90rmu62U5KbaAo+qSis)t z3Yj_VsI+x76XQh|(KO^wjP^ugl(GadhO1U;^_j;ydmqd?7*CrHvSeJJd8}DM<~4Nb ze7ydiAF$$0%_$P_mQ|F~7aI&)8*@^j){?Ns#>NT;moCEosuQYfs^RJ7iEn0oC-9v! zcP_sB{(H>&?mK)#$6tT@Ex!EfD}3?gmtsH6rXir=MICsR%Ynfwbuw;emj&nIUAAlq zzMnmZlrBNv-AByH!2e3%naaRzZdzuaxH^~d%6V_ta3Hqu3AFOA!VtOwTxA7 zZP8_MHRMDrM!f%gIGWDF){Wm`(W1FnJ?ASV|L)(>|3Cjb2L9*&Kp&O8WSwL!zx?0u z*|dt$X;9$hT(kn-gBo}_$x0i>$7|5lRfOWAX!!Zs;2@p%@wUOE zhfM^Q8LoyOd-3!x@5QFTTa~c};XVxB%>rKDAn{%BE*0<=#;!(d!CD!D4>#)L&O`0-3xzp>he%&gpUAqz+H>`%2 zGY#v9Qo)(Jcz0v=Gb;#c3UwN^s!f4)+TEZM@Mrq zy4us}voFBNP%(yj(=ptaN@|vYTZJ1VnV1;PAlR0P>)|eqhFJOD<*aJ5dqpiKZ&b@x z@nd6^lE0z5D;MqU*=T9WMngk7YHO2FQAq$Ui9sHXpt7<{={uNgKCVhzSK zk5wCib;{InqRwWX)0D9s&#ddLkigsB5CM~m2jBX8S$)XhEp%w=9)6uykc)^=KUiCt z(U8Q7hAWmZH8sZZQ>PIc5rqd2?jtfPf?)dtKK<--{OzN^s{qo=OzyIwQ_}~BfZ}|Nm{)jVYPeE3?=~S*Z@g{Buo$5Vt;wTNLzr!qgUR%ej z@bU|QUtll-Lc*kUakht*#U*$<>JfOCppwB`7f5QC6>r=WaA*2>dr0+mwj`mh#8@WR z3S*Wai{KmPK38^kJ-l}o4sQ7zzN@}O=Bl~KU%wb>E9M|+$=66&@CT%>`XfA#a$=H& zurVUor>sUd4S7dN@jic4AmLZMg6h!0T?nTkAFqBI=qu3qcN0bZ@(pNeat211Pti?Q zDU(Mk%_1w_ZaldeNZ{Rx{_4$=dp09-IjoE~k+NEg`E$P%cf*oJ-(uOKPqBOZA~{!) zvKF1C>t)t|r0Fp3-AKb|e+=@Iw!+kKE%xheho0UJ9NfPH{%-qGU+IJP)+|Xxo|Q;9 zpWzam(q9jw3tM1*c`IUr^e{P^49>Ln>N$azl)M%iHXVh*z~oYMEoji?Hcj#Ju{x)q zs}!)hRw>}AW2*B+o$?tgu)hm>ehxaOPKrAMj(B)PioCTY4Z(qiSibCA)hYe^FY(b| ze+PT>jR*@kK^==Vu6b;gi74}nU*Y_*PjPV1N7%IXPx$ncKM-iA)$Bh4mLdG}ApYj- z&#`I!Qmk9E1Zj!xsIQ4ebA7xdckgbGLvzJNG?nUOusZ}J{n6;CI)?Vj!x--N#?5j1 zj(R;Y(&K^2u{4S2y*XJYI~7lmjgD4hV4w^=-393E%%%S`6AksL0^X{s1eBGiZD>DJ#k%@HR%m^wPn%0Ut7W({hU? zsv)m19}!{xGP!0)(B(-qb{m`^@PdqKz{o97x=>;|A7DXfBg&o*Z=zO z_{A@ODd7F(uL!=s_@#jN4+P$`=S~Z3wI#%?dS$|G%IE7$O6>%eE?t79bB}x;Pp(uVC z^62r&*A^nyXC8vC&c-#j9f%6GBo)Bhl3anW+evuYEJT>|cL;a=9>GrEA<=)HBu*Fb zHXS1H780ad(cY4dqcpsaq8}44ykH-miSZd6)7OKihXouRjId|-Hu(G5fsVXt)`-3mIWcP?x<{ zTnqy>n=n|r1!FBo@#uCY9!w^qw`LCt6ILVIXBlFAmP)p@^3;v!ZF0h$n-#b@l7iN< z1N0fJKt7ECYBN_$X14Ci{SwE^31WB;Hsxwi3mvBSdSjOZm(xC94a};pK~r;0XrXc% zNZ&iA^BnujOK{a>9bdz)41PS9%I&~QbG1a~oOHgsD<83O-dMe6>C|Z8laK$5Yra=x z`<%2C4@3m)l!QB;cHiTw`7D@T_=@1mN!b4^3U?-Or|sw3r|sKszQC4E%dlekd_;!Y zpg1o86(u34t%}9v@~O$=th}>@d_5M4$a`w3cqiaBl!X zw}zlwgRxQGqpbi#gZZ*qW)JUH(UpU?woEiNWuT6erB@Sp%VSYk7=fJJP*J_<89_)+ z@ke5kf^Rqt->(H-g`c<^EMafC0v4BNVb9KQ>0bSgMv^~Z_S`v`Gk-2NZd!{VKYJv_ zcp;gL%Xds5tW1GbgRs^<1Gt)LAl4bf_1(4^$8>!WDPEpjGZ9yV<%jL#<*0_7{5(WP zT$9Nz8ygETW0T7`cJdS=qGRy*@k4}1go&$x!TVbp0{^f7>;Fyme-do}O`!XWfBzN! zRlxfTQM_l*otc8H#Q#c!#I)jNu(C_T!r}@Ihs-6;m%*!@s526h78eFEN+_?2iV zu|fwyS6mGoP9~8I3c4Il#!H9$I?~WuZG)=xjRdsysLk0!H^f0yX6;8=`aTpT??rKz zF$!{gk(ug=f^0t&W;-DxS`R59n~)Q;9VN-T>2dqfU2`16&8Km*_X=J^RP!_HNH{~6BuD3k zB2yD<3bYysl@iuq$|b{>>oZ*ungZr_KIZyN#jB20_?hNvVE2Q1ytp8AikVX{K7Ynb za@9(=fq@c&jVHEmUn3!3Z1d)Ri_mKZD9ZCfabYmhVhPEOmLSM|5!~(O!T9`l zm^=GpeER9%Wl;r(lYRU#so9VJO2;|{td$JmnQdgB&~==yaqa4bSTJuETpTYDd~FdG zZjZ!xcO=K#Aj*F|!aNrsE#U$Ra~zNqx(e~vmLVtA0A)pvC`jCd!o<}y0;BJ7xDex` zWfvJ_j-z`-jb4N6ck1xpOkM-ZWuB$ zgGBkpCk7xY#(T=w>wnD#jy9`cZ9EId4}FE@OFzNlg?|@YF#jWL-Z)qGPfL#VCh(H! z%6|ax&)F1!mHmgx_&w90U6dUtir0h{ueVj44nrT_pBB|nSW=A0@N2NMvk+HW*MB4X7Xt1t@$U@YU;auI@4x=rFYw1d z{Tb)apPd4)f~``&TBHMm^&cV~B+geIb5w#!@SEHL;r^ z0ez%ym0wqt1Kk<2Ja~Z92e#3$?>g`Q<%FKrQ1o}ji}kd}NI-slO(<$AqDZ|&prSYg zc)TM>YgB7fA^MUyHmAplmBva7=52fTXj zI(S?2#}DhNt%jgoO;$y(&pQEM*IB*zLtj2E$7IJTjMQ(%FsbLk+RXytp}JkTI}#wv zT%X*_BZYii)HNF`W~G{s&~p}(((NKO-XSaU7_ySpj1{gZPz73Pp8;Ccrh$_|%59nt zSG$Jm%IB-D(R{udjHi9T>UGrP)v<1IhAh(P7NwYz<%aWTc3|(Gt=PABD-EBwBHC{Q zYD#U<)|`UIngCQ4JEAnt28CHx$V@RuRM=(R>acI|{dZsEhws0^_p`pjm!JO?pMLUZ zeDVo{^$T$)eEj!6;G@6&QQ~{~y6g+)=w%L^yv z8-lpRKt#v-iLW;-!VN*e4sfzv4I9(%U~2F+P9FXg2X=piJ=^|@-CO^HlSgJFJkUk~ zS2G6i44VmBR>jk8KM!c7h^OJIfmYe{Ili_yCkQ=FQOeceZT(O1mX?)yt~o*1 z8jg;35|wbt&_Ke+A|u1-*dE`{nTNUa7hvV8kfWm(?!Acc434jFaUsh&e;qU@t>Co&X(<=IcQyFZM=ik|Uxc91t8}4sUm3 z_;?y4(BBl{!Inr(bd~tg2e-2D;6@A{jECUG<4VcZ%I*c;d4N?cuhZw5>xuCi3=WnG zY|~Qx>Ai2kiWLiJh`Ioa>2u=GYS~h{QCBR)(xvmTkdD`^SwgSxjPa3DsGSse-9JJ6 zK0~*GUZ;7=IEO4}$dW8stWsZd{)T4U9pqdM+b~?G11s5B>v253n@NhXn;v@|lf9PI zzHJJ+eBF5KQTl(1mII+;cUG5>}zJ(GjD( z>&R#&hKI@}(Rgo9Ar0X<@puVRQvzUWa!OXO&7a4UkKYm;KgHHf^RRBsd{MFs=Y56s zt3Jo-72jjolG&IyXBHNaqTaUQ3+U~bjqO{OWBayMI6|=Bvu6Y5&;K5O{?i}u$3Oo5 zAM8&vO0CYedE-)CF+G8VICm81+95r14UMc;por9PN%CrOS5#!})PXlsfwv|}z*|b- zEiH|e$u`aBo01kR6K!$v-UMHca<~e2$MtZqm<=oA?_qjz7A~Lr1{cqKjf_U59GF)9-LqCWxSu)JSe^#5E zvw^o;XMeAyr74c;AHg@@eUGi%w!zlcN~erf1OzK&I|lYuJ6UopI~CL8CCiv(8&jFc z7`T%6fgtR{ZU+La23-cOayKX-TUl9P@80d$ux=R)PcK1U#3Gc$uR;SUUiR;*s0Ma1 zsK^EeujXn{(9KbKd3!lWLk{{o!q8fA3iSngC`;ds_~1?S<6I8CecS0~{9g7-?{ii>YNjZHpa=uwEKmFt*xI14$Z)ZAgPL#@aHk?TN!QC2yFKD$4KktiHQNEIEm|YJHUk-y~7lbZfg#s=ESp%^KVa*kxAp9brh8Q+tVT{!=1I9yqQtQ1=W1(;#w@_E>__G?6V zufR2*vp8~SE582fGyE{?Q(QXnHJmKhz{2b(PM_L?LkG8E)8^ne&8h`BptlJYS5Cpp{T#uECpuT-is4$g*{wrv>}r%}?m%;6l=yiY8d3$k6%}#f z>n$f^02i{`AwOI)m}O=Ki_bSswt#oXHGczo?qhIqIsym#gRr&U4=c-ku(a5Vs}9Ey z8{tBLW$azJ3E-bNufbFSnc8%4=5i)%r_Ecyt4*#2`dG#4F!bU5MaHMv=atvJ z&d$w2d~B#BLT9xr8Ok{POXrtmh+0^hVV|BJ3@%>Kxd;?E8KyIBI?t}!WkPNJqost@ zz^j`)(|ox)|E`m>0x&CIYikP$qcS+T0`At!#nn)rvJI^@UZi#tWl~LZF=*wWYz4## z&~q`|pNEnDTuBMZ0q+AH!DuSnjoOS=D2QE#aF2O7tN$%2q0KbZ{BmlC;hDP(yW4I= zYr#61*t$W`dhxWDK-DSWNj}G3TEN9wA9Lq?IdvmW0a!cM z)j$2@FR-`RfyQ!6^fo(Vv^Rv{TOoUiaeOU@dMRsAuq9>6@KtqEssu^iSM1U4c%3DX zLXX44+o^a;O82>dmv=^}q~|M<9JEiU>wS9ue(E@JtT@3C^(H?T9FjR4mzaCSTo!%IhS{P)QWVnfySXVEEiGB3 zdKtcH65&u&lPD0bs!Ehd2lo3Gv+uVcQYPKf(gTs04B7g0PlYS;GeU1K>Pl&0XT!c%E4nrT_pOKk` ziT=scPZ@F%;Q^#xZE#i6LJ|nc1hBF?O@UEMkS=?qF<5n5^)OJ?Rz5DWeUFyRoR3-E z3Y2vKmSb@@s0?NdUiI7xxC~(~S$(@%uSdA+T%=xGh=QoasLa@pj>b?@xGAD^HHE8{ zyzklwsax6lhc~<&%E#DHfvnIP>ST*0wj{I;Ca_9fR}_2A{pPCVxX z?quwD=JE+|<^Du%L(X-MC4MYho>QA7?&h?H3?<%Cmv`r7R|fCE@Gf{YH-pO1rc0b6lr$%eS6S0|zciKCfjaa>A5kC6p&$@Ge!1Bd^N3h#Gy_XPepZgA}TB6QBlcJ4{<1Bzi)m70XP(i$^PPY2o7~2_+EvVFJ~=N zNzy&NZ4n>kiIg}WWdz)JA^cNDz?`!8kI5LUQ}r3gT%TF$tc1Y(U?Pn~M)=##hWHN` zyjLu3zCL&1;$agrv&gGXS2NAbjGtOqn338vho$8el_%HSgzBn|&B}`R@3)ZiQn#^C zM(6l?c`UVC>8@p0g*=X~*Peqz$CL}>3e4&C*sfeLkqJEuU7Ll45w5vxL`uMXWQ8t7 zeiX;?5_lUzWp$cbFv0Ex8iJDAW%#mBm*G3y$10bAJD4XnI+%~a&JeT|?Ll4kYE-7K zL_VqBFptGJdtx>A>{yKTYdLe(4_GwsZ&FN^pOt~I(s#rxosEIfg1;Oyt)GWi9kCmcT zK3+}Haywtc?HaVT>)BNO^|LHI=s$)#ox5?Ht%Gfkq~KKVg`ZFNdJ@7mrj$$1Z^#`0^W}HEGn}kwwIH|voU;mb(>PaiKrq7D<5#QxF9kzgLPqMZW8I><8KFd zFKf8CGk9%C@p?`{P*my+C~C)3>U9Qury)J_oVtF>rXKebrOxtGuVSc1AH%gr-gZ`+ ze7NA%{%q_V{^xlEgUx&Q?tZjq&kpR_vlF{_tCF*YsdASXFY(>CPZ_s!si(JF+O=!; zO8ai9>ru%jkCn%0&#NBKwtKhExGrt{oV#$%^Dv51PogyaG%9n>qQ2Au9ZivveT?IF z-*Gh%fZ5f+@Es!X4$E#7%GJQz0S$JBqM5+kkh2EYvsR1pEs9@`IRC|n3fP0_aBD<_ zm?6+@9m3t`A}yE{cFHRBR&2yz?N;3CH6w+{DwKDUy^cFKt7Nqj?;_jVlZyHpPZZ}n zA}z&|l>AA|o2UGM0$nj(U3XKmee&^NU~^>;s*3E-MC&5+&)%15(qRf{>N< z{X3kr{ki~`jX}&4aF2E1WSFusK()jy%4$fFtM|#B1Rry97tXT9bq&gF%DusPX4Pvb zKeF;Ev%Mh@bKYKw_a)=}6F;&Gf)|FoQTcqQC*l}{(;$A|2dvsO*mApe%s|$z=aSFy z1RsI(bq!uUj=_tE;dn{*;z1Z$I03bk&a0SX)e&f}5q>YKQ(%?;_6_}iV`jM9djfX{ z&G7O`30^%d$IWhI^w(^~P~$OKlrr8+zmvi(sL5O{yHFRT979sPD*~_Cz|GYJhL?|F z`SOMTpm=}IH1MukF%LVou9Q@eOP9@8;MI+=mMxiulz1EZ4TYeqBNLq+Iq2%lCd*Ng zF$7=+G3O0#Y)m8Nn<94oda}g(R#vFU2lo4>rUl62im(V*$>rebL+{(u3J#7YIDhsq z4(e^iPEy{xcdUbv!4X&(pMc@{LpXPGA5I?Kh2uwd;ry9HxaO-S;sm-ng**-886ehd zCS-r2oH4YqjCM}$ED;ck7fzY>T5?S1XO_#CFGi5RIqE7yQC}5? z=Ic?iP=a&q_O!80Pp0+Fa5W6~Wh+<10PjAVFB@Hs4HnY57<64Xl;M0^#VNFupFmU5 zej4I$L}m67T(1a0dvh#Wt4z^cdP1zP{v0N|4GFr&xIgYq!+Z7}zN>i0N6XRK8jR{v zE97UIAR*=g9PIXC&YUlFHzxyEcasWywHx*i`1F&%!QSQ!>Z+sB-A)|_z3&@iWw=XF z=RM&#zw4t11bTuZ1NMn7c{tZOX*(z5=A_&z6Bff)DO`SEyuCOlX3=(7;Efk~>mxo^ zAXZ>j8#8h?Eq)D#x{9b!3oF{Bd_gK$Edo)l2%dlwA26$5j)vf4-2|L~SKzCuP6bZ| zR;5T)o2GdASV5TEreUqMab2lbUVx$0EMKE3;+X)~UTYfss!k=nCsw_0U-ItH74&}j ze`v$A`vN8NxZpK4xA=daK6l=7#i}(AIZTYVJXy7B`3zg3Gj+Ur z^)jqprEJxzrDUpHxsq)OJ)Vs~Owbe~=yJJi83UQY&7o8bTvci?*G#U{8NWtYkPVt@ zqtRR&gVu(4*-3(Tm*9L1YBG((#WE#?jLVUJ-q?~AF8g(hFh0caEx;(%m9Ll14P|3^ zfNrjSdR%V`x?2L#*B(l3bZ)qa+A}adl0&d7BX!HMv-LV_lCUP8jAH0r zOHLy{ZY7dKmLkk+0W1u^#Sh>8S%G&3Xx|4gM>ROuoW=D@1}}9Q10@7S1wmHT5?ZF) z*+97ynsl&LZh}WT@Jd1!wmY1Ng|lE)3Se*2`{Oi*6JzC)NsDs?OpH}X5I-Nw);BsB z-{HOJ*gZkU&#yLtlMbord*!1hfPi#yh*3WBvM-|GDDTMmf6U)dbt! zJ6B`>z72FA&BxbYsf8fCYsQuh3y>0Zl16l9^t%qn2>*8JI~pS!87jf>U@?`Y7$)nd z_aiXwDL{LB9w}h8+KuhH#QnyK-#0ra49TfV{c=u+tIlRPbZ8g0Z(EOz>sMgzoLQoB zt<6rs?6N-29^Zq#JJ(^?&W$*G_89!U>=a<*e5c_%(*&l|mOP_vCUj?BlS!(+GMPr3 zDa+p0WFGl&!E0z_a$x(;UBjEVZ2fW1zJ0e&pFVZ{?Ag=RXV0CgK7005^@R&(8ZEAz ze{ODe9L5HlVR&}6>}ADv@$^cZIkudBOuU`SYRTTTZL4N$v6F^WCyy+}*<&kUaBeq@ z>C3e=KLs1hGqAQi4QmTBs;lEOu(div>hByJ?JmH{!2qsKhRDnCCh$gzl@|sgEx`>n z9_a(cck^fu1z<6P&v{ z(ro3dV94ZMdLE5kdI z=C6WanTLkbizrCigp}}g2=!ipD~7WPyzJxE!B%d-_v&;rYKoT^a&)$4km4;OAXX7b zr+u{Im%Z00b%v}=>XE|LTnoITttebF?g$vV+D$u7z~yblhv>%Tg&iZh`rtqj-NYr5 zwsLHwl#D^FRIn&vQNU^^=KFWG%|Yv?TpL_xpRn4(NBNi41Yk3PS=sBCZ3Ivqgmpe) z4kLT@vYS4~F5Lv%OmONz_@)bxLM2+b2R=2$Mn9&_D$bo+s4^c&cUv&^RR!{0-V$T0Zyjh!rf{<0=-Wn zCc*((sUFDB@*$vlAvfJq%DhZ6Dhsl_QIhA6io$ECDh@(zc?cS-BXr=6qA%GAhYxPU zH9vF7P8R5AA+SGpdOunTl*RdhIDJwNK3?YN@6M57dsl-y>T-9XE`L87O3tCC@DkD! z&cng}B+Sf?!2SFlv~66Bj!nzZxp_I-schY}5G`94qx|qj*ckHj86qdm3gg{&xY6f` z+hbt_B_6g{p_5c9?>y05AB@@xClusZBR<9mwl)Vbhr`K!4!k;J@Y-3PM0F{`LdF|dx!TXV^;#J+8I7vox6h*b5C#BNXm$AP6b=KN&D1rm93A4 zusm$lhOT_BpN;A~#AP54(oM}aJX9>u<_uiJgEV3oE|J``V zn~191v$rQJMKLm@*>5ay$P6_O?RwZu?ag@htQ{|25MT*ZCKe96J6gZCtt9Rb$ z^aZJ3UTXc~2}77h6!&W7^Oa0w^tteN9ue+D%5e=&=x@OBgL80HZx&7*SpoecTP2ej z1NI0F-%lUkfK!L(;KK2_aJD~)3+MFU?QVpa&3{gHSQI)aj5&HbO6CLO)LRTk$r|g<2lRaX!2HbZo%Jz_%)5#_gsY&YTq_aZG^59ty6$@GvxmKn7lInf7@6LSE0 zF}qM4y9{OVOW&5I9*)sr=)?Q7wRikK%*-w4T)242d({5bz4HL=dJiC zO9Z>GhM)a+@MW``1wXs*;BWsuysQbr=Cj~z_AS{gxLbS&AKM=gc=ZPaUHu-RZcC65 zafzVoh2mU)lo41<^8*C3Wd#9KR!;4;WxSJYIO?my(Nq&jK#h^4=UnDz`Qm`y7Ff~` zqO~CoMwgCY#qvd>u1gDpkr3lT3SuLoBd%homlbazx*9#`2fYU6DJvvNOnks1m|pk+ z8#XMJ9{=ouZ_)QZ{sq0dT)eys1t&vqBg_8N@34L8_t?E-BkasJqorWI?BF}vX^FeH zIR9!DVq-jT^5j936#3wKg*^&$t`K+)U~8>>yi<_<3Fxx%GwkKG3OLi9)!mA{E%z%K+9U&NP26-;nH17$2*Up(z8D6%iW)m(vb*b>>RR%7`ay z_?Q9AZAGMtyuGd9?rshboq2j%!rRLdUY-{4@UWoL5TMkLwdLslx6z)R5O zJ>kTc%n+t?>}ThVCOIYNGt%L4EtwKxTTC|s}m&ETAz3%iq*N8hyTw2u8 z%GN>L0qZ(i&0jw~x+zuPza-z$ToWbK`OR(3E!qE8dXhc$ zXzLN`I$JEvbq*rj=OEgPK5*~3lJP6fcP`?6sg(LWB+!>2<+YW_NueP|eh?~4Ld8|U z3XiR(Jd~7e7;4HwaGmOnHBo539)p%T0&YVrI+{51SfZ5m)sfT_A10Nto1QC>l*JYr zI_(#q6$i(Ax^YtVE%d|Y^nAG(r5{~?R}5;hx1%&^1@*Se5av0L6v(Goy6AJPST+x5 z=6;QS-L^lSR5ElK!d&M6`FGg0d^YqCtVWE_3e;z>LR-;#47ZuX=}}v!2G7B zbhNZ&qLtd38q?tJW-gmN8XKR+l`H39VSXN#mKUfz2lFdu$WF_~kQNr_sjfS3aY0Pg z&%?(0qL{Un0j$VuZ7#vi)=)}&J3}~KHG!Lp8Qfh>;OcAyPlCIzkBu^KYe^h$a6w-_ z(-)+U#Xa$clqkC_cy|l|FRN2lx^1F%Igi5>cm<>k*KSEZ&&#D>zF=1cgO<;++d=d1 zYRBvc=JTwG`FNP>YVuFHL6lFJ{myDRvx-xG^QK>X@AoEYlyY4UU1b|F(&dc4Zu&gy zQ^=ChLmkLSPcS-4cTk7D6%+k_n4rg2P!TG%G}_SIPRd8kVCF>aJW}cH%0^Ls z2+~u%kr?NOxJV~Nh1nrI*ao42RtWaDkO}QzvXB6(`(07yZ$@?nfxf0<;ei(PoA*R{ zQ6TbD43HMIh-`s`edb0iLLR|3KT28Q4B(c=)9*ZCDasQGydSdS{m=e1 z&2U3n%yA@#??p<)UZh6uLweL+q=#)lTIdR-lcj}F8MX#Far=-PPeTi`?702NP1Hw8 zt`k8wjE3Xkq-Y~Z9fpyyvW=Ls1_G-BZk#}ucbQ=5@+visW@w{hXUB`!wPQU3d@Zn( z%HV4@I7T40wmb{t%g1o)gdUpe5-{ACgJE8+){}(m`G*9&9Jd?kJs+1&eSsBAKO?m~ z59j88i$UGCKMY<5@BkSf7ZP}PF8cxc`&Uv2vjjDyPFf4sW2p5CII#^YURHE__H0Ie zwiRmg_n{Z3~E-c?2aIN^NLlkQojnU zIv=kEx0%8E52r4=yLaVlen4K zhpx7kR}-u3V`mt1edc!ZT<6Sr?4wse<_MN@<%$|BlS$@*-W&pOCc4|x(b|}Zy6Pwq zLu^$fhImBEqtB|6V6q^p)AyRMMyKUGI;DCAwXs;@(P>4FF>)i93UGOKDTB5sW(kT2 zwhFjQX95=$No>m*ydUn8;s5N<*Uw{XUUtZ>;(}ll=ljx)lRA#nzI7l|1Pj)<;x`-Zv|BRm)~RG+WFYIZ7nP> zuSQkcDgm!jye0DEX7KK%*Df!;Mv#x9A9FaVoj{}{+vD9_;PAn%*t2UbbrfrG z=)h(=-YiQ;cWz&fQ~JEpZ9f_+?a|%rP471fH^xa#>wLTn-Mgf0If1sQ8G21oF?16t zW8WhwTpCWY|CZef3|*dNX=zc)woVu8SydU2%E~yDl}1ZG2@bgDgezHD!7w#DgF}aR zBQenj$;m$Ow%-rKT_54%w%@>D>%Z&l*D%=rXBh1GJ1%Vh7#DYb0>j;(;?gcDR5ny*= zxPCVt-3%8O#+w(-cziP&Dh`PK(V)Z11sC-+UYy9CR$@$Oz{QbSQmKH_ds;!JgZDllpGY*Z{$!cRs zS;otx7KeE?*TqsBL6pj7YUlH8Ee#2DK0(@A$lB;yR<14Vw((yEH9s5rQL%qlEg9xz zqKzf`s3d5XC9gzI^fLH5F2J503$b?1T%1`t3(ddzH?;ox7ic4E{q-;D_+L@~tN#zu zKm9%SuKo^(^j5*%Y&B{#Rx9wfo0GCAmmhpsh!gbmwxhN>3AYH0ysgW~aGC5(!Nca` z$M)jjex7jIOdZ1}9MId0eS0=w@9quQPj!>aN2oIkAO(^|YJ_L9*>^`nMgpzo*A@5@ zgn5@*_UmfHN0m&wjDTA-HDT6G#%_gX0JZPo10jm;(#`1vdJBrtioU z16`@4b}iuQWQ_6QLfpGmi3fM8r|gNqw?P2R#;TBk`-&qes4iR7^CX;rw_U-M)vV@< z5P*_RO}_n%0@kjPx>C1OZU_l~V;iUE9KiECfwAuy8AfD8|=3_>`-%WJit;f03G|EkML33>+osW}y zm4#AAQw)iuIJ##!Yas817>B<01oXCXBCB}xwIyJnGf9lw`#TcfwlyUE6TCn7cP-Fo zD?#N}TT?39o03R%rV8x1PxP%2r8@}x!wDbG6UtSU;wQC1X6L-0GZYi^BElSo-`jFhc5Na=eO^E`zo~ zp!0W%SJ~>4%*vu#CKa?mx3zl3<`_lk((Qh z{QL+>sKO;H+>{i5M926bD8yaX^dCR5ADcF>g@eO67#l3Wv8}(;0dgi_r$PJvu>$eC zaGh>rP``Ulvx5X)i-W&ILF@)JRJg;<*$9qy7coS`;oGFpcp=H%n-#c6z<7AKhLkT2 zvG1`0u2ssHAf&k>UO(sTYNU7xRI<8GCd>$;QYz4@g&7)XHL!BY(A8WC3|Vf|K+7c? z!4{MB95<<)ARAF|eBC0YO7O1Yl4aory*8hF^RkWr${hheKl_Z?@60Ozo9O*E()+Db z*Kqw+6P=@L={-oCv&1oL{{#E8`SnyT4W9ht*lBHbAun)YW5vsUc5Ca4s49%4!PmC0!wK16lRHEEJ9LiW*5s4BS)pBTNLAJka7R&c#RcWY15^+>Re6$lT zUpx#qr%U1rY^aVxUZx*CCP41(_QpgM)8oqvgTw{J;hqCsX&59M>Pg24FK+6|pko@5 z_GG_pZ_4~|ccA#s{(^#hw=~wJ-RkMc643T`X3&?CjIj8 zGhjKN0@oE-Q$)4)6Q~8Ox;6$a!&?AMpyhMZ;H59^odptE=Wta8P*z|gIX*DWFC_4}d7$Ow{H&a|{^vTaN> zDWISbXW5V5+RZGAX1^hl}8KRu9hXKpL<@zKULzhbiC{MO=`}@X^ zWstM!7J&%V8S-q?=l=1Suhl@WscW9xqxZ)ErVd1wZFAHI|36e`HO#(nQO0DvyqqUF z?QIQFe?1AI!Hzg_d_Q8N-KgCF%7 zN=c#8J=b(ShDK%jID2XzJY9|8?`?+sOdpvT=eT=Ivy&2C#Jh5^FaPAR-LSfH5~fD_ zFe7WMi6qdbVyHWnpqqx_?le-pblj8mw&S1R{rSJ(5Wg+0ODc(%6 zfu3wxB{tHZBT&>>$YgB zwnB5Y4cc3xNeS>wG!3(;Y_9W1U6}>yO3lz*X@QP98}v5WW2oaQCi>iPcOnLlACUUG zSB{%wIRySh+`m;wH-9+|1zYj@Rj-6O@eq)GZalmjCwL6g`y7>+*kS@P1DHRP6zW`( zNO|PS1c(A}JsJDz2*i^`xH*xJo0Ao?!ff&eyD~~u%qBscL%}$S3a{H|U+(qVB=O_2 z4>vzQOi~7>rUnpfeGnh-EpCO#C^rO$IKj`~4j!JCaJ*`QJ^Qv|#mXf(e|kAiAN?Fh zH~)sWKmF@KL^tC@_3|`ZHzd@q!JY+=ff~DzUTroM0y6PBowyM0! z{5#|CoYk3HeOMqczQy^ANey!v&HMCOu?l|rkQa8;QCYA2z|R=OYE>G$BHr){#HW>b z{j8Ge)dZ^=vg-t54m)Fo$&h1Z%*N2Ea_XgEDyBf8#%6-#Hb)7O5;Ev0+tV(}; zT}Rfa>hgFt<+9-CR-ol$hOMT!xz0dmQ`b&k!{DYmcO0zd*_9&TW%bMd7pr}a{%E5P zNrCsk{+%$od=i%pPe>SFKi$LDmKWgbZHeQ@_TliMT?o2n1B3I2X%rTU^Jfo|c(IUC z>u{gS^4CxIVi}Flyxq;{x#5&pR87(**28NRD&HA!2qTaUu1SkQyTBvMB|e{ZH`zM}MJV*S7R@72X;rMaDS~CJ1UbMpU}Rak>E} zM~lQH{o-Jroabe_tT;JW0zZz2{JeaZ!@J~|jALv^`so^KQ@+?dl~GKWLzk16v#I63 zxdL2nm%Iz~T6_~Sa2c|E6Y|Z-^&4X)VhlPC@MoXt1OZL0&Qhy?c!;h|Jn(vW-lnIU z6n$5FhJ*lhwNuB^PO7_844k$59Bq@#w6*jF!^FXfD~0&YE)=?e&u=h6nc> z=`)SRP^&3=>rSAjMjw5RM)W^N;l_;`0WU``ba&;6dx4cMuhr+(N?MdcenGf$DG+qy z6TBr)Yeb|Q!opn%x>pr+y{zEmas}3;jCSnWgr&Q@3u`H6L^jH{2Ed2vyl|M9cGvJ({T0(it~9h$pmyX)98stT0CJo)p65r zfxmnHo_P|E)h`2>T@jo-o)4&o=I9qruCGP`%>v+K`g>t<Pu%`y7I=sGqneB~zR1K<@^9Nk7IP1bw!dpq(UR__FV6a-3jGHcp`A)l|IVhe0Q9 zhbi##jBk;EcZe4nkox5KMz+3gb^&A)fHO%UkjmnmzVy5|=zrsEWbDUf7sK6&cnsF- zp}%G`26#K2>sv9}xEIeJMyB$e)7lPeb$_n7()X9~p!9^6pIFP(pJ$Aj8;<8H?eJnY$tr^EVqOE8~ySt#GIg051@)5i?m z+p5mMC1uU;iQ%ij%a7&jSRJ#UTBnEw#B8daf1l1yCI}04lH3~nnXvfbFte(PSe!Vn zhe-N8q|zwp;DMdUO!F6UVPSq2*_nYfdZ;1QTuXKx{oQ%6vN$JDW&oc(b$~!?CLlJx zd>mH^#O7wF5FPGBsyPe>=MJH|EL`I3&z#(cQYtxd6+?HJI?ai}9E=ZSvp{>>-JbVP z@c!Iicx2F);lc7-9MZ&qy-Vui4wbhEw6`WobZSE_5xsqbCqindt(wl!(3pVB=?A%f zgVZNOb&?>+rYT_}0pD_7`S-+ipi{W4sM*wzlfz^Pie%%%bRAvGfMj(# zM#ti6;OC|v9VZ5hhJ4atcI7xg#Xh837z0>t_ouA8WX}nZxm_F>LJ( zVM#+$6SK3}ymcKGFIj*yXLsY+p; zR|s}mfS8~&xO7er=g;gDe<4roaExhvbu=1lV6J`i= zM?6WtgVCW<>R7oGE~DRP1z9<|8*EXQwguU7d+GDtE*q+{)DrEn><~nag25doc z#9nliac4?!o%F@)*WGybtP@==F367Gi{ey0>2Pm%?!}Ay5d_B}+4yv{%MsPN`e-iR zhg)si@nq--ftM8V6nJNXmK83;m+NeN%`H`Dwaab{g0BKBgO?x6%2)%h&P6e$fT<*7 zcUMhS99o*vB$FAhG_SLE!EACwPDUFCr><^XPEpO-`1=;XU_RP0+B8;mgpyPhS}K zjQ4Jly0}>_rGj*o*d1O)L&N<^Qol0v*TBo_lZ;g{Ls5_Q zH1d)T(raarYOO?XM;MAzHq!aE^w@K7x8I5Ul#}SC_cA(KiLPchq(`oThvODlSzbh- z+j>+KS);QvPoT@dRe4#}js)ypV81TMGBUM`Kvq zUV;VPjArKNVQ6#;8#k}P!o~A(=G$-G~mkg7c^M;Pi=INKbS{VUC|H$S5lcmR+E$%foTKia=ZwLl%d|x+HY9 zWyl02`+?cVKSCoVHgTZYt`ksHulxDhu7+-W3IPa};|f|eOvubzaj$9Ys`tV3`0cHEx`BdsDJC$>askAhQpRw;->lI`4+i zM8^%(OV&{vl{^zqKxVtotF5$Uj5k;rt0dg4h8e&N=c!{&A(L@^`nXyhi|c~ER5JeY zFm$I}3v|rGDTcIwnqVoZAg2^=p@esF4g-}|FHel?ypFwxlv6K3m({O=a;_+1R?8FI zIgs)D*D`|L7>Ytu(GKLruY{Z9K3H5ihoq1VXln=*aE_0pqrONF0j^7ED5eivtCL8J z(nD8AI);Z;{@$GU^`wSZ$x>V=>mA65(rJ>~ei2vAmm@pX zL|h9TF2>7zHSltrZgFw6xES*C!(}o}_TD1svRi?-eQ~&IN@fgu2O}MHFA#Lk;gZoA zoHIC%bsJV;!J>Ht-lJrPaAeyz1jT8vzHbVg8icj>Y4|F*PJ?&4ZMu~Df`7qfz0VOD zXpG2UOPnF-9zVJr3DFM7O!YusrZ1^qKQVSca423mLAZ*BvpfOEu84M0SDkHX1Pq2R zjbeKFyJHA*XIvzmCmVO9d1;s6?yy0I$-$nRQJTC0bp`wBG5oz$AUV+z=BB%4nR9&L zT2yDQ!(fM#tPt$%%12y`A$63;;db>53gTCxrFb(Y2mSEmNh^&+3J`qlG#njFNi`os zOW}Il?Kz0o&+-X~tY+ERouDaSuCr+X<~9Z|n|6*PC^WUq*D#1#0khg=AZs9I)3xhd z4{zRdBPr1bXHFlY_hpa5{4h!I!_ha@l?k|Fc253JD~k(gZcImISuBhUPr$*>5El*f z5#Vb>&@D!2kOQumo`&JYWAOE|07p2P)A0rBq@5ivW1K$Y`?sp_fJMozY8n-*@IQ9< z+~tul-LJQ4q<3ecn94%j94%mYzwPTP_$PRO?k^@LY}2jD`kTC+IR~vv%;Zz5KUVhq zNgJNgkB;H{_(3C{QqL*brwG21*Oh?$;4XofR4}_C?%w8=SQ?1wi(!R)la8q_3YqHM z^D=DtygKIPq1*X7D%9xXnXqlmI(XdMvG?0xAMB;khHYA5Gg`>@G7#p8LsK+YQRr+CI zpp+h)jH=wd@N`&6H~B%B8Xrb%&@MDLC8NK;lz!=vvvbAD3=0y2*GV&77cXdgUxGo1Dh^izjjF>`|;)w-O5$&ZYVhf$z~Ba|nz& zpw834s!W6COz7_CYo@N7d0q$D8Kq`&OyD)zKMUd4NQnkq!3q5xlGQ6R#9C&_)05qi zk>Y`jWDjJec_SyoS7JvCasp%~o@2OctD+?$rIUuZ3}0T1!Zz5SFRQjVMQ9&Ew}Z|n z$DD<|#Tpo1(ueQW4akXJipuQ0^w=bHcNZcm(iE2rwi1-iBHU{wiV|0$yUAXbWH&Wu zA}ZVf)|UFXYIh2$q01yRaj4T%Mmc=m&-*xRYzz_Leh`(Zt1#Z8hnJ6Y2!sq*1}KA+ zAd^p6fP$)XSag#=PDmAyAia^ObpiU&K!vZ;3c)K zt(je- z9Gp0H2&d@gWAG|KGEk{}2fjLZYOsChoPzOB0e5EGlo5C@?fV9SK1K-eGQ!bATW~;c z1A_d_5EW{J_$WujM_(lcd=*Iq;^cT&DqW;ZOY%T=Iw@j;aCu2M>TBcB(wHQnf$c4+ z=7?(9K0TdhXowS~w}+KGm`Xf)I39vXZZ=g)4G z5Uc>_rAQB7hQ=x@`d#Frx+V!Rkp{3bKLTruqq1dGLBbleH#if(%4oz9jjIm(VQO*) zSFLs+J!~;LDt6)V-4tD>G+sEtE(A4EH?4fRKJ%F2$}z%PJ1bj;E0=5xSvHP(;C9XR zz-?StzFtnVS&$bdzFyuoDl0RX)bC+rXNKTBb*{BFDR@rza%6-X?5I=D&Ilr9djp{@h<|T*SuPHydugeBMF8<&`nKQikiiB{;8`p_1BJ{W5g5 zQgb;-Ns5>it!X^Cs@t6^=n2?iIA6L^=v(?uWY>4C`3 z4w2muxa4KOyeL9qb!k``5MT=jM?=`yU4$hm6myGn1l`lPYow#mF;1% zQ)doh_1a~aJAXFxPw3$|shK0&XA>B8Fr5k5nUH;_jUdW^)}5OP-}mhu2orb>_Iw3j zHv@RN7~mj5mlK40yIn$nkBMZ&;w)L5IV*xxa72g=!h)<39AJsyKx>2r+loa;UL_Ft zAScToIhg?{DhQ^|EskJI9aTj%%Be%k%zSQrI=zq2qkIz&V5BLwE9)@xZ%3zj)pw6S1#fcM(8YscMQ=^XqCQ z16F}nndVy10L;+kcww!b{k>h1+nATM8ylS>CGU!>jwa$>Xm86wV1NT`tS=!p##1_q zEP`$^jhHyjcbGPVFXSd*Q3wc9uBsb#NE(zJqedD>Z33>1dmDOGHe;T zk9FV`5R<9;Oa)w{gDNN@zILSf5Nc*EInp1Csr=3|=iWKPQc0|0oa9Ip$SDu*i5( zK~Rt*!7N-<3lG!X+|1$SVNExp6`Zb`A~eVug*oA3`7|WU%?Ln7f)fp09S|4kjF@nD zB#|o1O7Wv}Av7euhKxjK#7Ed8I@}ep;ck-1JuCH^I-l;3w0Kf-k&cKCb3;s+6B47G zkVeD5?DSxI9^N*Eo;%_yDL*$vh1ek>id9|!4Zj1BnQ~3alz3kPlr=nE&EV!_0!O+z zE?hW_%a@PCh+un}V0+Q<7%p5qN~Vts1e~)v*s`)cb@mXc-2GU&dMW12`vFJkCOdv| zKMrsELBUi&%21sFSgn1k?R`_%%!KU}XmvJKU+~{>Vb_=NbUp{StLLD%XDxPaTM1|T zv-JNMz}@8%{co4xLMqgP)Y!R0ICuI0PM_E( zKFE}KAL|Dntq2BG2&x=`h=A#Z-+mKr%yZZs&WG$yq9d1-a5rw< zsz(z2mV)VbotqOTTTAu#7K^*#9toqa_8cT9_<-|=a3n-ffV~{^y~gf^WV-jdNW?sQ z)QG1K>S>hA$%|CX^ppE_(x%Qe2#|TH_YyqiroY z1Kphk6T^dL_a-N5o)cu>GH_M$??!?x!S^;N0jD|{1DB1L)3!8cWB>l0vi|%c4V5_& zNN^C{B&q)5$I7MNnq3R*HsEctTU%5V00XzKE)_Mk$)qadQCb#@;?h{y*c#&e1%1TQ zjT)EWhkbh6v1`{BQUWwIC%b5Hk^o>qHz(c1$z)vq|7$ZJuhqHKS*F;vpS6r6%?SKt zydRd6tpO}ePLeu44XZ0>uy^-*oI16S0DDljB0odJ>eFWkNCMk~0@~vz6=2!)kMG0s zm5VWZ&UZMhzZXZ3?Zbi1-%UaC9mtBRCDVZWli+2WhU@##ea8sA=XQKfpgoPNwx_Ur z$0}^uxD=LV$7ncz61G;Srp(^vG!2Q*5M)o%koXu(jP!BY@CXfw^>FCmHc9ZkbNf1M z-n0tGj_#q(&K>Cq{z#|J?B`7T9Dm9(xr6(O@8CZ&^&S57InA<@sB=ysSkv#dFf$PD zPDV6hI*Eb)QUc~MLAM=oF&^}rzDf$2l;gt|q|jqHZ}I3zg-+QrU|9_h$Rt{GV;Tzc zBk<}K!&_6nYUSPQ*9`6+f-}biYl?b^+6M{NJyi0w{gPvtw`JnpIB0bHngq|o+mkhu zL;b~rUG2GDqeEpwH^wS%(&+WcLjos9LcDm=g69O-7X;mxGy>*LQ5m=lVL3-7Ls_-) zIXV_lH@+Pks{E(o{kcC4yxi;J?M(1;1}0uLLv8;6-VT{`drH84bieu4&_MZESxI79 zM7VF5w~vdjv-AJ2z4w61D$DkL?-=);GhU@Wo_o$X=X5Ngy1Kinx`MeZb4EZU=bQ!1 zksKuFoKXZ3b558A6a_>Dvl1l>2qG$RzB$+0`};nUWmosP@4a#N9OFOM4j+`Y7wh-^ z_gpC?HY_wCCNeT8DKRl3GbbncXu;KkcdDLU>1b~)9b~STrp^kEm)53z(Ne;N@V#Aj z3QSD&Av-G?Axu5|$I;QA!q@FIwwd1v{D!79!9o0Xrp2{$(4Ek5t5dY^6#nrZJ(dOs z4kWRmReScvLqwD}czSPy^c~TVg3drkPZKOGjls=z9YS{vY~1LK4$Dst%%2lMbgb*7 zvF?f2uu+mmH&%ILmP419w1MDuPZ!v{))L&eIDjWQTiPMO&ei~&oaoER0-RkeQDTW; zb+&|6czqQsEy2Oj9G0ssfjM($fgL_S`&AZTtN)V#M}(*dU4>)TnWlJ8lmJ~S#dHIm zk1SRszAi!r87#pa9j^+|@-)avYu8!d4PI6#5at}9NZrNy!ufOKt>|_e| z_J&|$ss&ows-UM!J1VGy#tId%w>3p)8Y=@Yy-AFOE{Q$M!^43)TqEmZv_`^~)u+Pw zNFB!4{(YIjaAZ#;LO2;+brf3<;n9OL2*4-svZI)#LTs#!q2OvRJbQW`Hf?kSb2ELG z`s(k0fM%ow8XB&_>+W)PUVi5|T)DU#U2{2fqO0si(9ueHZ{HG##k2*_9rJUNcr2zc zDiO|)dRrQA)|K8oe(u=ejKn?J2_cyoG2T1VqTO<`61)!YPY<||wm|_`%a-P1XuSqSGB0zzE*8hLhM-VUKM#psT$UR;n+AtsAXi+h%;D z*<=ly)?32Hbr!GzwQh|$I64@DrG+kj`D%iZ(Mr(PQ3W;iC7`aplx+n?J5<}-A$ZC0 zjsz`2cKEfCpj8w;^A7;;XuZD<_v{FT)EIZzndl7%vcll>p&0OXcY=rak0bo^D0ZWmdKskMg%q+l}p)>n-h)jJ`1ri zK5WcxSg1Q3z`u{z-L%@72wDO#r6?4^OG{Ng9cpj8-CUS|=va1UY*=Dkuv>gg(B_1g z;EjoKq3e_5!`7xGhObUfj&$CU8ts^~D{=Md<5_+W%Ja^k1MVTf_9FBdY!SlT0rPVP zV!9@Rm^Ml6x2`s#FD78sK=F0Wn_cA=~xD0d|i3>c(A&%u;$3& ztlg23VSXW@LEgc^0e*o&{@WG68;rn3@Op-O`*=ind%H(@dAY>|2KuBPJ-qW`Rpr%} zY!?P0)j&>{;QONW7L=8pM(`qN*4Tls?-ua)-^vz*IeH|8EzwAT-Lz>H18#i6cJ?`E z1TJ+#B_##H3Jq1J&~Q&UbR-QNovhe!s;F3hh)v+&wYD(@FRxAD;l2TXmor31_>KX} zzd_`J#=5Q`YOuT%pS29U#>OiUzS>}ArH9f7 zOO%bRA%58yGuhZ0G2mL;7=yW`AuL`pAAXuO1D!rX%^KmW`y&UVsIed`N`x{4wESnr z>R{v7<;SEo20x&~wL;ihfENDS)t1kL4Qotc(>illkEP2hBUt6Y7m&BN)kEi}1^W8x zpp7n9Q)@Y>uUG;rRxCvrOMEnfH&y^|LfG2W#0Z!4a(_?LS?TEM8zbDnX zsNnFfmip^2-o36E>VJEm0hew6Pdhi$2Btj~?3|8ik$5&Ts;6SG@%c>&yyHb}T{(jH zX%h`?;rmTdWs$^hPa5t**Exs>`m3Pg?z!h!g$dyip&p@O!CnO3px{6PuYX|RcDdt4 z@cJNleSAD3y#(-jdb-B=__!xzX2uM*-I_?O|BBEZDG4Pt0=)vCHM0oP# zDm;308FgL;UfMj79Icg=F$4r`V}E?XA#QN$bS7kFM>FWEs;NM9tREc22I$~uiLa_F zASONl;tdhx?2I<=-T1aARH<#Gor^T*o9pS1xpK_$s|S zEdbJEJs~yL3zDKdKx^e9Ff>pDQYaU8rGlHxU3g`4j{D_?oyn8U%+)yHccf6>ryYtVTolly8CFQBI#Ic1uK`*bwYPPxHg|oZ6 zq9TKnBO=1w!ox$|!@@#5LqmhSf`bEng3$3Y@CNvaju)ZpiEfvHH(CI1tcS<8I8^+J z4p+0Ej`I{ya&(Lx#Ryyww9A*xhK2Kg1RG0Dbgx=qVTQ0ZQU^nQRWQ(74!Sxj zps7g?7o9NzclmMzwaR>!YH-0<@pY?h(fJy}+SLf&90V_ZF^vshdUj(2R}_2Z?*Z;F z)yabbc(W0_2-Gu2V!+GQ5gyz*0MJ(o?ai0L7acE676}d7%$94sb~PJ(5XLlFBq(4r zq$c@8{*~PbUTe6PzXy&SN>!>!`O_&2)|>S_uQyyqEs>uRsD_Q~6+VydAIIy>*b zICf-bdUW`9_vnc2ZV2CPv5^7H@pABnFz`~EAuTD=IU^;?ac5eLLuPuMZ5D!ecV?3L z-rcFjd$N+v(-T6oZshNO^R~O3!xo{-c5Eil5_stxOLD&b2;P>4VhOzCMcwne9K14T z%fZW24pfN*mC*!;t?7e>=hh>;0+ES@cIV? z_yzhAc>S2;jbM(~%RSoDa~OEz{I`3h7hOO02%$UF+*AThjm1Faef)z85BGvg7x%)m zXZh%Qudr)*dAlGq)SY#rQ3sos*Lt?I!ukykkg+2i(lf$fBSJVf&L5&<{Jw5U-dX2hyZP{jV^{rxk(`62lw*Olwac|6bKocq4d zea!JcPKg+SG89VNCxN9OKT6x*$1I4451HJm|M}qu6t_7MiG4y;XHf#^OO2@m+ZZ0? zqMJ%n2hSb|$c1_VPNDksZBq$6$?y7M9n*cw&)L|HNX2DL1|BHrE*?rtyJ?#N*qkeh zLkBqe<9KFwlHRcs!VvqVRNl&IuK#PF+bEk@bkNvmAh9_WY`uZ($F2OClSoj{x+J>+ zSMRgoX#u?BBTBgpIzc%kBYOES&gJL@e6s7!j%ODskssH5mL+7|v2QBY=he-D@Dg47 zHwlVUF(VjEl-?k0H9WZ>I#05p45UpLi%vW$;W`3SwZ?Wg2a3yseEXWi?=^m%^oSK8 z%y0di%pIFBxe`*(p?us5yf|kIGA*;3luVlo)YMpOVkWu$sQ^9;Op87vWbmUCU&HsHX@1V_{I+Sr(n0!T+NxU3Nx4kAVllAp0cs?cN zqn6;LXor-_$dv)HlQ(yxvz6f!|`X;%YuT=h4z~zxaoK2U5z4klWAG`o{bzfrc z@_5cL{MS|RsVUN!*kw2oyo-tLcvY&(z6{$w*=zt!Gl)SQL!QkNB$OQQy@&U4cYQ#@ zE6*wk_safg+xehN9G?4N>Yfin1^#s~lpCR~D%(K)JM++7@W-!b+%iF&14 z?}@h~_0edbg3&T?I$T9i9nKUbJL|Ev(q@p#3PnDsgOvG#CimJx6Ve7uUJh(d)g1pw=8f5jySyAUJ&+h1qn zpG$AA=^F@;T};0mZ7aUn0)m&YQiNkP?2_Er)=Pfr&39-UUI>+czS!u36+iouZhdBN zK6Ts@C`0yOk%~pD&lCqLRL+deCQl{MzQaN>vdVL*%bpkG&vpGf$zV5^W&5RMZ`AM9 zsr$P_ELptJsh7nStbOju;d}2Z{1$bOe%a|7=Kzo=B|Z1|szCv!(lqWQ^%@#d5bLjA zFI|U{BFKj+$|>4Ct-r9-(XAydGE*_7q8xV#|AIAW;mN7ySsPoG3Evy~_K$j`Rrr58 z4cA&ZRgu70d&(#0E$}7^SEKs-2QVYYh;}z(V|p+)z}GO=VxfT{9_&e zmJ%s=-z)sT<9Q^;75ap1`8-7}>rlIz(@@+DUvv^W;{~C0r)bvtHm&rK^uolQSiRw$ zboPD(0q?b+9rA0X_}TD_qQv@gF$%o8p``etIvMsElkEZD%wRn4?V{=Yfub(&Dfd_A zws@XaHhls6%-(^mj$6^nC&xiBvKlVMh4xXp^WsTU+J`4}6Le`Et~ zW;n5Z3+hlL`r=!1y+@O>+&uF@s|dNf`upD15b$-j%ybRTGYt6!QVYEH^l(DvS(p7} zj~6B+ZEwGe0`Z8VAGr(wi0OYTdO@$$!Vv?xemmm1Wkb0v8iOd@R2VxMf$OrlRaZKQ za7ix~R4`H31Um8N9{W0m+3_&tTL zCO<{1)N0nyNh-tn`6VSRQ@>rvqQfjn@PLQ5zyD^|_nrTkz^|(~ zh36%?xqoUiE<8g4Df@)}f=OVFCb3VzCvv+#Kj+5-fwGCrQ@iO);rF+^Gc(qSx3{r7 zo*y}7L~%rI7bw=KREoTcfQo@}O*Z~t(qsD&UXpnnYKmg4av69}eeS^?kK7kJnOohh zerrj7cl#a#5sMMxp)J|K&)z79d3wH-I9OyNA|WaM)FSy#N=`c|O8($$7spk{6N^E= zhGIciu!iZ3K)eya%jhG+^F+_sG7H=PbV=WC*qsx@I!7%!;Zdihdc<~rBg~7MG)c+} z3KYh2&bah)uJLPTFjQt$_aq;)?o!pvGss#cK9$g-@ zkuYRLOzs{3Ufc_PzJRBO>xt-!} zIr#51vHP{5_bEp?^TArg0*Eoh7$8=#4WCO1{FI9V{%+Zxf0tgJFS7O%E(cz+A-gjtDU)yZp{vHxSA7Tq>Jg+)~z8%=5sq{Vxqn{+FS!!+X>pqnfk4pU#n^wWN)82dR zvx-#ybrQ4Wi0%K;tGrQ=fV!vXAre%1sx%_h96ss;PNscW=)<@29=Jq@vDi zW`#w3J5Nu*{r!^NaSu286dCtwDmq`0i$iJoi-&nnND5na?r!X;E6aZ`uie;G0gdeEM2+-8RiLvIiiGQ6x{n_5)d3db=S#^3de48sBgYX_?D5||M&z9e? z%9c5|dZmr35-ofrsOvO94G{SdrEA%a=Ci0r@nu6f^!4ff>ld4~Vfy^(qnC)w3r=sq z16G3$#aT6+q#G=3z|@BCZg};*HG(kaVt`J>Iv4mmCZE#<5=PdrcHKJ&=@31do~2Fu-LC|y70Ha`JX`j+<2#q6gNMI0Gn%#qrqv z>$KC#o2Y>MvT}{JUj6;u^OO>c9?=TFzn=*|S!7`IB+g!&V9ec7(^Kc*t}v{M_JskE zv)*_t+b-_nCDT;6S8CLKRp694^H2EZnEZaHh;g120bEJ|m0=>43?Z>~xXqrmF|J0q zFRa9b>1}|&2?53zy|+`8sP2e~e^*RFTHlt9jq1nch-Q-y7U<-?Xh%dR@_fft|48K1W$Q)@}NucLsP=mbCXH%hR> zq08<6YLw)!HoxAn!gh&~Y@LZ0M>8rgRbwFm!Jnb|wZVwNrmh7`n%mwNcP5v#KEh>1LdBJ{<3?3FZnmQ;rraBvH=w%+OCGpGwR_H2tj?K&S6 zp7lQ8Q;Vy8`dr&9F&T1EdePuWEl}b1TyjZi4*qMpi$g%3(X8ebfmfVFG-C2UhIC^M zP7iHv3k&AxhDwzm8%{=lxHx1u8Jh#7;Q>p`bI<7DSD=)r1AdY|y0q7&EQCuG_{TS( zph~qbqmoZhdmIbW^xd12M8dZKT)8}#;eaetcX7Y2`3@cjZh?Olo}W-*j>$j zUhm78wj)fVV;TH0vf!ZxT=)V<`tIvi;{)E|)=0hjR%muADqm@rg>c1jCy=BWut4xV zp4ggvg`MDcT=3bu#@l9k1*FZcy~I2@Vu#Zai}%^{6G1<%vTeveaA`(T1e3vbz*MkF zV}QrRncb+Cl|Q=Rm2CiFuIp)0S1nFRmsev750`rDdN60R?DoJn;6;6?Ie+IG_k8Oh ziDe#X@ufb2m5}U{F&bny-Lfcl|o?kDTWZ z`qXNWw2$lZe;14AvXV;i-jy*jWts*(RCeFJKA)uY@X#-1`Y|qj1P)!DRWoW_?u^2_lf=0ntK(=#K;LwA=}BWVEK9eXA|FMWlLhW=%>j2ziFv#sa>nvm|Th~-Cn%e zj$ZupU%hzUE`>3_VUf|?ZP2xTtU#4lhviSK6Wk#39`N^e%Q*XNwnF@J-@yK{>%DAY zG1_S+;*pcD$Vn49zhZ{;!3zsqt>k+evzJ$7|D3`IT~)(Kb$jnB0X)rGAX?4!#0=zZImjD zovLOr(n6inBxDfWTm>fzesq7oIi0XYBLEn5bmS?hsuf}8z=A@!X~m6=lywYj1njFK z_3XA{UaRtt26-ybi}vll0qh4WkUlfk(ihY+t>4@Y(KZWHH5$JiQ$)Bo++425|MR|F z#9_|eL&1i~ZM=xtU-HH<p?YqvwCP0Un2r{DLm({YKeW(!V`jzn=75(^E;--hVSGN~j^?46M z?HQ5`ghbXSvr`OoIGPOlYiAFbUbS6S6}+v7TjCzfxi(sR2J&6??k`vUoKXS-YIM>R z`s&|E4oTW^M=UaZbzt2~B|7tqO7!bU?Dua5w8eu?p=!nf)HNoBqkT66m$sb#kuf~U z0)x*``Kf($Qb7u1`I2mZe@ew}Rgl15@2;^na`h=H4JUhJlRB<7ll6n=&xr5!_b102 z2UCEojaq&r5Z~r%5)?^qw646i`~k2N8UVcRtkV#yg5D7NOW7pE65H59r72NuxTj+8 z)ScW^mW7w`U0y5|cUR(EBbVdz5ajjJB@_oKPNPr%fGrur#)=-@r8zIm9W`&h$9W1J zEn@jFx#bC|o$BK=m}Eo}GXRdOKAPCC$IUnJ5r~g1b}|>8}~VbT&{j z7=FGOdku{^*Wl0g@QR(nJ(kCrKwt|8cx&nN`|-BkUXnnkA5mXAez~a{T;|Vo3>g7G zQ(0k=;i;2^4r~t6l0kDi-Y>cQm$MpJ_zJfNyL3wlA++!8Fr8@d^{41tmxP2j-@W*w z72>>1&!xeqQtU^n?bw3dHfAYkLTy*%2n?lXjXGoSMa|^ccr&uh!UrndpAYol|N7J< zONGn&NU^EJez?y0zlo1;@?Fc`y0XpPGLtmU; z_8%MNEISG!xel&n36|u%T2*>UXrAF}NqVqT63T{@SqRd%-mwaY^@b7Vu11ojK8hqT zzZ{P(R->r#i!`BJhPjj5-a>F}gh@JCVeA8t-YdqMmfk4Ym0is1uPOSFJGsS^P&!?A^ofM4jgH!~7)%%`A ze4>kT?w`e@!$(j2+r-<1L{q;|_V7vzq;CZUl?|bb-%6mrae${kUL60T?8~dvcYMD+ z7h5f&cYT(6921S}L(Gyn!)dUaU*was+U!YPFX4pQHVS{u$dLlTc$7Lay#ifa8@cEUhy}|&JU2uwX zfZh8|-pPO7kd`$gl5{X7w4=#r;7r+~GX{>zgIg$J{33v39l+sOjxnn1xHo#MDtZ2G zoMuyG)Rk>G;i767SvCFLqs`-dF{0yF;)r&1Qo=Me2Ha~S0 znzSlOM1S_6VbzX^2hO^mQ{b2QC z?+-!+Jgowxd5Hr#{E3j>=!;^))hswl5pdi^8h0Gd_#`Nqc`x$)Fe|M2qY&G4Hx|}B zqj?jnOj|shwp>92~tdA}_ceFSMzS#_OKgTy-F$~V-U z$?s}DFRd_Apc@Zo;Id{R`A@Bb;OJ9nwCYHpOonra$-ZZBSe5=W;^~jcVhM@mk$C+S%{Gzw@H%+3_E2p`L#t4X~E+fYhm$wbbSLHq!KybmD>IvB(+2 ziYIkm1HIan&0Iq(mk2$a#R;1i1%`DUz%>2%>Ilo6ZW8}hoRkUO24u&;7PTV66?K^B zlxgsoKAew3E2*KRo!j>Od_UKW95l6SL6Nj#AwGWB+9OLCOuu!z|wLgVG~t8-tvSAjJ29UgW?*O zoYvl*__W&QJOQT_E|Vlu!J50Ci>gB=ERr?bSO(!;TzKizl$`>_pQ4g65`qmeGlFSrGC-3-4vrex++gs@KsG#L6$Ne64(QL-t1A|sbku=6ZQ zK$mCWM??OQ39`Zzc6?ii+p&#x=VqX^6#c;ZV3Yk~^9%R?7B&S|;s1_%qvCBx;dxME z5GDNPgda`quQ`14ju9O6DD{$p3^wB;`yjRnR*ey`eMsF3tauVe(s#D~k|49Zi80LO zFd_cYyS}ijchAt{^ul9gjY|zevc%&8`KAh*tI8po%$6YDeSFJG;f7X_HWN)8x|V&YKf^Trne=}B{|1-?}BgOT-o&%ny>vgxB!Wm(hzJZbnCRZ}B3 zN6AFVL`(2tn+y73m`kS^RIzd5fBW!C4Xp)Z z@7$0Bg?PTX(v@yJdW+DWtp*p?`Jq)hLK!=ACk9yjJG>O@-h9~Oj|w7Q4BGKuxYKR zbUoYpqRz-#Mh@1&?gz&5A8`0$4?`{8OFYXmu&q*vb!&H9+b-~#qKXoAKqFPyZaaPm z2(j+wsUVlbG7u7)7ZS-1rPYy)OQi7oUqiZQSGvOg^SrSoIA`Bc(FmMyb93|KUfWg<|Voye}O?c#rPFWQ687-?xA z$2DzV^zAmW!iFc$|Mbf>YYiar1?m-L?JZJedAOL@sh2qged(TSDX4?9@yp7=b`Go# zCirgRFh!-=9}h4$bek0TzagtJfhCjX%F z-Gt1Aqp)VFaU`^W)rGNhQA=x<<8y6Je9-YJlS;-Fb|j8Y#i{$= zP_ThvepnE4J-B8O899b*X{*}=^GhiwMP&_to&@C+LYG82F6(vL)3O>(4UqZ!Dd-IY zEL69YfuHRK4U`{>HM;&%kNjt%;^hjv;lmZdW`U!uRZLw|)Ahn6CHrjOim0-MPlm>$ z=3X!k2~|%Nlv#s#b-U-WXO~N7eayx=J)0Pjm~9>eC_-cH71bNG48LQ7?Cp65c88qf zbQsBHlwi+*fHHOQK5;biQQxYcD5mpwbR55%d%XbZE83BU=aQQYf^CiRP}C%qL9{dH`ryMiNMtmJ3hlrb50^?qm7lsN{Mc zpB+*4HX#OiB#&QY6hWk#lVDVk`>^8NcS0)I#wM6xSQlmU9(8vS^aRWhGdB|7&kS5X zuM#O7MRl1lnzeev(}cI41tVXNoxhA`GS0MLEL)A~9C_;xD=v*1O-xHksO7&{zE|t8 z(fqadd3GhVFH{Ohn%dR3q9g+LHe`8hGZ&p}wO`bAE zl}8}8%Z9UeKMoa;0pxM`!k0dI!kb40ZVKX_kH2m|T5xunZJ1m1cQ)7I_wV`fKyRgD zhRoqrKo%EY7em-6rXQ=qE*hff1tLUU-GurFr+{y^nN_nU-nzMkqo{Y&8)J| z+r2C!spMHcq$2X(K{>-ThercTpCNQnz{Qu9gko(6cO3$k%=@|_tN)Z@jywTgm*G2m zokWL+B^x66BbP=*EYX**9XXXkKBBrq={-5YUQfVhk0ww4PI))F`**)~H*Fli5RL!A zvd{t(c{ywYe}H5#7b;37dkWkFzrKk>KJz3Dx$Lf2JpRK;T5H! z##UECo{7zs*1$O)QUKH+Z(-S zuvSTU1XgaS(~dHSAEu6-{P~`6(&r|(A!%`Y&Np@zt?6~#-Y(yYMO;=C$(#d*E0$V_taLC9}pg(*w z!IoZ)V$Z{z(bhCb9oo8i5Xv(dP9n{s1N4h{sQl^R zRutXGRkkY7ZfV_TNwn{Jojknyda-94D9l-w&| zc=!Z5VC(4;PYV&J9{O;HKQYi`KY7W0PdsJ2woXJHVTE%kc#0a&Hzr=C89N94UZsGD z9>3>#avR#$_Nf$c^4xaEgOSH(IL{z zDgYf-f$-VcC5tsq(`ppW}*n)9t z(L|5}_RlR}d1zc@xW` zyVB~Ap?~R1SiT7P%dCG{RIRm8-c|+n@x!tx3*zSE2WaLE?S3UQsCAW1F38nf+dbPL z;(ei&@AFSVudGczh5B00|NXIJcbPqThzm#7Ro1z&dO;f`4g(vcnEoxS<00x;V+s(a zm{5MGqEbuW#6qWNc&!M9M1e}rl>wen8DA%8EP)RDNmKj)iX>+*VYI|5mAh*X$~^Q9lP)g$dkt-$bB)O1)^=y z1A74?@>MqBtxsR_a9$Iy+H`Gjgku+sKUY*QVhF;rTylV85aj2F#Z)}$37VW;lG6V(s}U8cBS z1k==?o8ROlwR?}NTQ=D%+)8ac%2vrS0xqA7L@741Y8>P|r9AW9Y%-bo$yPLsCkCx< zfKv2UfWHzF49kI!zpkOeLsm!@3ko+y8KRfsQz0nb`tX#ai`nGregJ8KYf-usD{PQ> z**D9qND5!xnh{k=5S$8GWYK8_iLOp&kxeuWLlQ3>htK0~JUlL!Q6{~E3w5qvN&}_| z6-OZ~2f|2?fYx~N)mracJLVZv2K!JR?dt4l9#qoqe>zX4$j|@HtayCyy=2GJDZ^Nm zc6Ted+7)#e`0y_M{0hxZ+Bx=$Yh|E7sa-j?huE`k=Ks`kRD+k}ql?y`z??;fCuZyh z5hcz#oU8EcR_c=3GZ)V7Hm}DTm(@4KNYWkfYxrrm{u8i^^Fosl8ePl^D=!bTU`p{U zDt2_27+esR3l{t$78fB$=X=T5XzgY8Qt4nUH5M~(O1Un{aH|}F$8OF!Ta>-QhCBEa z`jB6eIhkNX!(0n%5R{p380>RXA<%2-1sDUMnK+_rsuq6oCpgqkpGlhMij#7ri- zDQsO&ftIuqTTU3%L1X3?HzudNAA@8-c8)|@n;~76b$z3MM<+iF18jAk!a}0Ozcmkx zJ^@b$$7U*vdHqyam?!U5$C5yFw7xL1PJsR2ka*J{^<^n;yR~PUqaxqi!wE$Teho#6 z6+ScZ_7PM1(YiF1@G|6C4_mfU#ppCCYmfh-eCtN;#ZW@%1)h2thUar(q*`Ueu068v zneoHV*^!;Ewi~MvGrL2@!nSV{(;n!AKJY9vfgP=WQal0QkiZNkPq6wI7R>oR5mv~C zE)VmPyjPoSM|O6qf3NDqOJlc@>NHs|k8z(M?S$fwUIoHnmkd9TjQ{bB12+_OvQ5az4kd#0;x z0J^|CJ^J$KbpSZbgHFnvJ@(@IY%+Dyqgr)%1hNxC(k_-K`V?bS&{i#7_yKj(ng8`T z0IaW$N#8FocI;LTVhUsO{)J0{FUG#hK_u2;=iBSAr}Z8ReHJQwTH8b1{5Da@3uiabllh9Ynp-8deKULW*u_7qG=xZZzdWrZ_QVDknYjz%lRdXaP@S!C1d zHT{TtGCbvibH7m@zth!xtXu$3%w~HT+f8J|$rS*6PV_rbyjPxbM;a^TuLW=C5~~%% z$)>@G$d~{8)+bWW73af|*{>bwn4xbp9vf_eZEC*7#2*#*Ssz=)=Q z@=+<9Sbr93>BD$isXY54^P{4sOa(;U(>7ff!oOh+2chAQuAOaLWt$CHJXC&RA&SmY zBcRlRn)R5Lwf;xcFXKp9hN16Nm6Qk1ce*BVkxhFgwe);a?X?x(ExOICwMRXp1 z#l+wK1wVPRo?(M`{ZD7sHgZ1Yci^rM(5svDSrcnwz73@^zU0L-JPC^%CxyO|;*Z$u zrpTIW&O~TRia(X8gvl#hFZc@5nwVT)!2KaJ#>-qAG2W}>d`QBDe~YKaSJQgHVxe^GH;Kq4 zlvf-W!Z{!&NzJYu6+d7~g`O04mHfD74)=PiJW|(m=HEWV3RPIv8V+o zW9i8gUCCDwkfNmpUph;c)8eaOT)gZqn;4OfW!ZeGvKq!~s?IwvPe}|ptoqr!pq#bB zyPNuAY+WdCjVJt}?#ndYQrV83X8mcPV9)I7#7XPeAm{Sx>c3ORVac|O)?vJ-Wtc=Q zD=SkATU!U&p!PSZ<^T~QaVW>&OzaN0vj2ydVU<7pirj2~0}p~)N*ljC%+q%F*O=H( zoSZeq^$^pcgvl0FHW2R>GN`xUAo;L5B~CVX;p5y(Cw?$?eyShr!ml@YJ^;<#zu$JwI}g)D2bB(x)yv+K zx_^v(2CjWZRQY?E3mxMBb@)u}|Fctaon zgxl#J(CEYaicA;FQ8?Y7(1;_l3G?Q1`iEM0>myp8#-jI3S^H93JBe-e>m~SzK9>Bk z{_>$U5;1-I*sLlHH)}}J-r(;IeAKst{p)mQGGZ7rQLv|1!*@|$i4F#(-S*rDp&jlQ zrcmMUQROBB$=lmS-S@1`_6uf_1?7wid14wwSk5`HxBY3PQ+;I7H0#t6v86b)Nz$2fTv!0r-3@+-vV_@9H@F=BE6wj zEAxN;^%*{kqkUjAG&Vk&n4R4+TUn9TjE$|uXKh|@<77KyJ>K!s92_wUE3X{XN}Xi; z{}6O}lo3UJGuwieMg@JU8mW zK7@vI3udptIHza93SVj}lf_?G%%|C5v)?%Jh}3rEltG8a(-HsX#yE53rdf z{;^1$XgkOU&f4ls-fteT_I5J&pHMyK#CX2s0_q+9uw#O6RgJA#lTd@c{#Eu;U`WK> z)3K|w3cFHed~4a)eXS|<^^UPj_-F+NE{j;4Ks6l2#ob0RiuCRj(fOq(pAOFrL+m`1 zfMfm-WTLH2_O@o2>^?dkbqE_5dS3E|fa9?URm}igvC}g#Haj9vX?V#xfXs4#ydg!* zYX6im?$H$OuMG&tC2Pr+qV^YN9N3)eCt3-^nV|>}*iv>a1y7 zITX4zh2lsFab`=09`><`2Mqum@I+t0L}RicN;w8E!gb_{H$q(E29^@hon5R7iX%nc zwY2$S9yc!)DU9nF^1T9Z`!7j5k!P-EYa*>iI{$$evQn-k~`czEO_H4x^X zqKN!lN$4ZDuuTTzRgEC5S`Eh=y}xFXV;aLVFlRw8zr#PWs+$|iE zaAf+$DC6qCP}Ky=M7N0Ud_?39Xx)BHUNJzuJu#ne40(L8LN~^$y88qE_QL&#@BEvc zjhgLe>r35f0s0^@iK*~4{{_r!UyZT`AAI{F%MjGS8mFP!{X|FyyLAj+YZ^pJ08 z9QuGbJTw)}&zGjSz6SjxBX6bnsW|(?r#B-DCBM4H@%Lp8g&`;A6l9_!JL!7S9iBq|g~1SAX&P@iM;( zFdmVnfm>C-!<{vZI(We@mtIboC~1oNS-0h_q|IN+rrx2Ryt5_ayvkWv^2UD}t8Zcfg{*l=EHI3!&3@x(53 zcxr^Xb%x>(t%Z4g(}E85O;bd=kJ!W|r`0ia0F8mn#>15bkh{C8 zOh6n|FeZq3ej*=7fc}B7vh{(S!H<6yEh&irr1--Icwc?L#g*a>Cyfw#AP8KzWjXM{ zusyG_B3$bJ+DEZoKo5%`kc^ufspB$2;jyWEV)!>f))a zau<^u|8T2GRSH(-#ngA|>OWuek(g6^Lw2unE1W;Q3RtOFg$UlV)prhs`s*$I+dLwT z83Sm~=Q|Vf1z8Q0YXrXXo_Xw9FzK*?h1Y}5%s9aL#T|cXJ1t|}qiYUA4C6j^a|+q^ z3da}JSrJEYn;+9N#N<Z4<+)9VveelBJ**Q$T`+4xWqSF(AT-d~{`%e-j;ek?W! z5tq~XcPq^v$r>980dpzUHp01IS@l`i4)mE1-9IvW)Bss(Yspw@g@L)kW9KZt4d3w_ zOLl8H{0_EZ$+}Z4v%FJ$TX#(%msi`4KZvPJSVOT5oQOWKHuFXje&Br|Wk5U-EuWhv zu-g8X<-Ff#iEV>=k^Qqmw68enmli^FW1$e;(zZmu(u$=jtxJ#8l*gVgQ$R01)E*b;V zp@}T6kGG{~RFqd=opD2p|L%4qY-d843(Rdj!JvT3o}NA5a0icwaAOFQj zZHnxkB}>wtWuE6uOIy}VKy%hyOIyZV0Ib~r@%WB@~yY>Fhpl)I&*7@qaLYe>lEpB;J@J+_}*OhAj3*js$-^^4tQbUF8!|(ob zOKQ76J=44YOtFTRJA5B_-Kx`3X{N)}V5UPdwUm)>{#r1PabGa6MDL@2Mv5VCg7wfq z+3&Y+i#QYz2qPJ($$mc&^PZa^%T959nS%z*U^{_(?JFer;IhLr&?J?t*_ixn);RSP zVVp`bW3E*(nyS$qkb%G4lG)bfB6QQq%Xn1jAS#hw|X&Jmk&$soPg)LLo)B6>u zcl>4Wie+6(wMVA;7wgTW0O=QL68XeOdo*@mu6z3{Z5*P_;U^LpEcKrpeK~7UnV=fQ z8zXBGig)l_HoR~5tk^noW9g~Ar>#~(r(ishmoX{HatSMSy`}&oU32&s->6kB$H-Nn z&V58)27a5D8Tsk(O|(_!Kunt;!Hp$9QSh!{B6wdw+kM!H(yoX#C5c3;Z@U=Ex>ixa z%J#OLwK=@IF+S%pR4gpPLNJHXCHYOjFU|9xM-&X8;ZU7#7{4S5$tjIp!L^A~Y90{R z>+C&&*SSpm3rpF8gK=KQBlZ{yKTJHfDZu<&a}jf~hoOW1b&ZdE8d2MGt6TV33YR1Ee8-=eSi)SI%@ zNd@jde`a&0$#Fg>a5v4t8Q10OtJK4TesZM@EW&Jf$@%wU#Fz)FCNhiZS53avUbjlPt^9M6FHRlyO~>a(>u|=?J~(N=o0&^9vTor6bbQxC2Y^)8 z`d%)PT#m%@F84AdBxQSF>|~J)E$Z?y7Jtup;j{~&$v_aUkOX;_>$Tf{mR|!6lHcZh zBrz8Q7|gd?hV~PVI?|LN#0o$4=zFMttC)*B`2M@lu_BK6!BL>>6ZX&g|K;ue;qk*p bf6+?dchC87u&)=IFQ3<`+r|7J=!|Ff From 8fa79377c329068325f9ea64bf1f6de45f300954 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 30 Apr 2013 11:08:14 +0200 Subject: [PATCH 03/39] Lowered rfm22b_rcvr supervisor timeout. Timeout values above 159 exceed uint8_t range during timeout calculation and effectively disable the supervisor. --- flight/targets/boards/revolution/pios_board.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/targets/boards/revolution/pios_board.h b/flight/targets/boards/revolution/pios_board.h index f58ace784..d7fed3b47 100644 --- a/flight/targets/boards/revolution/pios_board.h +++ b/flight/targets/boards/revolution/pios_board.h @@ -228,7 +228,7 @@ extern uint32_t pios_packet_handler; #define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 #define PIOS_GCSRCVR_TIMEOUT_MS 100 -#define PIOS_RFM22B_RCVR_TIMEOUT_MS 200 +#define PIOS_RFM22B_RCVR_TIMEOUT_MS 150 //------------------------- // Receiver PPM input From b48665e59b2eb5bff36670e60e4fa63e3c404f82 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 30 Apr 2013 11:24:43 +0200 Subject: [PATCH 04/39] rfm22b receiver supervisor now properly indicates a timeout condition. This allows upper layers to recognize control signal loss. --- flight/pios/common/pios_rfm22b_rcvr.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/pios/common/pios_rfm22b_rcvr.c b/flight/pios/common/pios_rfm22b_rcvr.c index faa21b604..3ea942103 100644 --- a/flight/pios/common/pios_rfm22b_rcvr.c +++ b/flight/pios/common/pios_rfm22b_rcvr.c @@ -110,7 +110,7 @@ static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id) { // Have we received fresh values since the last update? if (!rfm22b_dev->ppm_fresh) { for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { - rfm22b_dev->ppm_channel[i] = 0; + rfm22b_dev->ppm_channel[i] = PIOS_RCVR_TIMEOUT; } } rfm22b_dev->ppm_fresh = false; From 9f65409c5a2152b2dcfce9eb308aa6b49ef73c0c Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Fri, 3 May 2013 01:15:13 +0200 Subject: [PATCH 05/39] OP-938 Stop AH from running when board is not armed --- flight/modules/AltitudeHold/altitudehold.c | 32 ++++++++++------------ 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/flight/modules/AltitudeHold/altitudehold.c b/flight/modules/AltitudeHold/altitudehold.c index ed3b0bcf6..e6f5e2e5a 100644 --- a/flight/modules/AltitudeHold/altitudehold.c +++ b/flight/modules/AltitudeHold/altitudehold.c @@ -43,19 +43,19 @@ * */ -#include "openpilot.h" +#include #include -#include "CoordinateConversions.h" -#include "altholdsmoothed.h" -#include "attitudeactual.h" -#include "altitudeholdsettings.h" -#include "altitudeholddesired.h" // object that will be updated by the module -#include "baroaltitude.h" -#include "positionactual.h" -#include "flightstatus.h" -#include "stabilizationdesired.h" -#include "accels.h" - +#include +#include +#include +#include +#include // object that will be updated by the module +#include +#include +#include +#include +#include +#include // Private constants #define MAX_QUEUE_SIZE 2 #define STACK_SIZE_BYTES 1024 @@ -111,7 +111,6 @@ float decay; float velocity_decay; bool running = false; float error; -float switchThrottle; float smoothed_altitude; float starting_altitude; @@ -161,7 +160,6 @@ static void altitudeHoldTask(void *parameters) if(flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD && !running) { // Copy the current throttle as a starting point for integral StabilizationDesiredThrottleGet(&throttleIntegral); - switchThrottle = throttleIntegral; error = 0; velocity = 0; running = true; @@ -336,7 +334,8 @@ static void altitudeHoldTask(void *parameters) // Verify that we are in altitude hold mode FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) { + if(flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD || + flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED) { running = false; } @@ -362,8 +361,7 @@ static void altitudeHoldTask(void *parameters) if(stabilizationDesired.Throttle > 1) { throttleIntegral -= (stabilizationDesired.Throttle - 1); stabilizationDesired.Throttle = 1; - } - else if (stabilizationDesired.Throttle < 0) { + } else if (stabilizationDesired.Throttle < 0) { throttleIntegral -= stabilizationDesired.Throttle; stabilizationDesired.Throttle = 0; } From 976999eba08bac8c24e2cf17e624d8c8c4dc9793 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Fri, 3 May 2013 01:43:14 +0200 Subject: [PATCH 06/39] OP-938 Add an "Exp" to throttle stick when in AH to make it useable Conflicts: flight/modules/ManualControl/manualcontrol.c --- flight/modules/ManualControl/manualcontrol.c | 678 ++++++++++--------- 1 file changed, 349 insertions(+), 329 deletions(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index 479ea221c..fd069b33b 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -53,26 +53,25 @@ #if defined(PIOS_INCLUDE_USB_RCTX) #include "pios_usb_rctx.h" -#endif /* PIOS_INCLUDE_USB_RCTX */ +#endif /* PIOS_INCLUDE_USB_RCTX */ // Private constants #if defined(PIOS_MANUAL_STACK_SIZE) -#define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE +#define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE #else -#define STACK_SIZE_BYTES 1024 +#define STACK_SIZE_BYTES 1024 #endif -#define TASK_PRIORITY (tskIDLE_PRIORITY+4) -#define UPDATE_PERIOD_MS 20 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) +#define UPDATE_PERIOD_MS 20 #define THROTTLE_FAILSAFE -0.1f -#define ARMED_TIME_MS 1000 -#define ARMED_THRESHOLD 0.50f -//safe band to allow a bit of calibration error or trim offset (in microseconds) +#define ARMED_TIME_MS 1000 +#define ARMED_THRESHOLD 0.50f +// safe band to allow a bit of calibration error or trim offset (in microseconds) #define CONNECTION_OFFSET 250 // Private types -typedef enum -{ +typedef enum { ARM_STATE_DISARMED, ARM_STATE_ARMING_MANUAL, ARM_STATE_ARMED, ARM_STATE_DISARMING_MANUAL, ARM_STATE_DISARMING_TIMEOUT } ArmState_t; @@ -87,15 +86,15 @@ static float inputFiltered[MANUALCONTROLSETTINGS_RESPONSETIME_NUMELEM]; #endif // Private functions -static void updateActuatorDesired(ManualControlCommandData * cmd); -static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); -static void updateLandDesired(ManualControlCommandData * cmd, bool changed); -static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed); -static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home); -static void processFlightMode(ManualControlSettingsData * settings, float flightMode); -static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static void updateActuatorDesired(ManualControlCommandData *cmd); +static void updateStabilizationDesired(ManualControlCommandData *cmd, ManualControlSettingsData *settings); +static void updateLandDesired(ManualControlCommandData *cmd, bool changed); +static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed); +static void updatePathDesired(ManualControlCommandData *cmd, bool changed, bool home); +static void processFlightMode(ManualControlSettingsData *settings, float flightMode); +static void processArm(ManualControlCommandData *cmd, ManualControlSettingsData *settings); static void setArmedIfChanged(uint8_t val); -static void configurationUpdatedCb(UAVObjEvent * ev); +static void configurationUpdatedCb(UAVObjEvent *ev); static void manualControlTask(void *parameters); static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutral); @@ -109,17 +108,16 @@ static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel #endif #define RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP 12 -#define RCVR_ACTIVITY_MONITOR_MIN_RANGE 10 -struct rcvr_activity_fsm -{ +#define RCVR_ACTIVITY_MONITOR_MIN_RANGE 10 +struct rcvr_activity_fsm { ManualControlSettingsChannelGroupsOptions group; uint16_t prev[RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP]; uint8_t sample_count; }; static struct rcvr_activity_fsm activity_fsm; -static void resetRcvrActivity(struct rcvr_activity_fsm * fsm); -static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm); +static void resetRcvrActivity(struct rcvr_activity_fsm *fsm); +static bool updateRcvrActivity(struct rcvr_activity_fsm *fsm); #define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode && assumptions_channelcount) @@ -129,7 +127,7 @@ static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm); int32_t ManualControlStart() { // Start main task - xTaskCreate(manualControlTask, (signed char *) "ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle); + xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle); PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL); @@ -141,10 +139,10 @@ int32_t ManualControlStart() */ int32_t ManualControlInitialize() { - /* Check the assumptions about uavobject enum's are correct */ - if (!assumptions) + if (!assumptions) { return -1; + } AccessoryDesiredInitialize(); ManualControlCommandInitialize(); @@ -155,7 +153,7 @@ int32_t ManualControlInitialize() return 0; } -MODULE_INITCALL( ManualControlInitialize, ManualControlStart) +MODULE_INITCALL(ManualControlInitialize, ManualControlStart) /** * Module task @@ -168,7 +166,7 @@ static void manualControlTask(void *parameters) float flightMode = 0; uint8_t disconnected_count = 0; - uint8_t connected_count = 0; + uint8_t connected_count = 0; // For now manual instantiate extra instances of Accessory Desired. In future should be done dynamically // this includes not even registering it if not used @@ -231,7 +229,6 @@ static void manualControlTask(void *parameters) } if (!ManualControlCommandReadOnly()) { - bool valid_input_detected = true; // Read channel values in us @@ -246,37 +243,37 @@ static void manualControlTask(void *parameters) // If a channel has timed out this is not valid data and we shouldn't update anything // until we decide to go to failsafe - if (cmd.Channel[n] == PIOS_RCVR_TIMEOUT) + if (cmd.Channel[n] == PIOS_RCVR_TIMEOUT) { valid_input_detected = false; - else + } else { scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); + } } // Check settings, if error raise alarm if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE - || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE - || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE - || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE - || - // Check all channel mappings are valid - cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_INVALID - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_INVALID - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_INVALID - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_INVALID - || - // Check the driver exists - cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_NODRIVER - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_NODRIVER - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_NODRIVER - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_NODRIVER || - // Check the FlightModeNumber is valid - settings.FlightModeNumber < 1 || settings.FlightModeNumber > MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM || - // Similar checks for FlightMode channel but only if more than one flight mode has been set. Otherwise don't care - ((settings.FlightModeNumber > 1) - && (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_INVALID - || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_NODRIVER))) { - + || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE + || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE + || settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE + || + // Check all channel mappings are valid + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t)PIOS_RCVR_INVALID + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t)PIOS_RCVR_INVALID + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t)PIOS_RCVR_INVALID + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t)PIOS_RCVR_INVALID + || + // Check the driver exists + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t)PIOS_RCVR_NODRIVER + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t)PIOS_RCVR_NODRIVER + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t)PIOS_RCVR_NODRIVER + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t)PIOS_RCVR_NODRIVER || + // Check the FlightModeNumber is valid + settings.FlightModeNumber < 1 || settings.FlightModeNumber > MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM || + // Similar checks for FlightMode channel but only if more than one flight mode has been set. Otherwise don't care + ((settings.FlightModeNumber > 1) + && (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t)PIOS_RCVR_INVALID + || cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t)PIOS_RCVR_NODRIVER))) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE; ManualControlCommandSet(&cmd); @@ -290,32 +287,32 @@ static void manualControlTask(void *parameters) // decide if we have valid manual input or not valid_input_detected &= validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], - settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]) - && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], - settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]) - && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], - settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]) - && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], - settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]); + settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]) + && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], + settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]) + && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], + settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]) + && validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], + settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]); // Implement hysteresis loop on connection status if (valid_input_detected && (++connected_count > 10)) { - cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_TRUE; - connected_count = 0; + cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_TRUE; + connected_count = 0; disconnected_count = 0; } else if (!valid_input_detected && (++disconnected_count > 10)) { - cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE; - connected_count = 0; + cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE; + connected_count = 0; disconnected_count = 0; } if (cmd.Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE) { - cmd.Throttle = -1; // Shut down engine with no control - cmd.Roll = 0; + cmd.Throttle = -1; // Shut down engine with no control + cmd.Roll = 0; cmd.Yaw = 0; - cmd.Pitch = 0; + cmd.Pitch = 0; cmd.Collective = 0; - //cmd.FlightMode = MANUALCONTROLCOMMAND_FLIGHTMODE_AUTO; // don't do until AUTO implemented and functioning + // cmd.FlightMode = MANUALCONTROLCOMMAND_FLIGHTMODE_AUTO; // don't do until AUTO implemented and functioning // Important: Throttle < 0 will reset Stabilization coefficients among other things. Either change this, // or leave throttle at IDLE speed or above when going into AUTO-failsafe. AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); @@ -324,31 +321,33 @@ static void manualControlTask(void *parameters) // Set Accessory 0 if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { accessory.AccessoryVal = 0; - if (AccessoryDesiredInstSet(0, &accessory) != 0) + if (AccessoryDesiredInstSet(0, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } // Set Accessory 1 if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { accessory.AccessoryVal = 0; - if (AccessoryDesiredInstSet(1, &accessory) != 0) + if (AccessoryDesiredInstSet(1, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } // Set Accessory 2 if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { accessory.AccessoryVal = 0; - if (AccessoryDesiredInstSet(2, &accessory) != 0) + if (AccessoryDesiredInstSet(2, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } - } else if (valid_input_detected) { AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL); // Scale channels to -1 -> +1 range - cmd.Roll = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]; - cmd.Pitch = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]; - cmd.Yaw = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]; + cmd.Roll = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]; + cmd.Pitch = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]; + cmd.Yaw = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]; cmd.Throttle = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]; - flightMode = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE]; + flightMode = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE]; // Apply deadband for Roll/Pitch/Yaw stick inputs if (settings.Deadband) { @@ -360,18 +359,19 @@ static void manualControlTask(void *parameters) // Apply Low Pass Filter to input channels, time delta between calls in ms portTickType thisSysTime = xTaskGetTickCount(); float dT = (thisSysTime > lastSysTimeLPF) ? - (float)((thisSysTime - lastSysTimeLPF) * portTICK_RATE_MS) : - (float)UPDATE_PERIOD_MS; + (float)((thisSysTime - lastSysTimeLPF) * portTICK_RATE_MS) : + (float)UPDATE_PERIOD_MS; lastSysTimeLPF = thisSysTime; applyLPF(&cmd.Roll, MANUALCONTROLSETTINGS_RESPONSETIME_ROLL, &settings, dT); applyLPF(&cmd.Pitch, MANUALCONTROLSETTINGS_RESPONSETIME_PITCH, &settings, dT); applyLPF(&cmd.Yaw, MANUALCONTROLSETTINGS_RESPONSETIME_YAW, &settings, dT); #endif // USE_INPUT_LPF - if (cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_INVALID - && cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_NODRIVER - && cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t) PIOS_RCVR_TIMEOUT) + if (cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t)PIOS_RCVR_INVALID + && cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t)PIOS_RCVR_NODRIVER + && cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t)PIOS_RCVR_TIMEOUT) { cmd.Collective = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE]; + } AccessoryDesiredData accessory; // Set Accessory 0 @@ -380,8 +380,9 @@ static void manualControlTask(void *parameters) #ifdef USE_INPUT_LPF applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY0, &settings, dT); #endif - if (AccessoryDesiredInstSet(0, &accessory) != 0) + if (AccessoryDesiredInstSet(0, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } // Set Accessory 1 if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { @@ -389,8 +390,9 @@ static void manualControlTask(void *parameters) #ifdef USE_INPUT_LPF applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY1, &settings, dT); #endif - if (AccessoryDesiredInstSet(1, &accessory) != 0) + if (AccessoryDesiredInstSet(1, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } // Set Accessory 2 if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { @@ -398,12 +400,12 @@ static void manualControlTask(void *parameters) #ifdef USE_INPUT_LPF applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY2, &settings, dT); #endif - if (AccessoryDesiredInstSet(2, &accessory) != 0) + if (AccessoryDesiredInstSet(2, &accessory) != 0) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } } processFlightMode(&settings, flightMode); - } // Process arming outside conditional so system will disarm when disconnected @@ -414,13 +416,12 @@ static void manualControlTask(void *parameters) #if defined(PIOS_INCLUDE_USB_RCTX) if (pios_usb_rctx_id) { PIOS_USB_RCTX_Update(pios_usb_rctx_id, - cmd.Channel, - settings.ChannelMin, - settings.ChannelMax, - NELEMENTS(cmd.Channel)); + cmd.Channel, + settings.ChannelMin, + settings.ChannelMax, + NELEMENTS(cmd.Channel)); } -#endif /* PIOS_INCLUDE_USB_RCTX */ - +#endif /* PIOS_INCLUDE_USB_RCTX */ } else { ManualControlCommandGet(&cmd); /* Under GCS control */ } @@ -430,48 +431,48 @@ static void manualControlTask(void *parameters) // Depending on the mode update the Stabilization or Actuator objects static uint8_t lastFlightMode = FLIGHTSTATUS_FLIGHTMODE_MANUAL; switch (PARSE_FLIGHT_MODE(flightStatus.FlightMode)) { - case FLIGHTMODE_UNDEFINED: - // This reflects a bug in the code architecture! + case FLIGHTMODE_UNDEFINED: + // This reflects a bug in the code architecture! + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); + break; + case FLIGHTMODE_MANUAL: + updateActuatorDesired(&cmd); + break; + 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: + altitudeHoldDesired(&cmd, lastFlightMode != flightStatus.FlightMode); + break; + case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: + case FLIGHTSTATUS_FLIGHTMODE_POI: + updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, false); + break; + case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: + updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, true); + break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + // No need to call anything. This just avoids errors. + break; + case FLIGHTSTATUS_FLIGHTMODE_LAND: + updateLandDesired(&cmd, lastFlightMode != flightStatus.FlightMode); + break; + default: AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); - break; - case FLIGHTMODE_MANUAL: - updateActuatorDesired(&cmd); - break; - 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: - altitudeHoldDesired(&cmd, lastFlightMode != flightStatus.FlightMode); - break; - case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: - case FLIGHTSTATUS_FLIGHTMODE_POI: - updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, false); - break; - case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: - updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, true); - break; - case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: - // No need to call anything. This just avoids errors. - break; - case FLIGHTSTATUS_FLIGHTMODE_LAND: - updateLandDesired(&cmd, lastFlightMode != flightStatus.FlightMode); - break; - default: - AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); - } - break; + } + break; } lastFlightMode = flightStatus.FlightMode; } } -static void resetRcvrActivity(struct rcvr_activity_fsm * fsm) +static void resetRcvrActivity(struct rcvr_activity_fsm *fsm) { ReceiverActivityData data; bool updated = false; @@ -479,7 +480,7 @@ static void resetRcvrActivity(struct rcvr_activity_fsm * fsm) /* Clear all channel activity flags */ ReceiverActivityGet(&data); if (data.ActiveGroup != RECEIVERACTIVITY_ACTIVEGROUP_NONE && data.ActiveChannel != 255) { - data.ActiveGroup = RECEIVERACTIVITY_ACTIVEGROUP_NONE; + data.ActiveGroup = RECEIVERACTIVITY_ACTIVEGROUP_NONE; data.ActiveChannel = 255; updated = true; } @@ -500,14 +501,14 @@ static void updateRcvrActivitySample(uint32_t rcvr_id, uint16_t samples[], uint8 } } -static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm * fsm) +static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm *fsm) { bool activity_updated = false; /* Compare the current value to the previous sampled value */ for (uint8_t channel = 1; channel <= RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP; channel++) { uint16_t delta; - uint16_t prev = fsm->prev[channel - 1]; // Subtract 1 because channels are 1 indexed + uint16_t prev = fsm->prev[channel - 1]; // Subtract 1 because channels are 1 indexed uint16_t curr = PIOS_RCVR_Read(rcvr_id, channel); if (curr > prev) { delta = curr - prev; @@ -521,41 +522,41 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm /* Don't assume manualcontrolsettings and receiveractivity are in the same order. */ switch (fsm->group) { - case MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM: - group = RECEIVERACTIVITY_ACTIVEGROUP_PWM; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM: - group = RECEIVERACTIVITY_ACTIVEGROUP_PPM; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_DSMMAINPORT; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: - group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: - group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK: - group = RECEIVERACTIVITY_ACTIVEGROUP_OPLINK; - break; - default: - PIOS_Assert(0); - break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PWM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PPM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT: + group = RECEIVERACTIVITY_ACTIVEGROUP_DSMMAINPORT; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT: + group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: + group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: + group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK: + group = RECEIVERACTIVITY_ACTIVEGROUP_OPLINK; + break; + default: + PIOS_Assert(0); + break; } - ReceiverActivityActiveGroupSet((uint8_t*) &group); + ReceiverActivityActiveGroupSet((uint8_t *)&group); ReceiverActivityActiveChannelSet(&channel); activity_updated = true; } } - return (activity_updated); + return activity_updated; } -static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm) +static bool updateRcvrActivity(struct rcvr_activity_fsm *fsm) { bool activity_updated = false; @@ -574,13 +575,13 @@ static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm) /* Take a sample of each channel in this group */ updateRcvrActivitySample(pios_rcvr_group_map[fsm->group], fsm->prev, NELEMENTS(fsm->prev)); fsm->sample_count++; - return (false); + return false; } /* Compare with previous sample */ activity_updated = updateRcvrActivityCompare(pios_rcvr_group_map[fsm->group], fsm); - group_completed: +group_completed: /* Reset the sample counter */ fsm->sample_count = 0; @@ -604,87 +605,89 @@ static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm) } } - return (activity_updated); + return activity_updated; } -static void updateActuatorDesired(ManualControlCommandData * cmd) +static void updateActuatorDesired(ManualControlCommandData *cmd) { ActuatorDesiredData actuator; + ActuatorDesiredGet(&actuator); - actuator.Roll = cmd->Roll; - actuator.Pitch = cmd->Pitch; - actuator.Yaw = cmd->Yaw; + actuator.Roll = cmd->Roll; + actuator.Pitch = cmd->Pitch; + actuator.Yaw = cmd->Yaw; actuator.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle; ActuatorDesiredSet(&actuator); } -static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings) +static void updateStabilizationDesired(ManualControlCommandData *cmd, ManualControlSettingsData *settings) { StabilizationDesiredData stabilization; + StabilizationDesiredGet(&stabilization); StabilizationSettingsData stabSettings; StabilizationSettingsGet(&stabSettings); - uint8_t * stab_settings; + uint8_t *stab_settings; FlightStatusData flightStatus; FlightStatusGet(&flightStatus); switch (flightStatus.FlightMode) { - case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: - stab_settings = settings->Stabilization1Settings; - break; - case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: - stab_settings = settings->Stabilization2Settings; - break; - case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: - stab_settings = settings->Stabilization3Settings; - break; - default: - // Major error, this should not occur because only enter this block when one of these is true - AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); - return; + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: + stab_settings = settings->Stabilization1Settings; + break; + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: + stab_settings = settings->Stabilization2Settings; + break; + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: + stab_settings = settings->Stabilization3Settings; + break; + default: + // Major error, this should not occur because only enter this block when one of these is true + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); + return; } // TOOD: Add assumption about order of stabilization desired and manual control stabilization mode fields having same order - stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = stab_settings[0]; + stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = stab_settings[0]; stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = stab_settings[1]; - stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = stab_settings[2]; + stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = stab_settings[2]; stabilization.Roll = - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Roll : - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? - cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : - (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_RELAYRATE) ? - cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Roll * stabSettings.RollMax : 0; // this is an invalid mode + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Roll : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? + cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (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_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 : - (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : - (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? - cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : - (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_RELAYRATE) ? - cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : - (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : 0; // this is an invalid mode + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? + cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (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_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 : - (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : - (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? - cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : - (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_RELAYRATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : - (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Yaw * stabSettings.YawMax : 0; // this is an invalid mode + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? + cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (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_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; StabilizationDesiredSet(&stabilization); @@ -696,10 +699,11 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon * @brief Update the position desired to current location when * enabled and allow the waypoint to be moved by transmitter */ -static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool home) +static void updatePathDesired(ManualControlCommandData *cmd, bool changed, bool home) { static portTickType lastSysTime; portTickType thisSysTime = xTaskGetTickCount(); + /* float dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; */ lastSysTime = thisSysTime; @@ -711,16 +715,16 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool PathDesiredData pathDesired; PathDesiredGet(&pathDesired); pathDesired.Start[PATHDESIRED_START_NORTH] = 0; - pathDesired.Start[PATHDESIRED_START_EAST] = 0; - pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down - 10; - pathDesired.End[PATHDESIRED_END_NORTH] = 0; + pathDesired.Start[PATHDESIRED_START_EAST] = 0; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down - 10; + pathDesired.End[PATHDESIRED_END_NORTH] = 0; pathDesired.End[PATHDESIRED_END_EAST] = 0; pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down - 10; - pathDesired.StartingVelocity=1; - pathDesired.EndingVelocity=0; + pathDesired.StartingVelocity = 1; + pathDesired.EndingVelocity = 0; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; PathDesiredSet(&pathDesired); - } else if(changed) { + } else if (changed) { // After not being in this mode for a while init at current height PositionActualData positionActual; PositionActualGet(&positionActual); @@ -728,28 +732,28 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool PathDesiredData pathDesired; PathDesiredGet(&pathDesired); pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; - pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; - pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; - pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; + pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; + pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; pathDesired.End[PATHDESIRED_END_EAST] = positionActual.East; pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down; - pathDesired.StartingVelocity=1; - pathDesired.EndingVelocity=0; + pathDesired.StartingVelocity = 1; + pathDesired.EndingVelocity = 0; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; PathDesiredSet(&pathDesired); /* Disable this section, until such time as proper discussion can be had about how to implement it for all types of crafts. - } else { - PathDesiredData pathDesired; - PathDesiredGet(&pathDesired); - pathDesired.End[PATHDESIRED_END_NORTH] += dT * -cmd->Pitch; - pathDesired.End[PATHDESIRED_END_EAST] += dT * cmd->Roll; - pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; - PathDesiredSet(&pathDesired); + } else { + PathDesiredData pathDesired; + PathDesiredGet(&pathDesired); + pathDesired.End[PATHDESIRED_END_NORTH] += dT * -cmd->Pitch; + pathDesired.End[PATHDESIRED_END_EAST] += dT * cmd->Roll; + pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; + PathDesiredSet(&pathDesired); */ } } -static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +static void updateLandDesired(ManualControlCommandData *cmd, bool changed) { static portTickType lastSysTime; portTickType thisSysTime; @@ -764,19 +768,19 @@ static void updateLandDesired(ManualControlCommandData * cmd, bool changed) PathDesiredData pathDesired; PathDesiredGet(&pathDesired); - if(changed) { + if (changed) { // After not being in this mode for a while init at current height pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; - pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; - pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; - pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; + pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; + pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; pathDesired.End[PATHDESIRED_END_EAST] = positionActual.East; pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down; - pathDesired.StartingVelocity=1; - pathDesired.EndingVelocity=0; + pathDesired.StartingVelocity = 1; + pathDesired.EndingVelocity = 0; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; } - pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down+5; + pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down + 5; PathDesiredSet(&pathDesired); } @@ -785,16 +789,20 @@ static void updateLandDesired(ManualControlCommandData * cmd, bool changed) * enabled and enable altitude mode for stabilization * @todo: Need compile flag to exclude this from copter control */ -static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) +static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) { - const float DEADBAND_HIGH = 0.55; - const float DEADBAND_LOW = 0.45; + const float DEADBAND = .20f; + const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2; + const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2; + // this is the max speed in m/s at the extents of throttle + const float MAX_ALT_CHANGE_RATE = 5; static portTickType lastSysTime; static bool zeroed = false; portTickType thisSysTime; float dT; AltitudeHoldDesiredData altitudeHoldDesired; + AltitudeHoldDesiredGet(&altitudeHoldDesired); StabilizationSettingsData stabSettings; @@ -804,47 +812,48 @@ static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; lastSysTime = thisSysTime; - altitudeHoldDesired.Roll = cmd->Roll * stabSettings.RollMax; + altitudeHoldDesired.Roll = cmd->Roll * stabSettings.RollMax; altitudeHoldDesired.Pitch = cmd->Pitch * stabSettings.PitchMax; - altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; + altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; float currentDown; PositionActualDownGet(¤tDown); - if(changed) { + if (changed) { // After not being in this mode for a while init at current height altitudeHoldDesired.Altitude = 0; zeroed = false; } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT; + // being the two band simmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1 + // then apply an "exp" + altitudeHoldDesired.Altitude += powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) * MAX_ALT_CHANGE_RATE * dT; } else if (cmd->Throttle < DEADBAND_LOW && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT; + altitudeHoldDesired.Altitude += powf(((cmd->Throttle < 0 ? 0 : cmd->Throttle) - DEADBAND_LOW) / (DEADBAND_LOW), 3) * MAX_ALT_CHANGE_RATE * dT; } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) { // Require the stick to enter the dead band before they can move height zeroed = true; } - AltitudeHoldDesiredSet(&altitudeHoldDesired); } -#else +#else /* if defined(REVOLUTION) */ // TODO: These functions should never be accessible on CC. Any configuration that // could allow them to be called sholud already throw an error to prevent this happening // in flight -static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home) +static void updatePathDesired(ManualControlCommandData *cmd, bool changed, bool home) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } -static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +static void updateLandDesired(ManualControlCommandData *cmd, bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } -static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) +static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } -#endif +#endif /* if defined(REVOLUTION) */ /** * Convert channel from servo pulse duration (microseconds) to scaled -1/+1 range. */ @@ -855,13 +864,13 @@ static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutr // Scale if ((max > min && value >= neutral) || (min > max && value <= neutral)) { if (max != neutral) { - valueScaled = (float) (value - neutral) / (float) (max - neutral); + valueScaled = (float)(value - neutral) / (float)(max - neutral); } else { valueScaled = 0; } } else { if (min != neutral) { - valueScaled = (float) (value - neutral) / (float) (neutral - min); + valueScaled = (float)(value - neutral) / (float)(neutral - min); } else { valueScaled = 0; } @@ -893,13 +902,15 @@ static bool okToArm(void) { // read alarms SystemAlarmsData alarms; + SystemAlarmsGet(&alarms); // Check each alarm for (int i = 0; i < SYSTEMALARMS_ALARM_NUMELEM; i++) { - if (alarms.Alarm[i] >= SYSTEMALARMS_ALARM_ERROR) { // found an alarm thats set - if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) + if (alarms.Alarm[i] >= SYSTEMALARMS_ALARM_ERROR) { // found an alarm thats set + if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) { continue; + } return false; } @@ -915,6 +926,7 @@ static bool forcedDisArm(void) { // read alarms SystemAlarmsData alarms; + SystemAlarmsGet(&alarms); if (alarms.Alarm[SYSTEMALARMS_ALARM_GUIDANCE] == SYSTEMALARMS_ALARM_CRITICAL) { @@ -930,6 +942,7 @@ static bool forcedDisArm(void) static void setArmedIfChanged(uint8_t val) { FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); if (flightStatus.Armed != val) { @@ -943,9 +956,8 @@ static void setArmedIfChanged(uint8_t val) * @param[out] cmd The structure to set the armed in * @param[in] settings Settings indicating the necessary position */ -static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings) +static void processArm(ManualControlCommandData *cmd, ManualControlSettingsData *settings) { - bool lowThrottle = cmd->Throttle <= 0; if (forcedDisArm()) { @@ -959,22 +971,23 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED); } else { // Not really needed since this function not called when disconnected - if (cmd->Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE) + if (cmd->Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE) { lowThrottle = true; + } // The throttle is not low, in case we where arming or disarming, abort if (!lowThrottle) { switch (armState) { - case ARM_STATE_DISARMING_MANUAL: - case ARM_STATE_DISARMING_TIMEOUT: - armState = ARM_STATE_ARMED; - break; - case ARM_STATE_ARMING_MANUAL: - armState = ARM_STATE_DISARMED; - break; - default: - // Nothing needs to be done in the other states - break; + case ARM_STATE_DISARMING_MANUAL: + case ARM_STATE_DISARMING_TIMEOUT: + armState = ARM_STATE_ARMED; + break; + case ARM_STATE_ARMING_MANUAL: + armState = ARM_STATE_DISARMED; + break; + default: + // Nothing needs to be done in the other states + break; } return; } @@ -994,72 +1007,76 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData // Calc channel see assumptions7 int8_t sign = ((settings->Arming - MANUALCONTROLSETTINGS_ARMING_ROLLLEFT) % 2) ? -1 : 1; switch ((settings->Arming - MANUALCONTROLSETTINGS_ARMING_ROLLLEFT) / 2) { - case ARMING_CHANNEL_ROLL: - armingInputLevel = sign * cmd->Roll; - break; - case ARMING_CHANNEL_PITCH: - armingInputLevel = sign * cmd->Pitch; - break; - case ARMING_CHANNEL_YAW: - armingInputLevel = sign * cmd->Yaw; - break; + case ARMING_CHANNEL_ROLL: + armingInputLevel = sign * cmd->Roll; + break; + case ARMING_CHANNEL_PITCH: + armingInputLevel = sign * cmd->Pitch; + break; + case ARMING_CHANNEL_YAW: + armingInputLevel = sign * cmd->Yaw; + break; } - bool manualArm = false; + bool manualArm = false; bool manualDisarm = false; - if (armingInputLevel <= -ARMED_THRESHOLD) + if (armingInputLevel <= -ARMED_THRESHOLD) { manualArm = true; - else if (armingInputLevel >= +ARMED_THRESHOLD) + } else if (armingInputLevel >= +ARMED_THRESHOLD) { manualDisarm = true; + } switch (armState) { - case ARM_STATE_DISARMED: - setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED); + case ARM_STATE_DISARMED: + setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED); - // only allow arming if it's OK too - if (manualArm && okToArm()) { - armedDisarmStart = lastSysTime; - armState = ARM_STATE_ARMING_MANUAL; - } - break; - - case ARM_STATE_ARMING_MANUAL: - setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMING); - - if (manualArm && (timeDifferenceMs(armedDisarmStart, lastSysTime) > ARMED_TIME_MS)) - armState = ARM_STATE_ARMED; - else if (!manualArm) - armState = ARM_STATE_DISARMED; - break; - - case ARM_STATE_ARMED: - // When we get here, the throttle is low, - // we go immediately to disarming due to timeout, also when the disarming mechanism is not enabled + // only allow arming if it's OK too + if (manualArm && okToArm()) { armedDisarmStart = lastSysTime; - armState = ARM_STATE_DISARMING_TIMEOUT; - setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMED); - break; + armState = ARM_STATE_ARMING_MANUAL; + } + break; - case ARM_STATE_DISARMING_TIMEOUT: - // We get here when armed while throttle low, even when the arming timeout is not enabled - if ((settings->ArmedTimeout != 0) && (timeDifferenceMs(armedDisarmStart, lastSysTime) > settings->ArmedTimeout)) - armState = ARM_STATE_DISARMED; + case ARM_STATE_ARMING_MANUAL: + setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMING); - // Switch to disarming due to manual control when needed - if (manualDisarm) { - armedDisarmStart = lastSysTime; - armState = ARM_STATE_DISARMING_MANUAL; - } - break; + if (manualArm && (timeDifferenceMs(armedDisarmStart, lastSysTime) > ARMED_TIME_MS)) { + armState = ARM_STATE_ARMED; + } else if (!manualArm) { + armState = ARM_STATE_DISARMED; + } + break; - case ARM_STATE_DISARMING_MANUAL: - if (manualDisarm && (timeDifferenceMs(armedDisarmStart, lastSysTime) > ARMED_TIME_MS)) - armState = ARM_STATE_DISARMED; - else if (!manualDisarm) - armState = ARM_STATE_ARMED; - break; - } // End Switch + case ARM_STATE_ARMED: + // When we get here, the throttle is low, + // we go immediately to disarming due to timeout, also when the disarming mechanism is not enabled + armedDisarmStart = lastSysTime; + armState = ARM_STATE_DISARMING_TIMEOUT; + setArmedIfChanged(FLIGHTSTATUS_ARMED_ARMED); + break; + + case ARM_STATE_DISARMING_TIMEOUT: + // We get here when armed while throttle low, even when the arming timeout is not enabled + if ((settings->ArmedTimeout != 0) && (timeDifferenceMs(armedDisarmStart, lastSysTime) > settings->ArmedTimeout)) { + armState = ARM_STATE_DISARMED; + } + + // Switch to disarming due to manual control when needed + if (manualDisarm) { + armedDisarmStart = lastSysTime; + armState = ARM_STATE_DISARMING_MANUAL; + } + break; + + case ARM_STATE_DISARMING_MANUAL: + if (manualDisarm && (timeDifferenceMs(armedDisarmStart, lastSysTime) > ARMED_TIME_MS)) { + armState = ARM_STATE_DISARMED; + } else if (!manualDisarm) { + armState = ARM_STATE_ARMED; + } + break; + } // End Switch } } @@ -1072,12 +1089,14 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData static void processFlightMode(ManualControlSettingsData *settings, float flightMode) { FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); // Convert flightMode value into the switch position in the range [0..N-1] uint8_t pos = ((int16_t)(flightMode * 256.0f) + 256) * settings->FlightModeNumber >> 9; - if (pos >= settings->FlightModeNumber) + if (pos >= settings->FlightModeNumber) { pos = settings->FlightModeNumber - 1; + } uint8_t newMode = settings->FlightModePosition[pos]; @@ -1098,7 +1117,7 @@ bool validInputRange(int16_t min, int16_t max, uint16_t value) min = max; max = tmp; } - return (value >= min - CONNECTION_OFFSET && value <= max + CONNECTION_OFFSET); + return value >= min - CONNECTION_OFFSET && value <= max + CONNECTION_OFFSET; } /** @@ -1106,12 +1125,13 @@ bool validInputRange(int16_t min, int16_t max, uint16_t value) */ static void applyDeadband(float *value, float deadband) { - if (fabs(*value) < deadband) + if (fabs(*value) < deadband) { *value = 0.0f; - else if (*value > 0.0f) + } else if (*value > 0.0f) { *value -= deadband; - else + } else { *value += deadband; + } } #ifdef USE_INPUT_LPF @@ -1130,7 +1150,7 @@ static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel /** * Called whenever a critical configuration component changes */ -static void configurationUpdatedCb(UAVObjEvent * ev) +static void configurationUpdatedCb(UAVObjEvent *ev) { configuration_check(); } From 1c3fb70ab1203dfe55e14c671c6fea1c9f50d02d Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Fri, 3 May 2013 01:44:41 +0200 Subject: [PATCH 07/39] OP-629 Block arming on all navigation based modes Conflicts: flight/modules/ManualControl/manualcontrol.c --- flight/modules/ManualControl/manualcontrol.c | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index fd069b33b..a60614c62 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -916,7 +916,18 @@ static bool okToArm(void) } } - return true; + uint8_t flightMode; + FlightStatusFlightModeGet(&flightMode); + switch(flightMode) { + case FLIGHTSTATUS_FLIGHTMODE_MANUAL: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: + return true; + default: + return false; + + } } /** * @brief Determine if the aircraft is forced to disarm by an explicit alarm From c88c0e03a8b81043c54129dfde1708d20eeb5d7f Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Fri, 3 May 2013 22:28:34 +0200 Subject: [PATCH 08/39] OP-938 Reduce deadband to +/-10% around 0 --- flight/modules/ManualControl/manualcontrol.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index a60614c62..ad7c25ada 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -791,7 +791,7 @@ static void updateLandDesired(ManualControlCommandData *cmd, bool changed) */ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) { - const float DEADBAND = .20f; + const float DEADBAND = .10f; const float DEADBAND_HIGH = 1.0f / 2 + DEADBAND / 2; const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2; From 4c0e5a39ca8bf7145cd425538ffa9c9e4f4eae40 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sat, 4 May 2013 00:13:15 +0200 Subject: [PATCH 09/39] OP-935 Disables controls when no board is connected. Re-Factored the MixerCurve widget. --- .../openpilotgcs/stylesheets/default.qss | 32 +- .../cfg_vehicletypes/configccpmwidget.cpp | 4 +- .../cfg_vehicletypes/configcustomwidget.cpp | 3 +- .../configfixedwingwidget.cpp | 53 +-- .../cfg_vehicletypes/configfixedwingwidget.h | 3 + .../configgroundvehiclewidget.cpp | 59 +-- .../configgroundvehiclewidget.h | 3 + .../configmultirotorwidget.cpp | 164 +++---- .../cfg_vehicletypes/configmultirotorwidget.h | 2 + .../configcamerastabilizationwidget.cpp | 54 ++- .../config/configcamerastabilizationwidget.h | 2 +- .../plugins/config/configccattitudewidget.cpp | 12 +- .../src/plugins/config/configgadgetwidget.cpp | 5 +- .../src/plugins/config/configinputwidget.cpp | 214 ++++----- .../src/plugins/config/configinputwidget.h | 4 +- .../src/plugins/config/configoutputwidget.cpp | 178 ++++---- .../src/plugins/config/configoutputwidget.h | 2 +- .../config/configstabilizationwidget.cpp | 123 ++--- .../config/configstabilizationwidget.h | 2 +- .../src/plugins/config/configtxpidwidget.cpp | 29 +- .../src/plugins/config/configtxpidwidget.h | 1 + .../config/configvehicletypewidget.cpp | 6 +- .../src/plugins/config/defaultattitude.ui | 10 +- .../src/plugins/config/mixercurve.cpp | 103 +---- .../src/plugins/config/mixercurve.h | 1 - .../src/plugins/config/outputchannelform.h | 4 +- .../uavobjectwidgetutils/configtaskwidget.cpp | 30 +- .../uavobjectwidgetutils/configtaskwidget.h | 3 + .../uavobjectwidgetutils/mixercurvepoint.cpp | 79 ++-- .../uavobjectwidgetutils/mixercurvepoint.h | 35 +- .../uavobjectwidgetutils/mixercurvewidget.cpp | 423 ++---------------- .../uavobjectwidgetutils/mixercurvewidget.h | 27 +- 32 files changed, 641 insertions(+), 1029 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss index 0f100f1cc..3d2c71f2a 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss @@ -23,13 +23,27 @@ QSlider::add-page:horizontal { border-radius: 4px; } +QSlider::add-page:horizontal:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::sub-page:horizontal { - background: rgb(249, 117, 76); + background: rgb(78, 147, 246); border: 1px solid #777; height: 1px; border-radius: 4px; } +QSlider::sub-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::handle:horizontal { background: rgb(196, 196, 196); width: 18px; @@ -56,13 +70,27 @@ QSlider::sub-page:vertical { border-radius: 4px; } +QSlider::sub-page:vertical:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::add-page:vertical { - background: rgb(249, 117, 76); + background: rgb(78, 147, 246); border: 1px solid #777; width: 1px; border-radius: 4px; } +QSlider::add-page:vertical:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + QSlider::handle:vertical { background: rgb(196, 196, 196); width: 18px; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 6e764dc41..abab410fd 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -308,7 +308,9 @@ void ConfigCcpmWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->SwashLvlPositionSlider); parent.addWidget(m_aircraft->SwashLvlPositionSpinBox); parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget()); - parent.addWidget(m_aircraft->PitchCurve->getCurveWidget()); + parent.addWidget(m_aircraft->PitchCurve); + parent.addWidget(m_aircraft->ThrottleCurve->getCurveWidget()); + parent.addWidget(m_aircraft->PitchCurve); parent.addWidget(m_aircraft->ccpmAdvancedSettingsTable); } diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp index 684435b0a..192a20ed1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configcustomwidget.cpp @@ -68,7 +68,6 @@ ConfigCustomWidget::ConfigCustomWidget(QWidget *parent) : for (int i = 1; i < (int) VehicleConfig::CHANNEL_NUMELEM; i++) { m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd); } - } ConfigCustomWidget::~ConfigCustomWidget() @@ -84,7 +83,9 @@ void ConfigCustomWidget::setupUI(QString frameType) void ConfigCustomWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->customMixerTable); parent.addWidget(m_aircraft->customThrottle1Curve->getCurveWidget()); + parent.addWidget(m_aircraft->customThrottle1Curve); parent.addWidget(m_aircraft->customThrottle2Curve->getCurveWidget()); + parent.addWidget(m_aircraft->customThrottle2Curve); } void ConfigCustomWidget::resetActuators(GUIConfigDataUnion *configData) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index a2b7bf79f..da2575637 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -87,11 +87,9 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : m_aircraft->fixedWingType->addItems(fixedWingTypes); // Set default model to "Elevator aileron rudder" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - - //setupUI(m_aircraft->fixedWingType->currentText()); - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + setupUI(m_aircraft->fixedWingType->currentText()); } ConfigFixedWingWidget::~ConfigFixedWingWidget() @@ -109,64 +107,61 @@ void ConfigFixedWingWidget::setupUI(QString frameType) if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder1Label->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); - m_aircraft->fwRudder2Label->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator1Label->setEnabled(true); m_aircraft->fwElevator2ChannelBox->setEnabled(true); - m_aircraft->fwElevator2Label->setEnabled(true); m_aircraft->fwAileron1ChannelBox->setEnabled(true); - m_aircraft->fwAileron1Label->setEnabled(true); m_aircraft->fwAileron2ChannelBox->setEnabled(true); - m_aircraft->fwAileron2Label->setEnabled(true); m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonMixBox->setHidden(true); - + + m_aircraft->elevonSlider1->setEnabled(false); + m_aircraft->elevonSlider2->setEnabled(false); + } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator1Label->setEnabled(false); m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwElevator2Label->setEnabled(false); m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder1Label->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); - m_aircraft->fwRudder2Label->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonMixBox->setHidden(false); m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); - + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder1Label->setEnabled(false); m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwRudder2Label->setEnabled(false); - m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator1Label->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Vtail 1"); + m_aircraft->fwElevator1ChannelBox->setEnabled(true); + m_aircraft->fwElevator2Label->setText("Vtail 2"); - m_aircraft->elevonMixBox->setHidden(false); m_aircraft->fwElevator2ChannelBox->setEnabled(true); - m_aircraft->fwElevator2Label->setEnabled(true); + m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->elevonLabel1->setText("Rudder"); m_aircraft->elevonLabel2->setText("Pitch"); - } + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget()); + parent.addWidget(m_aircraft->fixedWingThrottle); parent.addWidget(m_aircraft->fixedWingType); parent.addWidget(m_aircraft->fwEngineChannelBox); @@ -508,6 +503,14 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) return true; } +void ConfigFixedWingWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupUI(m_aircraft->fixedWingType->currentText()); + } +} + /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index c738920d9..3a0d45883 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -64,6 +64,9 @@ private: bool setupFrameElevon(QString airframeType); bool setupFrameVtail(QString airframeType); +protected: + void enableControls(bool enable); + private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp index 771a2afb5..d37b58695 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp @@ -79,11 +79,9 @@ ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(QWidget *parent) : m_aircraft->groundVehicleType->addItems(groundVehicleTypes); // Set default model to "Turnable (car)" - m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)")); - - //setupUI(m_aircraft->groundVehicleType->currentText()); - connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)")); + setupUI(m_aircraft->groundVehicleType->currentText()); } ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget() @@ -96,42 +94,32 @@ ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget() */ void ConfigGroundVehicleWidget::setupUI(QString frameType) { - m_aircraft->differentialSteeringMixBox->setHidden(true); - //STILL NEEDS WORK - // Setup the UI m_aircraft->gvEngineChannelBox->setEnabled(false); - m_aircraft->gvEngineLabel->setEnabled(false); - m_aircraft->gvAileron1ChannelBox->setEnabled(false); - m_aircraft->gvAileron1Label->setEnabled(false); - m_aircraft->gvAileron2ChannelBox->setEnabled(false); - m_aircraft->gvAileron2Label->setEnabled(false); + + m_aircraft->differentialSteeringSlider1->setEnabled(false); + m_aircraft->differentialSteeringSlider2->setEnabled(false); if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)") { // Tank setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Differential (tank)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); - m_aircraft->gvMotor1Label->setEnabled(true); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Left motor"); m_aircraft->gvMotor2Label->setText("Right motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(false); - m_aircraft->gvSteering1Label->setEnabled(false); - m_aircraft->gvSteering2ChannelBox->setEnabled(false); - m_aircraft->gvSteering2Label->setEnabled(false); m_aircraft->gvSteering2Label->setText("Rear steering"); - m_aircraft->differentialSteeringMixBox->setHidden(false); + m_aircraft->differentialSteeringSlider1->setEnabled(true); + m_aircraft->differentialSteeringSlider2->setEnabled(true); m_aircraft->gvThrottleCurve1GroupBox->setTitle("Left throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Right throttle curve"); @@ -140,24 +128,16 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType) // Motorcycle setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle")); m_aircraft->gvMotor1ChannelBox->setEnabled(false); - m_aircraft->gvMotor1Label->setEnabled(false); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(true); - m_aircraft->gvSteering1Label->setEnabled(true); - m_aircraft->gvSteering2ChannelBox->setEnabled(true); - m_aircraft->gvSteering2Label->setEnabled(true); m_aircraft->gvSteering2Label->setText("Balancing"); - m_aircraft->differentialSteeringMixBox->setHidden(true); - m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); } else { @@ -165,31 +145,40 @@ void ConfigGroundVehicleWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)")); m_aircraft->gvMotor1ChannelBox->setEnabled(true); - m_aircraft->gvMotor1Label->setEnabled(true); - m_aircraft->gvMotor2ChannelBox->setEnabled(true); - m_aircraft->gvMotor2Label->setEnabled(true); m_aircraft->gvMotor1Label->setText("Front motor"); m_aircraft->gvMotor2Label->setText("Rear motor"); m_aircraft->gvSteering1ChannelBox->setEnabled(true); - m_aircraft->gvSteering1Label->setEnabled(true); - m_aircraft->gvSteering2ChannelBox->setEnabled(true); - m_aircraft->gvSteering2Label->setEnabled(true); - - m_aircraft->differentialSteeringMixBox->setHidden(true); m_aircraft->gvThrottleCurve1GroupBox->setTitle("Front throttle curve"); m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve"); } } +void ConfigGroundVehicleWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupUI(m_aircraft->groundVehicleType->currentText()); + } +} + void ConfigGroundVehicleWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget()); + parent.addWidget(m_aircraft->groundVehicleThrottle1); parent.addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget()); + parent.addWidget(m_aircraft->groundVehicleThrottle2); parent.addWidget(m_aircraft->groundVehicleType); + parent.addWidget(m_aircraft->gvEngineChannelBox); + parent.addWidget(m_aircraft->gvAileron1ChannelBox); + parent.addWidget(m_aircraft->gvAileron2ChannelBox); + parent.addWidget(m_aircraft->gvMotor1ChannelBox); + parent.addWidget(m_aircraft->gvMotor2ChannelBox); + parent.addWidget(m_aircraft->gvSteering1ChannelBox); + parent.addWidget(m_aircraft->gvSteering2ChannelBox); } void ConfigGroundVehicleWidget::resetActuators(GUIConfigDataUnion *configData) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h index 475f54a19..0a7abd858 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h @@ -54,6 +54,9 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); +protected: + void enableControls(bool enable); + private: Ui_GroundConfigWidget *m_aircraft; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 7fc9d46a5..a51cf370b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -122,6 +122,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) : // Connect the multirotor motor reverse checkbox connect(m_aircraft->MultirotorRevMixerCheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor())); + updateEnableControls(); } ConfigMultiRotorWidget::~ConfigMultiRotorWidget() @@ -134,6 +135,81 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) Q_ASSERT(m_aircraft); Q_ASSERT(quad); + if (frameType == "Tri" || frameType == "Tricopter Y") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "QuadX" || frameType == "Quad X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); + + // init mixer levels + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(50); + } else if (frameType == "QuadP" || frameType == "Quad +") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "Hexa" || frameType == "Hexacopter") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); + + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(33); + setYawMixLevel(33); + } else if (frameType == "HexaX" || frameType == "Hexacopter X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Hexacopter X")); + + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(33); + } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(66); + } else if (frameType == "Octo" || frameType == "Octocopter") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); + + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(33); + setYawMixLevel(25); + } else if (frameType == "OctoV" || frameType == "Octocopter V") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, + m_aircraft->multirotorFrameType->findText("Octocopter V")); + + m_aircraft->mrRollMixLevel->setValue(25); + m_aircraft->mrPitchMixLevel->setValue(25); + setYawMixLevel(25); + } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + setYawMixLevel(50); + } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); + + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + setYawMixLevel(50); + } + + // Enable/Disable controls + setupEnabledControls(frameType); + + // Draw the appropriate airframe + updateAirframe(frameType); +} + +void ConfigMultiRotorWidget::setupEnabledControls(QString frameType) +{ // disable triyaw channel m_aircraft->triYawChannelBox->setEnabled(false); @@ -148,109 +224,32 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) } if (frameType == "Tri" || frameType == "Tricopter Y") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 3, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); - m_aircraft->triYawChannelBox->setEnabled(true); } else if (frameType == "QuadX" || frameType == "Quad X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 4, true); - - // init mixer levels - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(50); } else if (frameType == "QuadP" || frameType == "Quad +") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 4, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); } else if (frameType == "Hexa" || frameType == "Hexacopter") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(33); - setYawMixLevel(33); } else if (frameType == "HexaX" || frameType == "Hexacopter X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Hexacopter X")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(33); } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); - - // Enable all necessary motor channel boxes... enableComboBoxes(this, CHANNELBOXNAME, 6, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(66); } else if (frameType == "Octo" || frameType == "Octocopter") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(33); - setYawMixLevel(25); } else if (frameType == "OctoV" || frameType == "Octocopter V") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, - m_aircraft->multirotorFrameType->findText("Octocopter V")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(25); - m_aircraft->mrPitchMixLevel->setValue(25); - setYawMixLevel(25); } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { - setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); - - // Enable all necessary motor channel boxes enableComboBoxes(this, CHANNELBOXNAME, 8, true); - - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - setYawMixLevel(50); } - - // Draw the appropriate airframe - updateAirframe(frameType); } void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->multiThrottleCurve->getCurveWidget()); + parent.addWidget(m_aircraft->multiThrottleCurve); parent.addWidget(m_aircraft->multirotorFrameType); parent.addWidget(m_aircraft->multiMotorChannelBox1); parent.addWidget(m_aircraft->multiMotorChannelBox2); @@ -264,6 +263,7 @@ void ConfigMultiRotorWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->mrRollMixLevel); parent.addWidget(m_aircraft->mrYawMixLevel); parent.addWidget(m_aircraft->triYawChannelBox); + parent.addWidget(m_aircraft->MultirotorRevMixerCheckBox); } void ConfigMultiRotorWidget::resetActuators(GUIConfigDataUnion *configData) @@ -1048,3 +1048,11 @@ void ConfigMultiRotorWidget::resizeEvent(QResizeEvent *event) Q_UNUSED(event); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); } + +void ConfigMultiRotorWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(enable) { + setupEnabledControls(m_aircraft->multirotorFrameType->currentText()); + } +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index 9361c0755..75c251777 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -58,6 +58,7 @@ public: protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); + void enableControls(bool enable); private: Ui_MultiRotorConfigWidget *m_aircraft; @@ -77,6 +78,7 @@ private: void setYawMixLevel(int); void updateAirframe(QString multiRotorType); + void setupEnabledControls(QString multiRotorType); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 621c5b032..4b8e445e5 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -43,24 +43,24 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { - m_camerastabilization = new Ui_CameraStabilizationWidget(); - m_camerastabilization->setupUi(this); + ui = new Ui_CameraStabilizationWidget(); + ui->setupUi(this); - addApplySaveButtons(m_camerastabilization->camerastabilizationSaveRAM,m_camerastabilization->camerastabilizationSaveSD); + addApplySaveButtons(ui->camerastabilizationSaveRAM,ui->camerastabilizationSaveSD); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) - m_camerastabilization->camerastabilizationSaveRAM->setVisible(false); + ui->camerastabilizationSaveRAM->setVisible(false); // These widgets don't have direct relation to UAVObjects // and need special processing QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel, + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel, }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -78,10 +78,10 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent autoLoadWidgets(); // Add some widgets to track their UI dirty state and handle smartsave - addWidget(m_camerastabilization->enableCameraStabilization); - addWidget(m_camerastabilization->rollChannel); - addWidget(m_camerastabilization->pitchChannel); - addWidget(m_camerastabilization->yawChannel); + addWidget(ui->enableCameraStabilization); + addWidget(ui->rollChannel); + addWidget(ui->pitchChannel); + addWidget(ui->yawChannel); // Add some UAVObjects to monitor their changes in addition to autoloaded ones. // Note also that we want to reload some UAVObjects by "Reload" button and have @@ -97,6 +97,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int))); disableMouseWheelEvents(); + updateEnableControls(); } ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() @@ -120,7 +121,7 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); - m_camerastabilization->enableCameraStabilization->setChecked( + ui->enableCameraStabilization->setChecked( hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); // Load mixer outputs which are mapped to camera controls @@ -144,9 +145,9 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -175,7 +176,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() // Save state of the module enable checkbox first. // Do not use setData() member on whole object, if possible, since it triggers // unnessesary UAVObect update. - quint8 enableModule = m_camerastabilization->enableCameraStabilization->isChecked() ? + quint8 enableModule = ui->enableCameraStabilization->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule); @@ -202,13 +203,13 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); - m_camerastabilization->message->setText(""); + ui->message->setText(""); bool widgetUpdated; do { widgetUpdated = false; @@ -223,7 +224,7 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() // If the mixer channel already mapped to something, it should not be // used for camera output, we reset it to none outputs[i]->setCurrentIndex(0); - m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); + ui->message->setText("One of the channels is already assigned, reverted to none"); // Loop again or we may have inconsistent widget and UAVObject widgetUpdated = true; @@ -270,9 +271,9 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) // For outputs we set them all to none, so don't use any UAVObject to get defaults QComboBox *outputs[] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel, + ui->rollChannel, + ui->pitchChannel, + ui->yawChannel, }; const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); @@ -280,8 +281,3 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) outputs[i]->setCurrentIndex(0); } } - -/** - @} - @} - */ diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 871193e82..2715daa77 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -43,7 +43,7 @@ public: ~ConfigCameraStabilizationWidget(); private: - Ui_CameraStabilizationWidget *m_camerastabilization; + Ui_CameraStabilizationWidget *ui; void refreshWidgetsValues(UAVObject *obj); void updateObjectsFromWidgets(); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index febfcf4e6..cd840e93e 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -216,15 +216,9 @@ void ConfigCCAttitudeWidget::setAccelFiltering(bool active) void ConfigCCAttitudeWidget::enableControls(bool enable) { - if(ui->zeroBias) { - ui->zeroBias->setEnabled(enable); - } - if(ui->zeroGyroBiasOnArming) { - ui->zeroGyroBiasOnArming->setEnabled(enable); - } - if(ui->accelTauSpinbox) { - ui->accelTauSpinbox->setEnabled(enable); - } + ui->zeroBias->setEnabled(enable); + ui->zeroGyroBiasOnArming->setEnabled(enable); + ui->accelTauSpinbox->setEnabled(enable); ConfigTaskWidget::enableControls(enable); } diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 9fc52d559..a79aa3cfa 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -142,8 +142,6 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) oplinkTimeout = new QTimer(this); connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect())); oplinkConnected = false; - - ftw->setWidgetsEnabled(false); } ConfigGadgetWidget::~ConfigGadgetWidget() @@ -165,7 +163,6 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) } void ConfigGadgetWidget::onAutopilotDisconnect() { - ftw->setWidgetsEnabled(false); int selectedIndex = ftw->currentIndex(); @@ -238,7 +235,7 @@ void ConfigGadgetWidget::onAutopilotConnect() { } ftw->setCurrentIndex(selectedIndex); } - ftw->setWidgetsEnabled(true); + emit autopilotConnected(); } diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 67083b941..505c3a125 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -63,17 +63,17 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); flightStatusObj = FlightStatus::GetInstance(getObjectManager()); receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); - m_config = new Ui_InputWidget(); - m_config->setupUi(this); + ui = new Ui_InputWidget(); + ui->setupUi(this); - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) - m_config->saveRCInputToRAM->setVisible(false); + ui->saveRCInputToRAM->setVisible(false); - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + addApplySaveButtons(ui->saveRCInputToRAM,ui->saveRCInputToSD); //Generate the rows of buttons in the input channel form GUI unsigned int index=0; @@ -82,13 +82,16 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : { Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); inputChannelForm * inpForm=new inputChannelForm(this,index==0); - m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI + ui->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI inpForm->setName(name); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index); addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index); + addWidget(inpForm->ui->channelNumberDropdown); + addWidget(inpForm->ui->channelRev); + addWidget(inpForm->ui->channelResponseTime); // Input filter response time fields supported for some channels only switch (index) { @@ -114,51 +117,53 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ++index; } - addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f); + addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", ui->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(ui->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); + connect(ui->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); + connect(ui->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); - connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); - connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); - connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); + connect(ui->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); + connect(ui->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); + connect(ui->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); - m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum); + ui->stackedWidget->setCurrentIndex(0); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos1, 0, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos2, 1, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos3, 2, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos4, 3, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos5, 4, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", ui->fmsModePos6, 5, 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", ui->fmsPosNum); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Roll, "Roll", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Pitch, "Pitch", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", ui->fmsSsPos1Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true); + addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true); - addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); - addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); + addUAVObjectToWidgetRelation("ManualControlSettings","Arming",ui->armControl); + addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",ui->armTimeout,0,1000); connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider())); - enableControls(false); + + addWidget(ui->configurationWizard); + addWidget(ui->runCalibration); populateWidgets(); refreshWidgetsValues(); // Connect the help button - connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + connect(ui->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - m_config->graphicsView->setScene(new QGraphicsScene(this)); - m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); + ui->graphicsView->setScene(new QGraphicsScene(this)); + ui->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); m_renderer = new QSvgRenderer(); - QGraphicsScene *l_scene = m_config->graphicsView->scene(); - m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); + QGraphicsScene *l_scene = ui->graphicsView->scene(); + ui->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); if (QFile::exists(":/configgadget/images/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.svg")) && m_renderer->isValid()) { l_scene->clear(); // Deletes all items contained in the scene as well. @@ -271,7 +276,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : m_txAccess2Orig.translate(orig.x(),orig.y()); m_txAccess2->setTransform(m_txAccess2Orig,true); } - m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); + ui->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); animate=new QTimer(this); connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls())); @@ -293,7 +298,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ManualControlSettings::CHANNELGROUPS_ACCESSORY0 << ManualControlSettings::CHANNELGROUPS_ACCESSORY1 << ManualControlSettings::CHANNELGROUPS_ACCESSORY2; + + updateEnableControls(); } + void ConfigInputWidget::resetTxControls() { @@ -312,10 +320,19 @@ ConfigInputWidget::~ConfigInputWidget() } +void ConfigInputWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + + if(enable) { + updatePositionSlider(); + } +} + void ConfigInputWidget::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } void ConfigInputWidget::openHelp() @@ -335,8 +352,8 @@ void ConfigInputWidget::goToWizard() msgBox.exec(); // Set correct tab visible before starting wizard. - if(m_config->tabWidget->currentIndex() != 0) { - m_config->tabWidget->setCurrentIndex(0); + if(ui->tabWidget->currentIndex() != 0) { + ui->tabWidget->setCurrentIndex(0); } // Stash current manual settings data in case the wizard is @@ -351,27 +368,27 @@ void ConfigInputWidget::goToWizard() // start the wizard wizardSetUpStep(wizardWelcome); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); } void ConfigInputWidget::disableWizardButton(int value) { if(value!=0) - m_config->groupBox_3->setVisible(false); + ui->groupBox_3->setVisible(false); else - m_config->groupBox_3->setVisible(true); + ui->groupBox_3->setVisible(true); } void ConfigInputWidget::wzCancel() { dimOtherControls(false); manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); - m_config->stackedWidget->setCurrentIndex(0); + ui->stackedWidget->setCurrentIndex(0); if(wizardStep != wizardNone) wizardTearDownStep(wizardStep); wizardStep=wizardNone; - m_config->stackedWidget->setCurrentIndex(0); + ui->stackedWidget->setCurrentIndex(0); // Load settings back from beginning of wizard manualSettingsObj->setData(previousManualSettingsData); @@ -433,8 +450,8 @@ void ConfigInputWidget::wzNext() } manualSettingsObj->setData(manualSettingsData); // move to Arming Settings tab - m_config->stackedWidget->setCurrentIndex(0); - m_config->tabWidget->setCurrentIndex(2); + ui->stackedWidget->setCurrentIndex(0); + ui->tabWidget->setCurrentIndex(2); break; default: Q_ASSERT(0); @@ -481,7 +498,7 @@ void ConfigInputWidget::wzBack() void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) { - m_config->wzText2->clear(); + ui->wzText2->clear(); switch(step) { case wizardWelcome: @@ -491,22 +508,22 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) delete wd; } extraWidgets.clear(); - m_config->graphicsView->setVisible(false); + ui->graphicsView->setVisible(false); setTxMovement(nothing); - m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n" + ui->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n" "Please follow the instructions on the screen and only move your controls when asked to.\n" "Make sure you already configured your hardware settings on the proper tab and restarted your board.\n\n" "You can press 'back' at any time to return to the previous screen or press 'Cancel' to quit the wizard.\n")); - m_config->stackedWidget->setCurrentIndex(1); - m_config->wzBack->setEnabled(false); + ui->stackedWidget->setCurrentIndex(1); + ui->wzBack->setEnabled(false); break; case wizardChooseType: { - m_config->graphicsView->setVisible(true); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); + ui->graphicsView->setVisible(true); + ui->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio); setTxMovement(nothing); - m_config->wzText->setText(tr("Please choose your transmitter type:")); - m_config->wzBack->setEnabled(true); + ui->wzText->setText(tr("Please choose your transmitter type:")); + ui->wzBack->setEnabled(true); QRadioButton * typeAcro=new QRadioButton(tr("Acro: normal transmitter for fixed-wing or quad"),this); QRadioButton * typeHeli=new QRadioButton(tr("Helicopter: has collective pitch and throttle input"),this); if (transmitterType == heli) { @@ -515,20 +532,20 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) else { typeAcro->setChecked(true); } - m_config->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now.")); + ui->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now.")); extraWidgets.clear(); extraWidgets.append(typeAcro); extraWidgets.append(typeHeli); - m_config->radioButtonsLayout->layout()->addWidget(typeAcro); - m_config->radioButtonsLayout->layout()->addWidget(typeHeli); + ui->radioButtonsLayout->layout()->addWidget(typeAcro); + ui->radioButtonsLayout->layout()->addWidget(typeHeli); } break; case wizardChooseMode: { - m_config->wzBack->setEnabled(true); + ui->wzBack->setEnabled(true); extraWidgets.clear(); - m_config->wzText->setText(tr("Please choose your transmitter mode:")); + ui->wzText->setText(tr("Please choose your transmitter mode:")); for (int i = 0; i <= mode4; ++i) { QString label; txMode mode = static_cast(i); @@ -548,14 +565,14 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) case mode4: label = tr("Mode 4: Throttle and Ailerons on the left, Elevator and Rudder on the right"); break; default: Q_ASSERT(0); break; } - m_config->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw.")); + ui->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw.")); } QRadioButton * modeButton = new QRadioButton(label, this); if (transmitterMode == mode) { modeButton->setChecked(true); } extraWidgets.append(modeButton); - m_config->radioButtonsLayout->layout()->addWidget(modeButton); + ui->radioButtonsLayout->layout()->addWidget(modeButton); } } break; @@ -565,11 +582,11 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) nextChannel(); manualSettingsData=manualSettingsObj->getData(); connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); - m_config->wzNext->setEnabled(false); + ui->wzNext->setEnabled(false); break; case wizardIdentifyCenter: setTxMovement(centerAll); - m_config->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n" + ui->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n" "If your FlightMode switch has only two positions, leave it in either position."))); break; case wizardIdentifyLimits: @@ -578,7 +595,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) 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.\n\nPress Next when ready."))); + ui->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready."))); fastMdata(); manualSettingsData=manualSettingsObj->getData(); for(uint i=0;isetChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]); - dynamic_cast(m_config->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4); + dynamic_cast(ui->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4); extraWidgets.append(cb); connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); } } connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready."))); + ui->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready."))); fastMdata(); break; case wizardFinish: @@ -626,7 +643,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) 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 mimics your sticks movement.\n\n" + ui->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n" "IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings " "tab where you can set your desired arming sequence and save the configuration."))); fastMdata(); @@ -666,7 +683,7 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step) break; case wizardIdentifySticks: disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); - m_config->wzNext->setEnabled(true); + ui->wzNext->setEnabled(true); setTxMovement(nothing); break; case wizardIdentifyCenter: @@ -742,21 +759,21 @@ void ConfigInputWidget::restoreMdata() void ConfigInputWidget::setChannel(int newChan) { if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE) - m_config->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick."))); + ui->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick."))); else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) - m_config->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly."))); + ui->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly."))); else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE)) - m_config->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick."))); + ui->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick."))); else - m_config->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n" + ui->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n" "Move the %1 stick.")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan))); if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") || manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) { - m_config->wzNext->setEnabled(true); - m_config->wzText->setText(m_config->wzText->text() + tr(" Alternatively, click Next to skip this channel.")); + ui->wzNext->setEnabled(true); + ui->wzText->setText(ui->wzText->text() + tr(" Alternatively, click Next to skip this channel.")); } else - m_config->wzNext->setEnabled(false); + ui->wzNext->setEnabled(false); setMoveFromCommand(newChan); @@ -1249,15 +1266,6 @@ void ConfigInputWidget::dimOtherControls(bool value) m_txFlightMode->setOpacity(opac); } -void ConfigInputWidget::enableControls(bool enable) -{ - m_config->configurationWizard->setEnabled(enable); - m_config->runCalibration->setEnabled(enable); - - ConfigTaskWidget::enableControls(enable); - -} - void ConfigInputWidget::invertControls() { manualSettingsData=manualSettingsObj->getData(); @@ -1318,7 +1326,7 @@ void ConfigInputWidget::moveFMSlider() uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9; if (pos >= manualSettingsDataPriv.FlightModeNumber) pos = manualSettingsDataPriv.FlightModeNumber - 1; - m_config->fmsSlider->setValue(pos); + ui->fmsSlider->setValue(pos); } void ConfigInputWidget::updatePositionSlider() @@ -1328,22 +1336,22 @@ void ConfigInputWidget::updatePositionSlider() switch(manualSettingsDataPriv.FlightModeNumber) { default: case 6: - m_config->fmsModePos6->setEnabled(true); + ui->fmsModePos6->setEnabled(true); // pass through case 5: - m_config->fmsModePos5->setEnabled(true); + ui->fmsModePos5->setEnabled(true); // pass through case 4: - m_config->fmsModePos4->setEnabled(true); + ui->fmsModePos4->setEnabled(true); // pass through case 3: - m_config->fmsModePos3->setEnabled(true); + ui->fmsModePos3->setEnabled(true); // pass through case 2: - m_config->fmsModePos2->setEnabled(true); + ui->fmsModePos2->setEnabled(true); // pass through case 1: - m_config->fmsModePos1->setEnabled(true); + ui->fmsModePos1->setEnabled(true); // pass through case 0: break; @@ -1351,22 +1359,22 @@ void ConfigInputWidget::updatePositionSlider() switch(manualSettingsDataPriv.FlightModeNumber) { case 0: - m_config->fmsModePos1->setEnabled(false); + ui->fmsModePos1->setEnabled(false); // pass through case 1: - m_config->fmsModePos2->setEnabled(false); + ui->fmsModePos2->setEnabled(false); // pass through case 2: - m_config->fmsModePos3->setEnabled(false); + ui->fmsModePos3->setEnabled(false); // pass through case 3: - m_config->fmsModePos4->setEnabled(false); + ui->fmsModePos4->setEnabled(false); // pass through case 4: - m_config->fmsModePos5->setEnabled(false); + ui->fmsModePos5->setEnabled(false); // pass through case 5: - m_config->fmsModePos6->setEnabled(false); + ui->fmsModePos6->setEnabled(false); // pass through case 6: default: @@ -1395,7 +1403,7 @@ void ConfigInputWidget::updateCalibration() void ConfigInputWidget::simpleCalibration(bool enable) { if (enable) { - m_config->configurationWizard->setEnabled(false); + ui->configurationWizard->setEnabled(false); QMessageBox msgBox; msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety.")); @@ -1421,7 +1429,7 @@ void ConfigInputWidget::simpleCalibration(bool enable) connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration())); } else { - m_config->configurationWizard->setEnabled(true); + ui->configurationWizard->setEnabled(true); manualCommandData = manualCommandObj->getData(); manualSettingsData = manualSettingsObj->getData(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index 47705aa82..be8adedb8 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -61,6 +61,7 @@ public: enum txMovementType{vertical,horizontal,jump,mix}; enum txType {acro, heli}; void startInputWizard() { goToWizard(); } + void enableControls(bool enable); private: bool growing; @@ -68,7 +69,7 @@ private: txMovements currentMovement; int movePos; void setTxMovement(txMovements movement); - Ui_InputWidget *m_config; + Ui_InputWidget *ui; wizardSteps wizardStep; QList > extraWidgets; txMode transmitterMode; @@ -166,7 +167,6 @@ private slots: protected: void resizeEvent(QResizeEvent *event); - virtual void enableControls(bool enable); }; #endif diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index c1e364b86..d71918aba 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -51,46 +51,51 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) { - m_config = new Ui_OutputWidget(); - m_config->setupUi(this); + ui = new Ui_OutputWidget(); + ui->setupUi(this); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings *settings = pm->getObject(); if(!settings->useExpertMode()) { - m_config->saveRCOutputToRAM->setVisible(false); + ui->saveRCOutputToRAM->setVisible(false); } UAVSettingsImportExportFactory *importexportplugin = pm->getObject(); connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(stopTests())); - // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. - // Register for ActuatorSettings changes: - for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { - OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); - connect(m_config->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); - connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int))); - m_config->channelLayout->addWidget(form); - } - - connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); + connect(ui->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); // Configure the task widget // Connect the help button - connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + connect(ui->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + addApplySaveButtons(ui->saveRCOutputToRAM, ui->saveRCOutputToSD); // Track the ActuatorSettings object addUAVObject("ActuatorSettings"); + // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. + // Register for ActuatorSettings changes: + for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { + OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); + connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); + connect(form, SIGNAL(channelChanged(int,int)), this, SLOT(sendChannelTest(int,int))); + ui->channelLayout->addWidget(form); + addWidget(form->ui.actuatorMin); + addWidget(form->ui.actuatorNeutral); + addWidget(form->ui.actuatorMax); + addWidget(form->ui.actuatorRev); + addWidget(form->ui.actuatorLink); + } + // Associate the buttons with their UAVO fields - addWidget(m_config->cb_outputRate6); - addWidget(m_config->cb_outputRate5); - addWidget(m_config->cb_outputRate4); - addWidget(m_config->cb_outputRate3); - addWidget(m_config->cb_outputRate2); - addWidget(m_config->cb_outputRate1); - addWidget(m_config->spinningArmed); + addWidget(ui->cb_outputRate6); + addWidget(ui->cb_outputRate5); + addWidget(ui->cb_outputRate4); + addWidget(ui->cb_outputRate3); + addWidget(ui->cb_outputRate2); + addWidget(ui->cb_outputRate1); + addWidget(ui->spinningArmed); disconnect(this, SLOT(refreshWidgetsValues(UAVObject*))); @@ -102,15 +107,16 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren connect(obj,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(disableIfNotMe(UAVObject*))); refreshWidgetsValues(); + updateEnableControls(); } void ConfigOutputWidget::enableControls(bool enable) { ConfigTaskWidget::enableControls(enable); if(!enable) { - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); } - m_config->channelOutTest->setEnabled(enable); + ui->channelOutTest->setEnabled(enable); } ConfigOutputWidget::~ConfigOutputWidget() @@ -136,7 +142,7 @@ void ConfigOutputWidget::runChannelTests(bool state) // Unfortunately must cache this since callback will reoccur accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata(); - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); return; } @@ -149,7 +155,7 @@ void ConfigOutputWidget::runChannelTests(bool state) if(retval != QMessageBox::Yes) { state = false; qDebug() << "Cancelled"; - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); return; } } @@ -209,7 +215,7 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) */ void ConfigOutputWidget::sendChannelTest(int index, int value) { - if (!m_config->channelOutTest->isChecked()) { + if (!ui->channelOutTest->isChecked()) { return; } @@ -260,47 +266,47 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj) } // Get the SpinWhileArmed setting - m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); + ui->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); // Setup output rates for all banks - if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) { - m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); + if(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])) == -1) { + ui->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); } - if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) { - m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); + if(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])) == -1) { + ui->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); } - if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) { - m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); + if(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]) )== -1) { + ui->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); } - if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) { - m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); + if(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])) == -1) { + ui->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); } - if(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) { - m_config->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])); + if(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])) == -1) { + ui->cb_outputRate5->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[4])); } - if(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) { - m_config->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])); + if(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])) == -1) { + ui->cb_outputRate6->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[5])); } - m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); - m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); - m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); - m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); - m_config->cb_outputRate5->setCurrentIndex(m_config->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]))); - m_config->cb_outputRate6->setCurrentIndex(m_config->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]))); + ui->cb_outputRate1->setCurrentIndex(ui->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); + ui->cb_outputRate2->setCurrentIndex(ui->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); + ui->cb_outputRate3->setCurrentIndex(ui->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); + ui->cb_outputRate4->setCurrentIndex(ui->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); + ui->cb_outputRate5->setCurrentIndex(ui->cb_outputRate5->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[4]))); + ui->cb_outputRate6->setCurrentIndex(ui->cb_outputRate6->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[5]))); // Reset to all disabled - m_config->chBank1->setText("-"); - m_config->chBank2->setText("-"); - m_config->chBank3->setText("-"); - m_config->chBank4->setText("-"); - m_config->chBank5->setText("-"); - m_config->chBank6->setText("-"); - m_config->cb_outputRate1->setEnabled(false); - m_config->cb_outputRate2->setEnabled(false); - m_config->cb_outputRate3->setEnabled(false); - m_config->cb_outputRate4->setEnabled(false); - m_config->cb_outputRate5->setEnabled(false); - m_config->cb_outputRate6->setEnabled(false); + ui->chBank1->setText("-"); + ui->chBank2->setText("-"); + ui->chBank3->setText("-"); + ui->chBank4->setText("-"); + ui->chBank5->setText("-"); + ui->chBank6->setText("-"); + ui->cb_outputRate1->setEnabled(false); + ui->cb_outputRate2->setEnabled(false); + ui->cb_outputRate3->setEnabled(false); + ui->cb_outputRate4->setEnabled(false); + ui->cb_outputRate5->setEnabled(false); + ui->cb_outputRate6->setEnabled(false); // Get connected board model ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -313,29 +319,29 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj) // Setup labels and combos for banks according to board type if ((board & 0xff00) == 0x0400) { // Coptercontrol family of boards 4 timer banks - m_config->chBank1->setText("1-3"); - m_config->chBank2->setText("4"); - m_config->chBank3->setText("5,7-8"); - m_config->chBank4->setText("6,9-10"); - m_config->cb_outputRate1->setEnabled(true); - m_config->cb_outputRate2->setEnabled(true); - m_config->cb_outputRate3->setEnabled(true); - m_config->cb_outputRate4->setEnabled(true); + ui->chBank1->setText("1-3"); + ui->chBank2->setText("4"); + ui->chBank3->setText("5,7-8"); + ui->chBank4->setText("6,9-10"); + ui->cb_outputRate1->setEnabled(true); + ui->cb_outputRate2->setEnabled(true); + ui->cb_outputRate3->setEnabled(true); + ui->cb_outputRate4->setEnabled(true); } else if((board & 0xff00) == 0x0900) { // Revolution family of boards 6 timer banks - m_config->chBank1->setText("1-2"); - m_config->chBank2->setText("3"); - m_config->chBank3->setText("4"); - m_config->chBank4->setText("5-6"); - m_config->chBank5->setText("7-8"); - m_config->chBank6->setText("9-10"); - m_config->cb_outputRate1->setEnabled(true); - m_config->cb_outputRate2->setEnabled(true); - m_config->cb_outputRate3->setEnabled(true); - m_config->cb_outputRate4->setEnabled(true); - m_config->cb_outputRate5->setEnabled(true); - m_config->cb_outputRate6->setEnabled(true); + ui->chBank1->setText("1-2"); + ui->chBank2->setText("3"); + ui->chBank3->setText("4"); + ui->chBank4->setText("5-6"); + ui->chBank5->setText("7-8"); + ui->chBank6->setText("9-10"); + ui->cb_outputRate1->setEnabled(true); + ui->cb_outputRate2->setEnabled(true); + ui->cb_outputRate3->setEnabled(true); + ui->cb_outputRate4->setEnabled(true); + ui->cb_outputRate5->setEnabled(true); + ui->cb_outputRate6->setEnabled(true); } } @@ -371,14 +377,14 @@ void ConfigOutputWidget::updateObjectsFromWidgets() } // Set update rates - actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[4] = m_config->cb_outputRate5->currentText().toUInt(); - actuatorSettingsData.ChannelUpdateFreq[5] = m_config->cb_outputRate6->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[0] = ui->cb_outputRate1->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[1] = ui->cb_outputRate2->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[2] = ui->cb_outputRate3->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[3] = ui->cb_outputRate4->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[4] = ui->cb_outputRate5->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[5] = ui->cb_outputRate6->currentText().toUInt(); - actuatorSettingsData.MotorsSpinWhileArmed = m_config->spinningArmed->isChecked() ? + actuatorSettingsData.MotorsSpinWhileArmed = ui->spinningArmed->isChecked() ? ActuatorSettings::MOTORSSPINWHILEARMED_TRUE : ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; @@ -394,7 +400,7 @@ void ConfigOutputWidget::openHelp() void ConfigOutputWidget::stopTests() { - m_config->channelOutTest->setChecked(false); + ui->channelOutTest->setChecked(false); } void ConfigOutputWidget::disableIfNotMe(UAVObject* obj) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index 9a347d3f9..1d15c8de5 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -50,7 +50,7 @@ public: private: - Ui_OutputWidget *m_config; + Ui_OutputWidget *ui; QList sliders; diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 949d76529..bab5640f6 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -41,35 +41,53 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { - m_stabilization = new Ui_StabilizationWidget(); - m_stabilization->setupUi(this); + ui = new Ui_StabilizationWidget(); + ui->setupUi(this); ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings* settings = pm->getObject(); if(!settings->useExpertMode()) { - m_stabilization->saveStabilizationToRAM_6->setVisible(false); + ui->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_8, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + realtimeUpdates = new QTimer(this); connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply())); - connect(m_stabilization->checkBox_7, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_2, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_8, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); - connect(m_stabilization->checkBox_3, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(ui->realTimeUpdates_6, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + addWidget(ui->realTimeUpdates_6); + connect(ui->realTimeUpdates_8, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + addWidget(ui->realTimeUpdates_8); + + connect(ui->checkBox_7, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + addWidget(ui->checkBox_7); + connect(ui->checkBox_2, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + addWidget(ui->checkBox_2); + connect(ui->checkBox_8, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + addWidget(ui->checkBox_8); + connect(ui->checkBox_3, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + addWidget(ui->checkBox_3); + + addWidget(ui->pushButton_2); + addWidget(ui->pushButton_3); + addWidget(ui->pushButton_4); + addWidget(ui->pushButton_5); + addWidget(ui->pushButton_6); + addWidget(ui->pushButton_9); + addWidget(ui->pushButton_20); + addWidget(ui->pushButton_22); + addWidget(ui->pushButton_23); connect(this, SIGNAL(widgetContentsChanged(QWidget*)), this, SLOT(processLinkedWidgets(QWidget*))); // Link by default - m_stabilization->checkBox_7->setChecked(true); - m_stabilization->checkBox_8->setChecked(true); + ui->checkBox_7->setChecked(true); + ui->checkBox_8->setChecked(true); disableMouseWheelEvents(); + updateEnableControls(); } ConfigStabilizationWidget::~ConfigStabilizationWidget() @@ -79,8 +97,8 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) { - m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - m_stabilization->realTimeUpdates_8->setCheckState((Qt::CheckState)value); + ui->realTimeUpdates_6->setCheckState((Qt::CheckState)value); + ui->realTimeUpdates_8->setCheckState((Qt::CheckState)value); if(value == Qt::Checked && !realtimeUpdates->isActive()) { realtimeUpdates->start(300); @@ -92,84 +110,85 @@ void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) void ConfigStabilizationWidget::linkCheckBoxes(int value) { - if(sender() == m_stabilization->checkBox_7) { - m_stabilization->checkBox_3->setCheckState((Qt::CheckState)value); + if(sender() == ui->checkBox_7) { + ui->checkBox_3->setCheckState((Qt::CheckState)value); } - else if(sender() == m_stabilization->checkBox_3) { - m_stabilization->checkBox_7->setCheckState((Qt::CheckState)value); + else if(sender() == ui->checkBox_3) { + ui->checkBox_7->setCheckState((Qt::CheckState)value); } - else if(sender( )== m_stabilization->checkBox_8) { - m_stabilization->checkBox_2->setCheckState((Qt::CheckState)value); + else if(sender( )== ui->checkBox_8) { + ui->checkBox_2->setCheckState((Qt::CheckState)value); } - else if(sender() == m_stabilization->checkBox_2) { - m_stabilization->checkBox_8->setCheckState((Qt::CheckState)value); + else if(sender() == ui->checkBox_2) { + ui->checkBox_8->setCheckState((Qt::CheckState)value); } } void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) { - if(m_stabilization->checkBox_7->checkState()==Qt::Checked) + if(ui->checkBox_7->checkState()==Qt::Checked) { - if(widget== m_stabilization->RateRollKp_2) + if(widget== ui->RateRollKp_2) { - m_stabilization->RatePitchKp->setValue(m_stabilization->RateRollKp_2->value()); + ui->RatePitchKp->setValue(ui->RateRollKp_2->value()); } - else if(widget== m_stabilization->RateRollKi_2) + else if(widget== ui->RateRollKi_2) { - m_stabilization->RatePitchKi->setValue(m_stabilization->RateRollKi_2->value()); + ui->RatePitchKi->setValue(ui->RateRollKi_2->value()); } - else if(widget== m_stabilization->RateRollILimit_2) + else if(widget== ui->RateRollILimit_2) { - m_stabilization->RatePitchILimit->setValue(m_stabilization->RateRollILimit_2->value()); + ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value()); } - else if(widget== m_stabilization->RatePitchKp) + else if(widget== ui->RatePitchKp) { - m_stabilization->RateRollKp_2->setValue(m_stabilization->RatePitchKp->value()); + ui->RateRollKp_2->setValue(ui->RatePitchKp->value()); } - else if(widget== m_stabilization->RatePitchKi) + else if(widget== ui->RatePitchKi) { - m_stabilization->RateRollKi_2->setValue(m_stabilization->RatePitchKi->value()); + ui->RateRollKi_2->setValue(ui->RatePitchKi->value()); } - else if(widget== m_stabilization->RatePitchILimit) + else if(widget== ui->RatePitchILimit) { - m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value()); + ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value()); } - else if(widget== m_stabilization->RollRateKd) + else if(widget== ui->RollRateKd) { - m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value()); + ui->PitchRateKd->setValue(ui->RollRateKd->value()); } - else if(widget== m_stabilization->PitchRateKd) + else if(widget== ui->PitchRateKd) { - m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value()); + ui->RollRateKd->setValue(ui->PitchRateKd->value()); } } - if(m_stabilization->checkBox_8->checkState()==Qt::Checked) + if(ui->checkBox_8->checkState()==Qt::Checked) { - if(widget== m_stabilization->AttitudeRollKp) + if(widget== ui->AttitudeRollKp) { - m_stabilization->AttitudePitchKp_2->setValue(m_stabilization->AttitudeRollKp->value()); + ui->AttitudePitchKp_2->setValue(ui->AttitudeRollKp->value()); } - else if(widget== m_stabilization->AttitudeRollKi) + else if(widget== ui->AttitudeRollKi) { - m_stabilization->AttitudePitchKi_2->setValue(m_stabilization->AttitudeRollKi->value()); + ui->AttitudePitchKi_2->setValue(ui->AttitudeRollKi->value()); } - else if(widget== m_stabilization->AttitudeRollILimit) + else if(widget== ui->AttitudeRollILimit) { - m_stabilization->AttitudePitchILimit_2->setValue(m_stabilization->AttitudeRollILimit->value()); + ui->AttitudePitchILimit_2->setValue(ui->AttitudeRollILimit->value()); } - else if(widget== m_stabilization->AttitudePitchKp_2) + else if(widget== ui->AttitudePitchKp_2) { - m_stabilization->AttitudeRollKp->setValue(m_stabilization->AttitudePitchKp_2->value()); + ui->AttitudeRollKp->setValue(ui->AttitudePitchKp_2->value()); } - else if(widget== m_stabilization->AttitudePitchKi_2) + else if(widget== ui->AttitudePitchKi_2) { - m_stabilization->AttitudeRollKi->setValue(m_stabilization->AttitudePitchKi_2->value()); + ui->AttitudeRollKi->setValue(ui->AttitudePitchKi_2->value()); } - else if(widget== m_stabilization->AttitudePitchILimit_2) + else if(widget== ui->AttitudePitchILimit_2) { - m_stabilization->AttitudeRollILimit->setValue(m_stabilization->AttitudePitchILimit_2->value()); + ui->AttitudeRollILimit->setValue(ui->AttitudePitchILimit_2->value()); } } } + diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 266b59ae9..1cf4f51ed 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -46,7 +46,7 @@ public: ~ConfigStabilizationWidget(); private: - Ui_StabilizationWidget *m_stabilization; + Ui_StabilizationWidget *ui; QTimer * realtimeUpdates; private slots: void realtimeUpdatesSlot(int); diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 91ecfdb2e..7eb91becc 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -109,8 +109,29 @@ void ConfigTxPIDWidget::saveSettings() saveObjectToSD(obj); } +void ConfigTxPIDWidget::enableControls(bool enable) +{ + /* + m_txpid->PID1->setEnabled(enable); + m_txpid->PID2->setEnabled(enable); + m_txpid->PID3->setEnabled(enable); -/** - @} - @} - */ + m_txpid->Input1->setEnabled(enable); + m_txpid->Input2->setEnabled(enable); + m_txpid->Input3->setEnabled(enable); + + m_txpid->MinPID1->setEnabled(enable); + m_txpid->MinPID2->setEnabled(enable); + m_txpid->MinPID3->setEnabled(enable); + + m_txpid->MaxPID1->setEnabled(enable); + m_txpid->MaxPID2->setEnabled(enable); + m_txpid->MaxPID3->setEnabled(enable); + + m_txpid->ThrottleMin->setEnabled(enable); + m_txpid->ThrottleMax->setEnabled(enable); + + m_txpid->UpdateMode->setEnabled(enable); + */ + ConfigTaskWidget::setEnabled(enable); +} diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h index 14eb5925d..311a62372 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h @@ -44,6 +44,7 @@ private slots: void refreshValues(); void applySettings(); void saveSettings(); + void enableControls(bool enable); }; #endif // CONFIGTXPIDWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index f22d84214..af316585a 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -138,8 +138,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi // Connect the help pushbutton connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - enableControls(false); - refreshWidgetsValues(); // register widgets for dirty state management @@ -150,8 +148,12 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi addWidget(m_aircraft->accelTime); addWidget(m_aircraft->decelTime); addWidget(m_aircraft->maxAccelSlider); + addWidget(m_aircraft->ffTestBox1); + addWidget(m_aircraft->ffTestBox2); + addWidget(m_aircraft->ffTestBox3); disableMouseWheelEvents(); + updateEnableControls(); } /** diff --git a/ground/openpilotgcs/src/plugins/config/defaultattitude.ui b/ground/openpilotgcs/src/plugins/config/defaultattitude.ui index c191e996c..ebb726ae1 100644 --- a/ground/openpilotgcs/src/plugins/config/defaultattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/defaultattitude.ui @@ -29,11 +29,11 @@ <!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-weight:600;">Attitude / INS calibration</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-weight:600;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot INS or your CopterControl unit, depending on the board which is detected once telemetry is connected and running.</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;"></p></body></html> +</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-family:'Ubuntu'; font-size:11pt; font-weight:600;">Attitude Calibration</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; font-weight:600;"><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;">This panel will be updated to provide the relevant controls to let you calibrate your OpenPilot unit, depending on the board which is detected once telemetry is connected and running.</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></body></html> diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index b55974c86..3b45d7df5 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -43,10 +43,6 @@ MixerCurve::MixerCurve(QWidget *parent) : m_mixerUI->SettingsGroup->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(); @@ -54,27 +50,19 @@ 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->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(MixerNode*)),this, SLOT(CommandActivated(MixerNode*))); 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() @@ -103,7 +91,6 @@ void MixerCurve::setMixerType(MixerCurveType curveType) { m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); m_curve->setRange(-1.0, 1.0); - m_curve->setPositiveColor("#0000aa", "#0000aa"); m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); break; @@ -126,37 +113,26 @@ void MixerCurve::ResetCurve() initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin()); - m_curve->activateCommand("Linear"); - UpdateSettingsTable(); } void MixerCurve::PopupCurve() { - if (!m_curve->isCommandActive("Popup")) { + m_mixerUI->SettingsGroup->show(); + m_mixerUI->PopupCurve->hide(); - m_mixerUI->SettingsGroup->show(); - m_mixerUI->PopupCurve->hide(); + PopupWidget* popup = new PopupWidget(); + popup->popUp(this); - PopupWidget* popup = new PopupWidget(); - popup->popUp(this); - - m_mixerUI->SettingsGroup->hide(); - m_mixerUI->PopupCurve->show(); - m_curve->showCommands(false); - } + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->PopupCurve->show(); } + 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); @@ -229,8 +205,6 @@ 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; @@ -282,10 +256,12 @@ void MixerCurve::initCurve (const QList* points) m_curve->setCurve(points); UpdateSettingsTable(); } + QList MixerCurve::getCurve() { return m_curve->getCurve(); } + void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue) { setMin(minValue); @@ -296,39 +272,45 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue if (m_spinDelegate) m_spinDelegate->setRange(minValue, maxValue); } + void MixerCurve::setCurve(const QList* points) { m_curve->setCurve(points); 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() { return m_mixerUI->CurveMin->value(); } + double MixerCurve::getCurveMax() { return m_mixerUI->CurveMax->value(); @@ -370,59 +352,6 @@ void MixerCurve::SettingsTableChanged() m_curve->setCurve(&points); } -void MixerCurve::CommandActivated(MixerNode* node) -{ - QString name = (node) ? node->getName() : "Reset"; - - if (name == "Reset") { - ResetCurve(); - m_curve->showCommands(false); - } - else if (name == "Commands") { - - } - else if (name == "Popup" ) { - PopupCurve(); - } - 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 ef98414bc..58e0c2f8b 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -84,7 +84,6 @@ public slots: void UpdateSettingsTable(); private slots: - void CommandActivated(MixerNode* node = 0); void SettingsTableChanged(); void CurveTypeChanged(); void CurveMinChanged(double value); diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.h b/ground/openpilotgcs/src/plugins/config/outputchannelform.h index 873a5ea50..434f9517a 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.h +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.h @@ -38,7 +38,7 @@ class OutputChannelForm : public ConfigTaskWidget public: explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); ~OutputChannelForm(); - friend class ConfigOnputWidget; + friend class ConfigOutputWidget; void setAssignment(const QString &assignment); int index() const; @@ -57,10 +57,10 @@ signals: void channelChanged(int index, int value); private: - Ui::outputChannelForm ui; /// Channel index int m_index; bool m_inChannelTest; + Ui::outputChannelForm ui; private slots: void linkToggled(bool state); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index bf7a7dcc3..47ede15f8 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -429,12 +429,9 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav smartsave->addObject((UAVDataObject*)oTw->object); } } - TelemetryManager* telMngr = pm->getObject(); - if(telMngr->isConnected()) - enableControls(true); - else - enableControls(false); + updateEnableControls(); } + /** * SLOT function used the enable or disable the SAVE, UPLOAD and RELOAD buttons * @param enable set to true to enable the buttons or false to disable them @@ -442,12 +439,24 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav */ void ConfigTaskWidget::enableControls(bool enable) { - if(smartsave) + if(smartsave) { smartsave->enableControls(enable); - foreach (QPushButton * button, reloadButtonList) { + } + + foreach (QPushButton *button, reloadButtonList) { button->setEnabled(enable); } + + foreach(objectToWidget *ow,objOfInterest) { + if(ow->widget) { + ow->widget->setEnabled(enable); + foreach (shadow *sh, ow->shadowsList) { + sh->widget->setEnabled(enable); + } + } + } } + /** * SLOT function called when on of the widgets contents added to the framework changes */ @@ -1310,6 +1319,13 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field, } } +void ConfigTaskWidget::updateEnableControls() +{ + TelemetryManager* telMngr = pm->getObject(); + Q_ASSERT(telMngr); + enableControls(telMngr->isConnected()); +} + void ConfigTaskWidget::disableMouseWheelEvents() { //Disable mouse wheel events diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 78f0c5b0c..f10670868 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -195,6 +195,7 @@ private: void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; QTimer * timeOut; + protected slots: virtual void disableObjUpdates(); virtual void enableObjUpdates(); @@ -207,6 +208,8 @@ protected slots: protected: virtual void enableControls(bool enable); void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale); + void updateEnableControls(); + }; #endif // CONFIGTASKWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index c4462fc94..2ad7d4b95 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -43,17 +43,15 @@ MixerNode::MixerNode(MixerCurveWidget *graphWidget) setFlag(ItemSendsGeometryChanges); setCacheMode(DeviceCoordinateCache); setZValue(-1); - cmdActive = false; vertical = false; - cmdNode = false; - cmdToggle = true; drawNode = true; drawText = true; - posColor0 = "#1c870b"; //greenish? - posColor1 = "#116703"; //greenish? - negColor0 = "#aa0000"; //red - negColor1 = "#aa0000"; //red + positiveColor = "#609FF2"; //blueish? + neutralColor = "#14CE24"; //greenish? + negativeColor = "#EF5F5F"; //redish? + disabledColor = "#dddddd"; + disabledTextColor = "#aaaaaa"; } void MixerNode::addEdge(Edge *edge) @@ -70,7 +68,7 @@ QList MixerNode::edges() const QRectF MixerNode::boundingRect() const { - return cmdNode ? QRectF(-4, -4, 15, 10) : QRectF(-13, -13, 26, 26); + return QRectF(-13, -13, 26, 26); } QPainterPath MixerNode::shape() const @@ -82,48 +80,50 @@ QPainterPath MixerNode::shape() const void MixerNode::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *) { - QString text = cmdNode ? cmdText : QString().sprintf("%.2f", value()); + QString text = QString().sprintf("%.2f", value()); painter->setFont(graph->font()); if (drawNode) { QRadialGradient gradient(-3, -3, 10); + + QColor color; + if (value() < 0) { + color = negativeColor; + } + else if (value() == 0) { + color = neutralColor; + } + else { + color = positiveColor; + } + if (option->state & QStyle::State_Sunken) { gradient.setCenter(3, 3); gradient.setFocalPoint(3, 3); - gradient.setColorAt(1, Qt::darkBlue); - gradient.setColorAt(0, Qt::darkBlue); + QColor selColor = color.darker(); + gradient.setColorAt(1, selColor.darker()); + gradient.setColorAt(0, selColor); } 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); - } - else { - gradient.setColorAt(0, posColor0); - gradient.setColorAt(1, posColor1); - } - } + gradient.setColorAt(0, graph->isEnabled() ? color : disabledColor); + gradient.setColorAt(1, graph->isEnabled() ? color.darker() : disabledColor); } painter->setBrush(gradient); - painter->setPen(QPen(Qt::black, 0)); + painter->setPen(graph->isEnabled() ? QPen(Qt::black, 0) : QPen(disabledTextColor)); painter->drawEllipse(boundingRect()); - if (!image.isNull()) - painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image); + if (!image.isNull()) { + painter->drawImage(boundingRect().adjusted(1, 1, -1, -1), image); + } } if (drawText) { - painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); - if (cmdNode) { - painter->drawText(0,4,text); - } - else { - painter->drawText( (value() < 0) ? -13 : -11, 4, text); + if(graph->isEnabled()) { + painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); + } else { + painter->setPen(QPen(disabledTextColor)); } + + painter->drawText( (value() < 0) ? -10 : -8, 3, text); } } @@ -131,13 +131,6 @@ void MixerNode::verticalMove(bool flag){ vertical = flag; } -void MixerNode::commandNode(bool enable){ - cmdNode = enable; -} -void MixerNode::commandText(QString text){ - cmdText = text; -} - double MixerNode::value() { double h = graph->sceneRect().height(); double ratio = (h - pos().y()) / h; @@ -186,10 +179,6 @@ QVariant MixerNode::itemChange(GraphicsItemChange change, const QVariant &val) void MixerNode::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 3c4b0cc5d..edf00594a 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -50,22 +50,10 @@ public: enum { Type = UserType + 10 }; 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; } - bool getCommandActive() { return cmdActive; } - void setCommandActive(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; } + void setPositiveColor(QColor color = "#609FF2") {positiveColor = color; } + void setNegativeColor(QColor color = "#EF5F5F") {negativeColor = color; } void setImage(QImage img) { image = img; } void setDrawNode(bool draw) { drawNode = draw; } void setDrawText(bool draw) { drawText = draw; } @@ -76,9 +64,6 @@ public: double value(); -signals: - void commandActivated(QString text); - protected: QVariant itemChange(GraphicsItemChange change, const QVariant &val); @@ -89,18 +74,16 @@ private: QList edgeList; QPointF newPos; MixerCurveWidget* graph; - QString posColor0; - QString posColor1; - QString negColor0; - QString negColor1; + + QColor positiveColor; + QColor neutralColor; + QColor negativeColor; + QColor disabledColor; + QColor disabledTextColor; + QImage image; bool vertical; - QString cmdName; - bool cmdActive; - 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 4c52d1afb..03e2be777 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -66,286 +66,42 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) plot = new QGraphicsSvgItem(); renderer->load(QString(":/uavobjectwidgetutils/images/curve-bg.svg")); plot->setSharedRenderer(renderer); - //plot->setElementId("map"); + scene->addItem(plot); plot->setZValue(-1); scene->setSceneRect(plot->boundingRect()); setScene(scene); - posColor0 = "#1c870b"; //greenish? - posColor1 = "#116703"; //greenish? - negColor0 = "#ff0000"; //red - negColor1 = "#ff0000"; //red - - // commmand nodes - // reset - MixerNode* node = getCommandNode(0); - node->setName("Reset"); - node->setToolTip("Reset Curve to Defaults"); - node->setToggle(false); - node->setPositiveColor("#ffffff", "#ffffff"); //white - node->setNegativeColor("#ffffff", "#ffffff"); - scene->addItem(node); - - // linear - node = getCommandNode(1); - node->setName("Linear"); - node->setToolTip("Generate a Linear Curve"); - 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"); - 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"); - 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"); - 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"); - img = QImage(":/core/images/curve_step.png"); - if (!img.isNull()) - node->setImage(img); - else - node->commandText("z"); - scene->addItem(node); - - - // curve min/max nodes - 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"); - 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"); - 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"); - 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"); - 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"); - 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"); - scene->addItem(node); - - node = getCommandNode(12); - node->setName("StepValue"); - node->setDrawNode(false); - node->setToolTip("Current Step/Power Value"); - node->setToggle(false); - node->setPositiveColor("#0000aa", "#0000aa"); //blue - 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); - - // popup - node = getCommandNode(14); - node->setName("Popup"); - node->setToolTip("Advanced Mode..."); - node->commandText(""); - node->setToggle(false); - node->setPositiveColor("#ff0000", "#ff0000"); //red - node->setNegativeColor("#ff0000", "#ff0000"); - scene->addItem(node); - - resizeCommands(); - initNodes(MixerCurveWidget::NODE_NUMELEM); - } MixerCurveWidget::~MixerCurveWidget() { - while (!nodePool.isEmpty()) - delete nodePool.takeFirst(); + while (!nodeList.isEmpty()) { + delete nodeList.takeFirst(); + } - while (!edgePool.isEmpty()) - delete edgePool.takeFirst(); - - while (!cmdNodePool.isEmpty()) - delete cmdNodePool.takeFirst(); + while (!edgeList.isEmpty()) { + delete edgeList.takeFirst(); + } } -MixerNode* MixerCurveWidget::getCommandNode(int index) +void MixerCurveWidget::setPositiveColor(QString color) { - MixerNode* node; - - if (index >= 0 && index < cmdNodePool.count()) - { - node = cmdNodePool.at(index); + for (int i=0; i < nodeList.count(); i++) { + MixerNode* node = nodeList.at(i); + node->setPositiveColor(color); } - else { - node = new MixerNode(this); - node->commandNode(true); - node->commandText(""); - node->setCommandIndex(index); - node->setActive(false); - node->setPositiveColor("#aaaa00", "#aaaa00"); - node->setNegativeColor("#1c870b", "#116703"); - cmdNodePool.append(node); - } - return node; - } -MixerNode* MixerCurveWidget::getNode(int index) +void MixerCurveWidget::setNegativeColor(QString color) { - MixerNode* node; - - if (index >= 0 && index < nodePool.count()) - { - node = nodePool.at(index); - } - else { - node = new MixerNode(this); - nodePool.append(node); - } - return node; -} -Edge* MixerCurveWidget::getEdge(int index, MixerNode* sourceNode, MixerNode* destNode) -{ - Edge* edge; - - if (index >= 0 && index < edgePool.count()) - { - edge = edgePool.at(index); - edge->setSourceNode(sourceNode); - edge->setDestNode(destNode); - } - else { - edge = new Edge(sourceNode,destNode); - edgePool.append(edge); - } - return edge; -} - -void MixerCurveWidget::setPositiveColor(QString color0, QString color1) -{ - posColor0 = color0; - posColor1 = color1; - for (int i=0; isetPositiveColor(color0, color1); + for (int i=0; i < nodeList.count(); i++) { + MixerNode* node = nodeList.at(i); + node->setNegativeColor(color); } } -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. @@ -370,9 +126,11 @@ void MixerCurveWidget::initNodes(int numPoints) foreach(Edge *edge, node->edges()) { if (edge->sourceNode() == node) { scene()->removeItem(edge); + delete edge; } } scene()->removeItem(node); + delete node; } nodeList.clear(); @@ -380,9 +138,9 @@ void MixerCurveWidget::initNodes(int numPoints) // Create the nodes and edges MixerNode* prevNode = 0; - for (int i=0; iaddItem(node); @@ -390,7 +148,7 @@ void MixerCurveWidget::initNodes(int numPoints) node->setPos(0,0); if (prevNode) { - scene()->addItem(getEdge(i, prevNode, node)); + scene()->addItem(new Edge(prevNode, node)); } prevNode = node; @@ -469,7 +227,6 @@ 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); } @@ -478,61 +235,17 @@ 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() +void MixerCurveWidget::changeEvent(QEvent *event) { - QRectF rect = plot->boundingRect(); - - MixerNode* 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) + 20, rect.height() + 10); - - //commands on/off - node = getCommandNode(13); - node->setPos(rect.right() - 15, rect.bottomRight().x() - 14); - - for (int i = 1; i<6; i++) { - node = getCommandNode(i); - - //bottom right of widget - node->setPos(rect.right() - 130 + (i * 18), rect.bottomRight().x() - 14); + QGraphicsView::changeEvent(event); + if(event->type() == QEvent::EnabledChange) { + foreach (MixerNode *node, nodeList) { + node->update(); + } } - - //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() - 40, rect.bottomRight().y() + 5); - - //stepminus - node = getCommandNode(11); - node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 15); - - //step - node = getCommandNode(12); - node->setPos(rect.bottomRight().x() - 22, rect.bottomRight().y() + 9); } void MixerCurveWidget::itemMoved(double itemValue) @@ -575,87 +288,3 @@ double MixerCurveWidget::setRange(double min, double max) return curveMax - curveMin; } -MixerNode* MixerCurveWidget::getCmdNode(const QString& name) -{ - MixerNode* 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=1; isetCommandActive(node->getName() == name); - node->update(); - } -} - -void MixerCurveWidget::showCommand(const QString& name, bool show) -{ - MixerNode* node = getCmdNode(name); - if (node) { - if (show) - node->show(); - else - node->hide(); - } -} -void MixerCurveWidget::showCommands(bool show) -{ - for (int i=1; ishow(); - else - node->hide(); - - node->update(); - } -} -bool MixerCurveWidget::isCommandActive(const QString& name) -{ - bool active = false; - MixerNode* node = getCmdNode(name); - if (node) { - active = node->getCommandActive(); - } - return active; -} - -void MixerCurveWidget::cmdActivated(MixerNode* node) -{ - if (node->getToggle()) { - if (node->getName() == "Commands") { - node->setCommandActive(!node->getCommandActive()); - showCommands(node->getCommandActive()); - } - else { - for (int i=1; isetCommandActive(false); - n->update(); - } - - node->setCommandActive(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 d9469ba58..26df6a51e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -58,54 +58,35 @@ public: double getMax(); double setRange(double min, double max); - - void cmdActivated(MixerNode* node); - void activateCommand(const QString& name); - bool isCommandActive(const QString& name); - void showCommand(const QString& name, bool show); - void showCommands(bool show); - MixerNode* 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(MixerNode* node); private slots: private: QGraphicsSvgItem *plot; - QList nodePool; - QList cmdNodePool; - QList edgePool; + QList edgeList; QList nodeList; double curveMin; double curveMax; bool curveUpdating; - QString posColor0; - QString posColor1; - QString negColor0; - QString negColor1; - void initNodes(int numPoints); - MixerNode* getNode(int index); - MixerNode* getCommandNode(int index); - Edge* getEdge(int index, MixerNode* sourceNode, MixerNode* destNode); - void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00"); - void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000"); + void setPositiveColor(QString color); + void setNegativeColor(QString color); void resizeCommands(); protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); + void changeEvent(QEvent *event); }; From 175888526636150fdb4d48715d56c04465ac08ab Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sat, 4 May 2013 09:53:42 +0200 Subject: [PATCH 10/39] OP-935 Updated stylesheet. --- .../openpilotgcs/share/openpilotgcs/stylesheets/default.qss | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss index 3d2c71f2a..873b2f7de 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default.qss @@ -24,7 +24,7 @@ QSlider::add-page:horizontal { } QSlider::add-page:horizontal:disabled { - background: #ccc; + background: #eee; border: 1px solid #999; width: 1px; border-radius: 4px; @@ -38,7 +38,7 @@ QSlider::sub-page:horizontal { } QSlider::sub-page:horizontal:disabled { - background: #eee; + background: #ccc; border: 1px solid #999; width: 1px; border-radius: 4px; From 1e5ce7a5fb61b7a7857c91f7be786994f141e2ea Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 4 May 2013 16:34:11 +0200 Subject: [PATCH 11/39] OP-938 Add programmable EXP and max full throttle climb/descent rate --- flight/modules/ManualControl/manualcontrol.c | 16 +++++++++++----- .../uavobjectdefinition/altitudeholdsettings.xml | 2 ++ 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index ad7c25ada..b598f6f2b 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -50,6 +50,7 @@ #include "stabilizationdesired.h" #include "receiveractivity.h" #include "systemsettings.h" +#include #if defined(PIOS_INCLUDE_USB_RCTX) #include "pios_usb_rctx.h" @@ -796,15 +797,20 @@ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) const float DEADBAND_LOW = 1.0f / 2 - DEADBAND / 2; // this is the max speed in m/s at the extents of throttle - const float MAX_ALT_CHANGE_RATE = 5; + uint8_t throttleRate; + uint8_t throttleExp; + static portTickType lastSysTime; static bool zeroed = false; portTickType thisSysTime; float dT; - AltitudeHoldDesiredData altitudeHoldDesired; + AltitudeHoldDesiredData altitudeHoldDesired; AltitudeHoldDesiredGet(&altitudeHoldDesired); + AltitudeHoldSettingsThrottleExpGet(&throttleExp); + AltitudeHoldSettingsThrottleRateGet(&throttleRate); + StabilizationSettingsData stabSettings; StabilizationSettingsGet(&stabSettings); @@ -824,10 +830,10 @@ static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed) zeroed = false; } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { // being the two band simmetrical I can divide by DEADBAND_LOW to scale it to a value betweeon 0 and 1 - // then apply an "exp" - altitudeHoldDesired.Altitude += powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) * MAX_ALT_CHANGE_RATE * dT; + // then apply an "exp" f(x,k) = (k∙x∙x∙x + x∙(256−k)) / 256 + altitudeHoldDesired.Altitude += (throttleExp * powf((cmd->Throttle - DEADBAND_HIGH) / (DEADBAND_LOW), 3) + (256 - throttleExp)) / 256 * throttleRate * dT; } else if (cmd->Throttle < DEADBAND_LOW && zeroed) { - altitudeHoldDesired.Altitude += powf(((cmd->Throttle < 0 ? 0 : cmd->Throttle) - DEADBAND_LOW) / (DEADBAND_LOW), 3) * MAX_ALT_CHANGE_RATE * dT; + altitudeHoldDesired.Altitude -= (throttleExp * powf((DEADBAND_LOW - (cmd->Throttle < 0 ? 0 : cmd->Throttle)) / DEADBAND_LOW, 3) + (256 - throttleExp)) / 256 * throttleRate * dT; } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) { // Require the stick to enter the dead band before they can move height zeroed = true; diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml index 9b805458b..25c75aca3 100644 --- a/shared/uavobjectdefinition/altitudeholdsettings.xml +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -8,6 +8,8 @@ + + From 176bd3c4f79a76e75eac39e97d4ea49ad93a6b98 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 5 May 2013 12:45:35 +0200 Subject: [PATCH 12/39] OP-935 Adds Responsiveness sliders to basic stabilization screen. --- .../stylesheets/default_windows.qss | 17 - .../src/plugins/config/configgadgetwidget.cpp | 100 +- .../config/configstabilizationwidget.cpp | 151 +- .../config/configstabilizationwidget.h | 8 +- .../src/plugins/config/configtxpidwidget.cpp | 27 - .../src/plugins/config/configtxpidwidget.h | 1 - .../src/plugins/config/inputchannelform.cpp | 73 +- .../src/plugins/config/mixercurve.cpp | 191 +- .../src/plugins/config/stabilization.ui | 4713 ++++++++++++----- .../uavobjectwidgetutils/configtaskwidget.cpp | 1271 ++--- .../uavobjectwidgetutils/configtaskwidget.h | 124 +- .../uavobjectwidgetutils/mixercurvepoint.h | 68 +- .../uavobjectwidgetutils/mixercurvewidget.h | 55 +- .../uavobjectwidgetutils/popupwidget.h | 35 +- .../uavobjectwidgetutils/smartsavebutton.h | 23 +- 15 files changed, 4408 insertions(+), 2449 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss index e378375c0..e426d3f2c 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss @@ -1,18 +1 @@ /* Windows styles */ - -QGroupBox { - border: 1px solid gray; - border-radius: 3px; - margin-top: 1ex; - padding: 1ex 0px 0px 0px; - font-size: 11px; - font-weight: bold; -} - -QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top left; - left: 7px; - top: -1ex; - padding: 0px 3px; -} diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index a79aa3cfa..74dfea483 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -67,49 +67,49 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultHwSettingsWidget(this); + qwd = new DefaultHwSettingsWidget(this); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); icon = new QIcon(); icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigVehicleTypeWidget(this); + qwd = new ConfigVehicleTypeWidget(this); ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle")); icon = new QIcon(); icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigInputWidget(this); + qwd = new ConfigInputWidget(this); ftw->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input")); icon = new QIcon(); icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigOutputWidget(this); + qwd = new ConfigOutputWidget(this); ftw->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output")); icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultAttitudeWidget(this); + qwd = new DefaultAttitudeWidget(this); ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); icon = new QIcon(); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigStabilizationWidget(this); + qwd = new ConfigStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization")); icon = new QIcon(); icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigCameraStabilizationWidget(this); + qwd = new ConfigCameraStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab")); icon = new QIcon(); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigTxPIDWidget(this); + qwd = new ConfigTxPIDWidget(this); ftw->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); @@ -117,29 +117,29 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) // Listen to autopilot connection events ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - TelemetryManager* telMngr = pm->getObject(); + TelemetryManager *telMngr = pm->getObject(); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); // And check whether by any chance we are not already connected if (telMngr->isConnected()) { - onAutopilotConnect(); + onAutopilotConnect(); } help = 0; - connect(ftw,SIGNAL(currentAboutToShow(int,bool*)), this, SLOT(tabAboutToChange(int,bool*))); + connect(ftw, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *))); // Connect to the PipXStatus object updates UAVObjectManager *objManager = pm->getObject(); - oplinkStatusObj = dynamic_cast(objManager->getObject("OPLinkStatus")); - if (oplinkStatusObj != NULL ) { - connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateOPLinkStatus(UAVObject*))); + oplinkStatusObj = dynamic_cast(objManager->getObject("OPLinkStatus")); + if (oplinkStatusObj != NULL) { + connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateOPLinkStatus(UAVObject *))); } else { - qDebug() << "Error: Object is unknown (OPLinkStatus)."; + qDebug() << "Error: Object is unknown (OPLinkStatus)."; } // Create the timer that is used to timeout the connection to the OPLink. - oplinkTimeout = new QTimer(this); + oplinkTimeout = new QTimer(this); connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect())); oplinkConnected = false; } @@ -152,7 +152,7 @@ ConfigGadgetWidget::~ConfigGadgetWidget() void ConfigGadgetWidget::startInputWizard() { ftw->setCurrentIndex(ConfigGadgetWidget::input); - ConfigInputWidget* inputWidget = dynamic_cast(ftw->getWidget(ConfigGadgetWidget::input)); + ConfigInputWidget *inputWidget = dynamic_cast(ftw->getWidget(ConfigGadgetWidget::input)); Q_ASSERT(inputWidget); inputWidget->startInputWizard(); } @@ -162,11 +162,12 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) QWidget::resizeEvent(event); } -void ConfigGadgetWidget::onAutopilotDisconnect() { - +void ConfigGadgetWidget::onAutopilotDisconnect() +{ int selectedIndex = ftw->currentIndex(); QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new DefaultAttitudeWidget(this); @@ -176,7 +177,7 @@ void ConfigGadgetWidget::onAutopilotDisconnect() { icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new DefaultHwSettingsWidget(this); + qwd = new DefaultHwSettingsWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); @@ -185,20 +186,20 @@ void ConfigGadgetWidget::onAutopilotDisconnect() { emit autopilotDisconnected(); } -void ConfigGadgetWidget::onAutopilotConnect() { - - qDebug()<<"ConfigGadgetWidget onAutopilotConnect"; +void ConfigGadgetWidget::onAutopilotConnect() +{ + qDebug() << "ConfigGadgetWidget onAutopilotConnect"; // First of all, check what Board type we are talking to, and // if necessary, remove/add tabs in the config gadget: ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager* utilMngr = pm->getObject(); + UAVObjectUtilManager *utilMngr = pm->getObject(); if (utilMngr) { int selectedIndex = ftw->currentIndex(); int board = utilMngr->getBoardModel(); if ((board & 0xff00) == 1024) { // CopterControl family - QIcon *icon = new QIcon(); + QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigCCAttitudeWidget(this); @@ -208,14 +209,13 @@ void ConfigGadgetWidget::onAutopilotConnect() { icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigCCHWWidget(this); + qwd = new ConfigCCHWWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); - } else if ((board & 0xff00) == 0x0900) { // Revolution family - QIcon *icon = new QIcon(); + QIcon *icon = new QIcon(); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigRevoWidget(this); @@ -225,35 +225,33 @@ void ConfigGadgetWidget::onAutopilotConnect() { icon = new QIcon(); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); - qwd = new ConfigRevoHWWidget(this); + qwd = new ConfigRevoHWWidget(this); ftw->removeTab(ConfigGadgetWidget::hardware); ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); - } else { - //Unknown board + // Unknown board qDebug() << "Unknown board " << board; } - ftw->setCurrentIndex(selectedIndex); + ftw->setCurrentIndex(selectedIndex); } emit autopilotConnected(); } -void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed) +void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed) { Q_UNUSED(i); *proceed = true; - ConfigTaskWidget * wid = qobject_cast(ftw->currentWidget()); - if(!wid) { + ConfigTaskWidget *wid = qobject_cast(ftw->currentWidget()); + if (!wid) { return; } - if(wid->isDirty()) - { - int ans=QMessageBox::warning(this,tr("Unsaved changes"),tr("The tab you are leaving has unsaved changes," - "if you proceed they will be lost." - "Do you still want to proceed?"),QMessageBox::Yes,QMessageBox::No); - if(ans==QMessageBox::No) { - *proceed=false; + if (wid->isDirty()) { + int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes," + "if you proceed they will be lost." + "Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No); + if (ans == QMessageBox::No) { + *proceed = false; } else { wid->setDirty(false); } @@ -261,14 +259,13 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed) } /*! - \brief Called by updates to @OPLinkStatus - */ + \brief Called by updates to @OPLinkStatus + */ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *) { // Restart the disconnection timer. oplinkTimeout->start(5000); - if (!oplinkConnected) - { + if (!oplinkConnected) { qDebug() << "ConfigGadgetWidget onOPLinkConnect"; QIcon *icon = new QIcon(); @@ -281,9 +278,10 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *) } } -void ConfigGadgetWidget::onOPLinkDisconnect() { - qDebug()<<"ConfigGadgetWidget onOPLinkDisconnect"; - oplinkTimeout->stop(); - ftw->removeTab(ConfigGadgetWidget::oplink); - oplinkConnected = false; +void ConfigGadgetWidget::onOPLinkDisconnect() +{ + qDebug() << "ConfigGadgetWidget onOPLinkDisconnect"; + oplinkTimeout->stop(); + ftw->removeTab(ConfigGadgetWidget::oplink); + oplinkConnected = false; } diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index bab5640f6..bf390b175 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -45,9 +45,10 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa ui->setupUi(this); - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - Core::Internal::GeneralSettings* settings = pm->getObject(); - if(!settings->useExpertMode()) { + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings *settings = pm->getObject(); + + if (!settings->useExpertMode()) { ui->saveStabilizationToRAM_6->setVisible(false); } @@ -56,18 +57,18 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa realtimeUpdates = new QTimer(this); connect(realtimeUpdates, SIGNAL(timeout()), this, SLOT(apply())); - connect(ui->realTimeUpdates_6, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + connect(ui->realTimeUpdates_6, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); addWidget(ui->realTimeUpdates_6); - connect(ui->realTimeUpdates_8, SIGNAL(stateChanged(int)), this, SLOT(realtimeUpdatesSlot(int))); + connect(ui->realTimeUpdates_8, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); addWidget(ui->realTimeUpdates_8); - connect(ui->checkBox_7, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(ui->checkBox_7, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); addWidget(ui->checkBox_7); - connect(ui->checkBox_2, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(ui->checkBox_2, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); addWidget(ui->checkBox_2); - connect(ui->checkBox_8, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(ui->checkBox_8, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); addWidget(ui->checkBox_8); - connect(ui->checkBox_3, SIGNAL(stateChanged(int)), this, SLOT(linkCheckBoxes(int))); + connect(ui->checkBox_3, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); addWidget(ui->checkBox_3); addWidget(ui->pushButton_2); @@ -80,7 +81,12 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa addWidget(ui->pushButton_22); addWidget(ui->pushButton_23); - connect(this, SIGNAL(widgetContentsChanged(QWidget*)), this, SLOT(processLinkedWidgets(QWidget*))); + addWidget(ui->basicResponsivenessGroupBox); + connect(ui->basicResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + addWidget(ui->advancedResponsivenessGroupBox); + connect(ui->advancedResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); + + connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *))); // Link by default ui->checkBox_7->setChecked(true); @@ -95,100 +101,91 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() // Do nothing } -void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) -{ - ui->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - ui->realTimeUpdates_8->setCheckState((Qt::CheckState)value); - if(value == Qt::Checked && !realtimeUpdates->isActive()) { +void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o) +{ + ConfigTaskWidget::refreshWidgetsValues(o); + + ui->basicResponsivenessGroupBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() && + ui->rateRollKi_3->value() == ui->ratePitchKi_4->value()); +} + +void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value) +{ + ui->realTimeUpdates_6->setChecked(value); + ui->realTimeUpdates_8->setChecked(value); + + if (value && !realtimeUpdates->isActive()) { realtimeUpdates->start(300); - } - else if(value == Qt::Unchecked) { + } else { realtimeUpdates->stop(); } } -void ConfigStabilizationWidget::linkCheckBoxes(int value) +void ConfigStabilizationWidget::linkCheckBoxes(bool value) { - if(sender() == ui->checkBox_7) { - ui->checkBox_3->setCheckState((Qt::CheckState)value); - } - else if(sender() == ui->checkBox_3) { - ui->checkBox_7->setCheckState((Qt::CheckState)value); - } - else if(sender( )== ui->checkBox_8) { - ui->checkBox_2->setCheckState((Qt::CheckState)value); - } - else if(sender() == ui->checkBox_2) { - ui->checkBox_8->setCheckState((Qt::CheckState)value); + if (sender() == ui->checkBox_7) { + ui->checkBox_3->setChecked(value); + } else if (sender() == ui->checkBox_3) { + ui->checkBox_7->setChecked(value); + } else if (sender() == ui->checkBox_8) { + ui->checkBox_2->setChecked(value); + } else if (sender() == ui->checkBox_2) { + ui->checkBox_8->setChecked(value); + } else if (sender() == ui->basicResponsivenessGroupBox) { + ui->advancedResponsivenessGroupBox->setChecked(!value); + if(value) { + processLinkedWidgets(ui->AttitudeResponsivenessSlider); + processLinkedWidgets(ui->RateResponsivenessSlider); + } + } else if (sender() == ui->advancedResponsivenessGroupBox) { + ui->basicResponsivenessGroupBox->setChecked(!value); } } -void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) +void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget) { - if(ui->checkBox_7->checkState()==Qt::Checked) - { - if(widget== ui->RateRollKp_2) - { + if (ui->checkBox_7->isChecked()) { + if (widget == ui->RateRollKp_2) { ui->RatePitchKp->setValue(ui->RateRollKp_2->value()); - } - else if(widget== ui->RateRollKi_2) - { + } else if (widget == ui->RateRollKi_2) { ui->RatePitchKi->setValue(ui->RateRollKi_2->value()); - } - else if(widget== ui->RateRollILimit_2) - { + } else if (widget == ui->RateRollILimit_2) { ui->RatePitchILimit->setValue(ui->RateRollILimit_2->value()); - } - else if(widget== ui->RatePitchKp) - { + } else if (widget == ui->RatePitchKp) { ui->RateRollKp_2->setValue(ui->RatePitchKp->value()); - } - else if(widget== ui->RatePitchKi) - { + } else if (widget == ui->RatePitchKi) { ui->RateRollKi_2->setValue(ui->RatePitchKi->value()); - } - else if(widget== ui->RatePitchILimit) - { + } else if (widget == ui->RatePitchILimit) { ui->RateRollILimit_2->setValue(ui->RatePitchILimit->value()); - } - else if(widget== ui->RollRateKd) - { + } else if (widget == ui->RollRateKd) { ui->PitchRateKd->setValue(ui->RollRateKd->value()); - } - else if(widget== ui->PitchRateKd) - { + } else if (widget == ui->PitchRateKd) { ui->RollRateKd->setValue(ui->PitchRateKd->value()); } } - if(ui->checkBox_8->checkState()==Qt::Checked) - { - if(widget== ui->AttitudeRollKp) - { + + if (ui->checkBox_8->isChecked()) { + if (widget == ui->AttitudeRollKp) { ui->AttitudePitchKp_2->setValue(ui->AttitudeRollKp->value()); - } - else if(widget== ui->AttitudeRollKi) - { + } else if (widget == ui->AttitudeRollKi) { ui->AttitudePitchKi_2->setValue(ui->AttitudeRollKi->value()); - } - else if(widget== ui->AttitudeRollILimit) - { + } else if (widget == ui->AttitudeRollILimit) { ui->AttitudePitchILimit_2->setValue(ui->AttitudeRollILimit->value()); - } - else if(widget== ui->AttitudePitchKp_2) - { + } else if (widget == ui->AttitudePitchKp_2) { ui->AttitudeRollKp->setValue(ui->AttitudePitchKp_2->value()); - } - else if(widget== ui->AttitudePitchKi_2) - { + } else if (widget == ui->AttitudePitchKi_2) { ui->AttitudeRollKi->setValue(ui->AttitudePitchKi_2->value()); - } - else if(widget== ui->AttitudePitchILimit_2) - { + } else if (widget == ui->AttitudePitchILimit_2) { ui->AttitudeRollILimit->setValue(ui->AttitudePitchILimit_2->value()); } } + + if(ui->basicResponsivenessGroupBox->isChecked()) { + if (widget == ui->AttitudeResponsivenessSlider) { + ui->ratePitchKp_4->setValue(ui->AttitudeResponsivenessSlider->value()); + } else if (widget == ui->RateResponsivenessSlider) { + ui->ratePitchKi_4->setValue(ui->RateResponsivenessSlider->value()); + } + } } - - - diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 1cf4f51ed..8be034790 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -48,9 +48,13 @@ public: private: Ui_StabilizationWidget *ui; QTimer * realtimeUpdates; + +protected slots: + void refreshWidgetsValues(UAVObject *o = NULL); + private slots: - void realtimeUpdatesSlot(int); - void linkCheckBoxes(int value); + void realtimeUpdatesSlot(bool value); + void linkCheckBoxes(bool value); void processLinkedWidgets(QWidget*); }; diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 7eb91becc..b279135bb 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -108,30 +108,3 @@ void ConfigTxPIDWidget::saveSettings() UAVObject *obj = HwSettings::GetInstance(getObjectManager()); saveObjectToSD(obj); } - -void ConfigTxPIDWidget::enableControls(bool enable) -{ - /* - m_txpid->PID1->setEnabled(enable); - m_txpid->PID2->setEnabled(enable); - m_txpid->PID3->setEnabled(enable); - - m_txpid->Input1->setEnabled(enable); - m_txpid->Input2->setEnabled(enable); - m_txpid->Input3->setEnabled(enable); - - m_txpid->MinPID1->setEnabled(enable); - m_txpid->MinPID2->setEnabled(enable); - m_txpid->MinPID3->setEnabled(enable); - - m_txpid->MaxPID1->setEnabled(enable); - m_txpid->MaxPID2->setEnabled(enable); - m_txpid->MaxPID3->setEnabled(enable); - - m_txpid->ThrottleMin->setEnabled(enable); - m_txpid->ThrottleMax->setEnabled(enable); - - m_txpid->UpdateMode->setEnabled(enable); - */ - ConfigTaskWidget::setEnabled(enable); -} diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h index 311a62372..14eb5925d 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.h @@ -44,7 +44,6 @@ private slots: void refreshValues(); void applySettings(); void saveSettings(); - void enableControls(bool enable); }; #endif // CONFIGTXPIDWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index d94281035..0a573adce 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -4,15 +4,14 @@ #include "manualcontrolsettings.h" #include "gcsreceiver.h" -inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : +inputChannelForm::inputChannelForm(QWidget *parent, bool showlegend) : ConfigTaskWidget(parent), ui(new Ui::inputChannelForm) { ui->setupUi(this); - - //The first time through the loop, keep the legend. All other times, delete it. - if(!showlegend) - { + + // 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); @@ -27,19 +26,18 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : delete ui->legend4; delete ui->legend5; delete ui->legend6; - } - connect(ui->channelMin,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); - connect(ui->channelMax,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); - connect(ui->channelGroup,SIGNAL(currentIndexChanged(int)),this,SLOT(groupUpdated())); - connect(ui->channelNeutral,SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated(int))); + connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); + connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); + connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated())); + connect(ui->channelNeutral, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated(int))); // This is awkward but since we want the UI to be a dropdown but the field is not an enum // it breaks the UAUVObject widget relation of the task gadget. Running the data through // a spin box fixes this - connect(ui->channelNumberDropdown,SIGNAL(currentIndexChanged(int)),this,SLOT(channelDropdownUpdated(int))); - connect(ui->channelNumber,SIGNAL(valueChanged(int)),this,SLOT(channelNumberUpdated(int))); + connect(ui->channelNumberDropdown, SIGNAL(currentIndexChanged(int)), this, SLOT(channelDropdownUpdated(int))); + connect(ui->channelNumber, SIGNAL(valueChanged(int)), this, SLOT(channelNumberUpdated(int))); disableMouseWheelEvents(); } @@ -54,26 +52,28 @@ void inputChannelForm::setName(QString &name) { ui->channelName->setText(name); QFontMetrics metrics(ui->channelName->font()); - int width=metrics.width(name)+5; - foreach(inputChannelForm * form,parent()->findChildren()) - { - if(form==this) + int width = metrics.width(name) + 5; + foreach(inputChannelForm * form, parent()->findChildren()) { + if (form == this) { continue; - if(form->ui->channelName->minimumSize().width()ui->channelName->setMinimumSize(width,0); - else - width=form->ui->channelName->minimumSize().width(); + } + if (form->ui->channelName->minimumSize().width() < width) { + form->ui->channelName->setMinimumSize(width, 0); + } else { + width = form->ui->channelName->minimumSize().width(); + } } - ui->channelName->setMinimumSize(width,0); + ui->channelName->setMinimumSize(width, 0); } /** - * Update the direction of the slider and boundaries - */ + * Update the direction of the slider and boundaries + */ void inputChannelForm::minMaxUpdated() { bool reverse = ui->channelMin->value() > ui->channelMax->value(); - if(reverse) { + + if (reverse) { ui->channelNeutral->setMinimum(ui->channelMax->value()); ui->channelNeutral->setMaximum(ui->channelMin->value()); } else { @@ -91,11 +91,11 @@ void inputChannelForm::neutralUpdated(int newval) } /** - * Update the channel options based on the selected receiver type - * - * I fully admit this is terrible practice to embed data within UI - * like this. Open to suggestions. JC 2011-09-07 - */ + * Update the channel options based on the selected receiver type + * + * I fully admit this is terrible practice to embed data within UI + * like this. Open to suggestions. JC 2011-09-07 + */ void inputChannelForm::groupUpdated() { ui->channelNumberDropdown->clear(); @@ -103,7 +103,7 @@ void inputChannelForm::groupUpdated() quint8 count = 0; - switch(ui->channelGroup->currentIndex()) { + switch (ui->channelGroup->currentIndex()) { case -1: // Nothing selected count = 0; break; @@ -129,24 +129,25 @@ void inputChannelForm::groupUpdated() Q_ASSERT(0); } - for (int i = 0; i < count; i++) - ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i+1))); + for (int i = 0; i < count; i++) { + ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1))); + } ui->channelNumber->setMaximum(count); ui->channelNumber->setMinimum(0); } /** - * Update the dropdown from the hidden control - */ + * Update the dropdown from the hidden control + */ void inputChannelForm::channelDropdownUpdated(int newval) { ui->channelNumber->setValue(newval); } /** - * Update the hidden control from the dropdown - */ + * Update the hidden control from the dropdown + */ void inputChannelForm::channelNumberUpdated(int newval) { ui->channelNumberDropdown->setCurrentIndex(newval); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 3b45d7df5..17e9c48cd 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -38,7 +38,7 @@ MixerCurve::MixerCurve(QWidget *parent) : m_mixerUI->setupUi(this); // setup some convienence pointers - m_curve = m_mixerUI->CurveWidget; + m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; @@ -56,10 +56,10 @@ MixerCurve::MixerCurve(QWidget *parent) : // 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->PopupCurve, SIGNAL(clicked()),this,SLOT(PopupCurve())); + 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_settings, SIGNAL(cellChanged(int,int)), 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())); @@ -79,26 +79,26 @@ void MixerCurve::setMixerType(MixerCurveType curveType) m_mixerUI->CurveMax->setMaximum(1.0); switch (m_curveType) { - case MixerCurve::MIXERCURVE_THROTTLE: - { - 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); - break; - } - case MixerCurve::MIXERCURVE_PITCH: - { - 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); - break; - } + case MixerCurve::MIXERCURVE_THROTTLE: + { + 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); + break; + } + case MixerCurve::MIXERCURVE_PITCH: + { + 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); + break; + } } m_spinDelegate->setRange(m_mixerUI->CurveMin->minimum(), m_mixerUI->CurveMax->maximum()); - for (int i=0; isetItemDelegateForRow(i, m_spinDelegate); } @@ -121,7 +121,7 @@ void MixerCurve::PopupCurve() m_mixerUI->SettingsGroup->show(); m_mixerUI->PopupCurve->hide(); - PopupWidget* popup = new PopupWidget(); + PopupWidget *popup = new PopupWidget(); popup->popUp(this); m_mixerUI->SettingsGroup->hide(); @@ -130,7 +130,7 @@ void MixerCurve::PopupCurve() void MixerCurve::UpdateCurveUI() { - //get the user settings + // get the user settings QString curveType = m_mixerUI->CurveType->currentText(); @@ -138,7 +138,7 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setMaximum(100.0); m_mixerUI->CurveStep->setSingleStep(1.00); - //set default visible + // set default visible m_mixerUI->minLabel->setVisible(true); m_mixerUI->CurveMin->setVisible(true); m_mixerUI->maxLabel->setVisible(false); @@ -146,8 +146,7 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->stepLabel->setVisible(false); m_mixerUI->CurveStep->setVisible(false); - if ( curveType.compare("Flat")==0) - { + if (curveType.compare("Flat") == 0) { m_mixerUI->minLabel->setVisible(false); m_mixerUI->CurveMin->setVisible(false); m_mixerUI->stepLabel->setVisible(true); @@ -157,13 +156,11 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setSingleStep(0.01); m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2); } - if ( curveType.compare("Linear")==0) - { + if (curveType.compare("Linear") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); } - if ( curveType.compare("Step")==0) - { + if (curveType.compare("Step") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Step at"); @@ -172,8 +169,7 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setMinimum(1.0); } - if ( curveType.compare("Exp")==0) - { + if (curveType.compare("Exp") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Power"); @@ -182,13 +178,12 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setMinimum(1.0); } - if ( curveType.compare("Log")==0) - { + if (curveType.compare("Log") == 0) { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setVisible(true); - m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); m_mixerUI->CurveStep->setMinimum(1.0); } @@ -197,61 +192,52 @@ void MixerCurve::UpdateCurveUI() void MixerCurve::GenerateCurve() { - double scale; - double newValue; + double scale; + double newValue; - //get the user settings - double value1 = getCurveMin(); - double value2 = getCurveMax(); - double value3 = getCurveStep(); + // get the user settings + double value1 = getCurveMin(); + double value2 = getCurveMax(); + double value3 = getCurveStep(); - QString CurveType = m_mixerUI->CurveType->currentText(); + QString CurveType = m_mixerUI->CurveType->currentText(); - QList points; + QList points; - for (int i=0; i* points) + Wrappers for mixercurvewidget. + */ +void MixerCurve::initCurve(const QList *points) { m_curve->setCurve(points); UpdateSettingsTable(); @@ -269,11 +255,12 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue m_curve->initLinearCurve(numPoints, maxValue, minValue); - if (m_spinDelegate) + if (m_spinDelegate) { m_spinDelegate->setRange(minValue, maxValue); + } } -void MixerCurve::setCurve(const QList* points) +void MixerCurve::setCurve(const QList *points) { m_curve->setCurve(points); UpdateSettingsTable(); @@ -281,7 +268,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); } @@ -292,7 +279,7 @@ double MixerCurve::getMin() void MixerCurve::setMax(double value) { - //m_curve->setMax(value); + // m_curve->setMax(value); m_mixerUI->CurveMax->setMaximum(value); } @@ -326,11 +313,11 @@ void MixerCurve::UpdateSettingsTable() QList points = m_curve->getCurve(); int ptCnt = points.count(); - for (int i=0; iitem(i, 0); - if (item) - item->setText(QString().sprintf("%.2f",points.at( (ptCnt - 1) - i ))); + for (int i = 0; i < ptCnt; i++) { + QTableWidgetItem *item = m_settings->item(i, 0); + if (item) { + item->setText(QString().sprintf("%.2f", points.at((ptCnt - 1) - i))); + } } } @@ -338,12 +325,12 @@ void MixerCurve::SettingsTableChanged() { QList points; - for (int i=0; i < m_settings->rowCount(); i++) - { - QTableWidgetItem* item = m_settings->item(i, 0); + for (int i = 0; i < m_settings->rowCount(); i++) { + QTableWidgetItem *item = m_settings->item(i, 0); - if (item) + if (item) { points.push_front(item->text().toDouble()); + } } m_mixerUI->CurveMin->setValue(points.first()); @@ -369,7 +356,7 @@ void MixerCurve::CurveMinChanged(double value) void MixerCurve::CurveMaxChanged(double value) { // the max changed so redraw the curve - // mixercurvewidget::setCurve will trim any points above max + // mixercurvewidget::setCurve will trim any points above max QList points = m_curve->getCurve(); points.removeLast(); points.append(value); @@ -381,23 +368,25 @@ void MixerCurve::showEvent(QShowEvent *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())); - int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); - for (int i=0; irowCount(); i++) + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i = 0; i < m_settings->rowCount(); i++) { m_settings->setRowHeight(i, h); + } m_curve->showEvent(event); } -void MixerCurve::resizeEvent(QResizeEvent* event) +void MixerCurve::resizeEvent(QResizeEvent *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())); - int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); - for (int i=0; irowCount(); i++) + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i = 0; i < m_settings->rowCount(); i++) { m_settings->setRowHeight(i, h); + } m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index d1110d6fd..cedace74a 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,7 +6,7 @@ 0 0 - 1076 + 1075 834 @@ -589,6 +589,9 @@ QFrame::NoFrame + + QFrame::Sunken + 0 @@ -600,11 +603,2023 @@ 0 0 - 1046 + 1045 751 + + + 0 + 0 + + + + 9 + + + 9 + + + + + + + + Responsiveness + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + true + + + + 12 + + + + + + 0 + 0 + + + + Default + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QGroupBox{border: 0px;} + + + + + + true + + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + + + 14 + 200 + 14 + + + + + 6 + 150 + 6 + + + + + + + + + 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(14, 200, 14, 255), stop:0.78607 rgba(6, 150, 6 , 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Snappy + + + Qt::AlignCenter + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 10 + + + 500 + + + 150 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + 100 + + + 800 + + + 450 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 100 + + + 800 + + + 300 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + + + 34 + 34 + 200 + + + + + 6 + 6 + 150 + + + + + + + + + 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(34, 34, 200, 255), stop:0.78607 rgba(6, 6, 150, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Moderate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + + + 200 + 14 + 14 + + + + + 160 + 6 + 6 + + + + + + + + + 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(200, 14, 14, 255), stop:0.78607 rgba(160 , 6, 6 , 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Insane + + + Qt::AlignCenter + + + + + + + + 78 + 16 + + + + Attitude mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 78 + 16 + + + + Rate mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 10 + + + 500 + + + 1 + + + 255 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + 100 + + + 800 + + + 450 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 78 + 16 + + + + Rate mode yaw + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + 100 + + + 800 + + + 300 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + + @@ -1157,7 +3172,7 @@ false - + QGroupBox{border: 0px;} @@ -1166,569 +3181,15 @@ 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 - - - + + 0 + + + 0 + + + 0 + @@ -1742,555 +3203,18 @@ border-radius: 5; - - - - - 0 - 0 - + + + + Qt::Horizontal - + - 0 - 16 + 40 + 20 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 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 - - + @@ -2855,45 +3779,557 @@ border-radius: 5; - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + - + 0 0 - 78 + 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; - Proportional + Pitch - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + Qt::AlignCenter - + @@ -2947,7 +4383,7 @@ Then lower the value by 5 or so. - + @@ -2986,97 +4422,32 @@ Then lower the value by 5 or so. - - + + - + 0 0 - 0 - 25 + 78 + 16 - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 100 + + Proportional - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - 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 - - - - - + @@ -3127,7 +4498,97 @@ Then lower the value by 5 or so. - + + + + + 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 + + + + + @@ -3166,26 +4627,7 @@ Then lower the value by 5 or so. - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - + @@ -3236,7 +4678,26 @@ value as the Kp. - + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + @@ -3275,59 +4736,8 @@ value as the Kp. - - - - - 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 @@ -3356,7 +4766,7 @@ value as the Kp. objname:StabilizationSettings - fieldname:PitchRatePID + fieldname:YawRatePID element:Ki haslimits:yes scale:0.0001 @@ -3365,7 +4775,7 @@ value as the Kp. - + @@ -3416,8 +4826,59 @@ value as the Kp. - - + + + + + 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 @@ -3446,7 +4907,7 @@ value as the Kp. objname:StabilizationSettings - fieldname:YawRatePID + fieldname:PitchRatePID element:Ki haslimits:yes scale:0.0001 @@ -3455,6 +4916,569 @@ value as the Kp. + + + + + 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 + + + + @@ -4510,7 +6534,7 @@ value as the Kp. false - + QGroupBox{border: 0px;} @@ -4519,6 +6543,15 @@ value as the Kp. true + + 0 + + + 0 + + + 0 + @@ -6978,7 +9011,7 @@ border-radius: 5; 0 0 - 1046 + 1045 751 @@ -6986,8 +9019,11 @@ border-radius: 5; true + + 9 + - 12 + 9 @@ -7524,7 +9560,7 @@ border-radius: 5; - Rate Stabization Coefficients (Inner Loop) + Rate Stabilization Coefficients (Inner Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -8033,7 +10069,7 @@ border-radius: 5; false - + QGroupBox{border: 0px;} @@ -8045,8 +10081,11 @@ border-radius: 5; 0 + + 0 + - 9 + 0 @@ -10849,7 +12888,7 @@ Then lower the value by 20% or so. false - Attitude Stabization Coefficients (Outer Loop) + Attitude Stabilization Coefficients (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -11358,7 +13397,7 @@ Then lower the value by 20% or so. false - + QGroupBox{border: 0px;} @@ -11370,6 +13409,12 @@ Then lower the value by 20% or so. 0 + + 0 + + + 0 + @@ -13442,7 +15487,7 @@ border-radius: 5; - + 0 @@ -13976,11 +16021,17 @@ border-radius: 5; - Stick Range and Limits + Stick Responsiveness Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + true + + + false + 12 @@ -14475,7 +16526,7 @@ border-radius: 5; false - + QGroupBox{border: 0px;} @@ -14487,6 +16538,12 @@ border-radius: 5; 0 + + 0 + + + 0 + 0 @@ -15944,7 +18001,7 @@ border-radius: 5; - Full stick angle (deg) + Attitude mode response (deg) Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -16746,7 +18803,7 @@ border-radius: 5; - Full stick rate (deg/s) + Rate mode response (deg/s) Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -16901,13 +18958,16 @@ border-radius: 5; 0 0 - 1046 + 1045 751 + + 9 + - 12 + 9 @@ -16986,12 +19046,24 @@ border-radius: 5; + + QGroupBox{border: 0px;} + true - - 12 + + 0 + + + 9 + + + 0 + + + 0 @@ -19823,6 +21895,9 @@ border-radius: 5; + + QGroupBox{border: 0px;} + @@ -19830,8 +21905,17 @@ border-radius: 5; true - - 12 + + 0 + + + 9 + + + 0 + + + 0 @@ -22962,7 +25046,7 @@ border-radius: 5; false - + QGroupBox{border: 0px;} @@ -22971,8 +25055,17 @@ border-radius: 5; true - - 12 + + 0 + + + 9 + + + 0 + + + 0 diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 47ede15f8..0c4036091 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,44 +32,45 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),allowWidgetUpdates(true),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent), isConnected(false), allowWidgetUpdates(true), smartsave(NULL), dirty(false), outOfLimitsStyle("background-color: rgb(255, 0, 0);"), timeOut(NULL) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); - TelemetryManager* telMngr = pm->getObject(); - utilMngr = pm->getObject(); - connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()),Qt::UniqueConnection); - connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()),Qt::UniqueConnection); - UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); - connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects())); + TelemetryManager *telMngr = pm->getObject(); + utilMngr = pm->getObject(); + connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected()), Qt::UniqueConnection); + connect(telMngr, SIGNAL(disconnected()), this, SIGNAL(autoPilotDisconnected()), Qt::UniqueConnection); + UAVSettingsImportExportFactory *importexportplugin = pm->getObject(); + connect(importexportplugin, SIGNAL(importAboutToBegin()), this, SLOT(invalidateObjects())); } /** * Add a widget to the dirty detection pool * @param widget to add to the detection pool */ -void ConfigTaskWidget::addWidget(QWidget * widget) +void ConfigTaskWidget::addWidget(QWidget *widget) { - addUAVObjectToWidgetRelation("","",widget); + addUAVObjectToWidgetRelation("", "", widget); } /** * Add an object to the management system * @param objectName name of the object to add to the management system */ -void ConfigTaskWidget::addUAVObject(QString objectName,QList * reloadGroups) +void ConfigTaskWidget::addUAVObject(QString objectName, QList *reloadGroups) { - addUAVObjectToWidgetRelation(objectName,"",NULL,0,1,false,reloadGroups); + addUAVObjectToWidgetRelation(objectName, "", NULL, 0, 1, false, reloadGroups); } void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList *reloadGroups) { QString objstr; - if(objectName) - objstr=objectName->getName(); - addUAVObject(objstr, reloadGroups); + if (objectName) { + objstr = objectName->getName(); + } + addUAVObject(objstr, reloadGroups); } /** * Add an UAVObject field to widget relation to the management system @@ -78,25 +79,29 @@ void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList *reloadGro * @param widget pointer to the widget whitch will display/define the field value * @param index index of the field element to add to this relation */ -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index) { - UAVObject *obj=NULL; - UAVObjectField *_field=NULL; - obj = objManager->getObject(QString(object)); + UAVObject *obj = NULL; + UAVObjectField *_field = NULL; + + obj = objManager->getObject(QString(object)); Q_ASSERT(obj); _field = obj->getField(QString(field)); Q_ASSERT(_field); - addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index)); + addUAVObjectToWidgetRelation(object, field, widget, _field->getElementNames().indexOf(index)); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index); } /** @@ -112,38 +117,45 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectFie */ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { - UAVObject *obj=objManager->getObject(QString(object),instID); + UAVObject *obj = objManager->getObject(QString(object), instID); + Q_ASSERT(obj); UAVObjectField *_field; - int index=0; - if(!field.isEmpty() && obj) - { + int index = 0; + if (!field.isEmpty() && obj) { _field = obj->getField(QString(field)); - if(!element.isEmpty()) - index=_field->getElementNames().indexOf(QString(element)); + if (!element.isEmpty()) { + index = _field->getElementNames().indexOf(QString(element)); + } } - addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups,instID); + addUAVObjectToWidgetRelation(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID); } void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectField * field, QWidget * widget, int index,double scale,bool isLimited,QList* defaultReloadGroups, quint32 instID) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { QString objstr; QString fieldstr; - if(obj) - objstr=obj->getName(); - if(field) - fieldstr=field->getName(); - addUAVObjectToWidgetRelation(objstr,fieldstr,widget,index,scale,isLimited,defaultReloadGroups,instID); + + if (obj) { + objstr = obj->getName(); + } + if (field) { + fieldstr = field->getName(); + } + addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index, scale, isLimited, defaultReloadGroups, instID); } /** @@ -157,63 +169,55 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectFie * @param defaultReloadGroups default and reload groups this relation belongs to * @param instID instance ID of the object used on this relation */ -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,double scale,bool isLimited,QList* defaultReloadGroups, quint32 instID) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) { - if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups,instID)) + if (addShadowWidget(object, field, widget, index, scale, isLimited, defaultReloadGroups, instID)) { return; - - UAVObject *obj=NULL; - UAVObjectField *_field=NULL; - if(!object.isEmpty()) - { - obj = objManager->getObject(QString(object),instID); - Q_ASSERT(obj); - objectUpdates.insert(obj,true); - connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); } - if(!field.isEmpty() && obj) + + UAVObject *obj = NULL; + UAVObjectField *_field = NULL; + if (!object.isEmpty()) { + obj = objManager->getObject(QString(object), instID); + Q_ASSERT(obj); + objectUpdates.insert(obj, true); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(objectUpdated(UAVObject *))); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); + } + if (!field.isEmpty() && obj) { _field = obj->getField(QString(field)); - objectToWidget * ow=new objectToWidget(); - ow->field=_field; - ow->object=obj; - ow->widget=widget; - ow->index=index; - ow->scale=scale; - ow->isLimited=isLimited; + } + objectToWidget *ow = new objectToWidget(); + ow->field = _field; + ow->object = obj; + ow->widget = widget; + ow->index = index; + ow->scale = scale; + ow->isLimited = isLimited; objOfInterest.append(ow); - if(obj) - { - if(smartsave) - { - smartsave->addObject((UAVDataObject*)obj); + if (obj) { + if (smartsave) { + smartsave->addObject((UAVDataObject *)obj); } } - if(widget==NULL) - { - if(defaultReloadGroups && obj) - { - foreach(int i,*defaultReloadGroups) - { - if(this->defaultReloadGroups.contains(i)) - { + if (widget == NULL) { + if (defaultReloadGroups && obj) { + foreach(int i, *defaultReloadGroups) { + if (this->defaultReloadGroups.contains(i)) { this->defaultReloadGroups.value(i)->append(ow); - } - else - { - this->defaultReloadGroups.insert(i,new QList()); + } else { + this->defaultReloadGroups.insert(i, new QList()); this->defaultReloadGroups.value(i)->append(ow); } } } - } - else - { - connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged())); - if(defaultReloadGroups) - addWidgetToDefaultReloadGroups(widget,defaultReloadGroups); - shadowsList.insert(widget,ow); - loadWidgetLimits(widget,_field,index,isLimited,scale); + } else { + connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); + if (defaultReloadGroups) { + addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); + } + shadowsList.insert(widget, ow); + loadWidgetLimits(widget, _field, index, isLimited, scale); } } /** @@ -221,20 +225,20 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel */ ConfigTaskWidget::~ConfigTaskWidget() { - if(smartsave) + if (smartsave) { delete smartsave; - foreach(QList* pointer,defaultReloadGroups.values()) - { - if(pointer) + } + foreach(QList *pointer, defaultReloadGroups.values()) { + if (pointer) { delete pointer; + } } - foreach (objectToWidget* oTw, objOfInterest) - { - if(oTw) + foreach(objectToWidget * oTw, objOfInterest) { + if (oTw) { delete oTw; + } } - if(timeOut) - { + if (timeOut) { delete timeOut; timeOut = NULL; } @@ -245,7 +249,8 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) // saveObjectToSD is now handled by the UAVUtils plugin in one // central place (and one central queue) ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager* utilMngr = pm->getObject(); + UAVObjectUtilManager *utilMngr = pm->getObject(); + utilMngr->saveObjectToSD(obj); } @@ -253,9 +258,11 @@ void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) * Util function to get a pointer to the object manager * @return pointer to the UAVObjectManager */ -UAVObjectManager* ConfigTaskWidget::getObjectManager() { +UAVObjectManager *ConfigTaskWidget::getObjectManager() +{ ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager * objMngr = pm->getObject(); + UAVObjectManager *objMngr = pm->getObject(); + Q_ASSERT(objMngr); return objMngr; } @@ -267,8 +274,10 @@ UAVObjectManager* ConfigTaskWidget::getObjectManager() { double ConfigTaskWidget::listMean(QList list) { double accum = 0; - for(int i = 0; i < list.size(); i++) + + for (int i = 0; i < list.size(); i++) { accum += list[i]; + } return accum / list.size(); } @@ -280,15 +289,17 @@ double ConfigTaskWidget::listMean(QList list) double ConfigTaskWidget::listVar(QList list) { double mean_accum = 0; - double var_accum = 0; + double var_accum = 0; double mean; - for(int i = 0; i < list.size(); i++) + for (int i = 0; i < list.size(); i++) { mean_accum += list[i]; + } mean = mean_accum / list.size(); - for(int i = 0; i < list.size(); i++) + for (int i = 0; i < list.size(); i++) { var_accum += (list[i] - mean) * (list[i] - mean); + } // Use unbiased estimator return var_accum / (list.size() - 1); @@ -299,26 +310,26 @@ double ConfigTaskWidget::listVar(QList list) void ConfigTaskWidget::onAutopilotDisconnect() { - isConnected=false; + isConnected = false; enableControls(false); invalidateObjects(); } -void ConfigTaskWidget::forceConnectedState()//dynamic widgets don't recieve the connected signal. This should be called instead. +void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead. { - isConnected=true; + isConnected = true; setDirty(false); } void ConfigTaskWidget::onAutopilotConnect() { - if (utilMngr) - currentBoard = utilMngr->getBoardModel();//TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE + if (utilMngr) { + currentBoard = utilMngr->getBoardModel(); // TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE + } invalidateObjects(); - isConnected=true; - foreach(objectToWidget * ow,objOfInterest) - { - loadWidgetLimits(ow->widget,ow->field,ow->index,ow->isLimited,ow->scale); + isConnected = true; + foreach(objectToWidget * ow, objOfInterest) { + loadWidgetLimits(ow->widget, ow->field, ow->index, ow->isLimited, ow->scale); } setDirty(false); enableControls(true); @@ -330,16 +341,15 @@ void ConfigTaskWidget::onAutopilotConnect() */ void ConfigTaskWidget::populateWidgets() { - bool dirtyBack=dirty; + bool dirtyBack = dirty; emit populateWidgetsRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL || ow->widget==NULL) - { + + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { // do nothing + } else { + setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); } - else - setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); } setDirty(dirtyBack); } @@ -348,28 +358,24 @@ void ConfigTaskWidget::populateWidgets() * object field added to the framework pool * Overwrite this if you need to change the default behavior */ -void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) +void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj) { - if (!allowWidgetUpdates) + if (!allowWidgetUpdates) { return; + } - bool dirtyBack=dirty; + bool dirtyBack = dirty; emit refreshWidgetsValuesRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL || ow->widget==NULL) - { - //do nothing + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL || ow->widget == NULL) { + // do nothing + } else { + if (ow->object == obj || obj == NULL) { + setWidgetFromField(ow->widget, ow->field, ow->index, ow->scale, ow->isLimited); + } } - else - { - if(ow->object==obj || obj==NULL) - setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited); - } - } setDirty(dirtyBack); - } /** * SLOT function used to update the uavobject fields from widgets with relation to @@ -379,15 +385,11 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject * obj) void ConfigTaskWidget::updateObjectsFromWidgets() { emit updateObjectsFromWidgetsRequested(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->object==NULL || ow->field==NULL) - { + foreach(objectToWidget * ow, objOfInterest) { + if (ow->object == NULL || ow->field == NULL) {} else { + setFieldFromWidget(ow->widget, ow->field, ow->index, ow->scale); } - else - setFieldFromWidget(ow->widget,ow->field,ow->index,ow->scale); - } } /** @@ -396,9 +398,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets() */ void ConfigTaskWidget::helpButtonPressed() { - QString url=helpButtonList.value((QPushButton*)sender(),QString()); - if(!url.isEmpty()) - QDesktopServices::openUrl( QUrl(url, QUrl::StrictMode) ); + QString url = helpButtonList.value((QPushButton *)sender(), QString()); + + if (!url.isEmpty()) { + QDesktopServices::openUrl(QUrl(url, QUrl::StrictMode)); + } } /** * Add update and save buttons to the form @@ -408,25 +412,23 @@ void ConfigTaskWidget::helpButtonPressed() */ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save) { - if(!smartsave) - { - smartsave=new smartSaveButton(); - connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); - connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty())); - connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates())); - connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates())); + if (!smartsave) { + smartsave = new smartSaveButton(); + connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); + connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty())); + connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates())); + connect(smartsave, SIGNAL(endOp()), this, SLOT(enableObjUpdates())); } - if(update && save) - smartsave->addButtons(save,update); - else if (update) + if (update && save) { + smartsave->addButtons(save, update); + } else if (update) { smartsave->addApplyButton(update); - else if (save) + } else if (save) { smartsave->addSaveButton(save); - if(objOfInterest.count()>0) - { - foreach(objectToWidget * oTw,objOfInterest) - { - smartsave->addObject((UAVDataObject*)oTw->object); + } + if (objOfInterest.count() > 0) { + foreach(objectToWidget * oTw, objOfInterest) { + smartsave->addObject((UAVDataObject *)oTw->object); } } updateEnableControls(); @@ -439,18 +441,18 @@ void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *sav */ void ConfigTaskWidget::enableControls(bool enable) { - if(smartsave) { + if (smartsave) { smartsave->enableControls(enable); } - foreach (QPushButton *button, reloadButtonList) { + foreach(QPushButton * button, reloadButtonList) { button->setEnabled(enable); } - foreach(objectToWidget *ow,objOfInterest) { - if(ow->widget) { + foreach(objectToWidget * ow, objOfInterest) { + if (ow->widget) { ow->widget->setEnabled(enable); - foreach (shadow *sh, ow->shadowsList) { + foreach(shadow * sh, ow->shadowsList) { sh->widget->setEnabled(enable); } } @@ -462,16 +464,13 @@ void ConfigTaskWidget::enableControls(bool enable) */ void ConfigTaskWidget::forceShadowUpdates() { - foreach(objectToWidget * oTw,objOfInterest) - { - foreach (shadow * sh, oTw->shadowsList) - { - disconnectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged())); + foreach(objectToWidget * oTw, objOfInterest) { + foreach(shadow * sh, oTw->shadowsList) { + disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); setWidgetFromVariant(sh->widget, getVariantFromWidget(oTw->widget, oTw->scale, oTw->getUnits()), sh->scale); - emit widgetContentsChanged((QWidget*)sh->widget); - connectWidgetUpdatesToSlot((QWidget*)sh->widget, SLOT(widgetsContentsChanged())); - + emit widgetContentsChanged((QWidget *)sh->widget); + connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); } } setDirty(true); @@ -481,49 +480,44 @@ void ConfigTaskWidget::forceShadowUpdates() */ void ConfigTaskWidget::widgetsContentsChanged() { - emit widgetContentsChanged((QWidget*)sender()); + emit widgetContentsChanged((QWidget *)sender()); double scale; - objectToWidget * oTw= shadowsList.value((QWidget*)sender(),NULL); - if(oTw) - { - if(oTw->widget==(QWidget*)sender()) - { - scale=oTw->scale; - checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), oTw->scale, oTw->getUnits()), oTw->scale); - } - else - { - foreach (shadow * sh, oTw->shadowsList) - { - if(sh->widget==(QWidget*)sender()) - { - scale=sh->scale; - checkWidgetsLimits((QWidget*)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), scale); + objectToWidget *oTw = shadowsList.value((QWidget *)sender(), NULL); + + if (oTw) { + if (oTw->widget == (QWidget *)sender()) { + scale = oTw->scale; + checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), + oTw->scale, oTw->getUnits()), oTw->scale); + } else { + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget == (QWidget *)sender()) { + scale = sh->scale; + checkWidgetsLimits((QWidget *)sender(), oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), + scale, oTw->getUnits()), scale); } } } - if(oTw->widget!=(QWidget *)sender()) - { - disconnectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged())); - checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale); - setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), oTw->scale); - emit widgetContentsChanged((QWidget*)oTw->widget); - connectWidgetUpdatesToSlot((QWidget*)oTw->widget, SLOT(widgetsContentsChanged())); + if (oTw->widget != (QWidget *)sender()) { + disconnectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); + checkWidgetsLimits(oTw->widget, oTw->field, oTw->index, oTw->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); + setWidgetFromVariant(oTw->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), oTw->scale); + emit widgetContentsChanged((QWidget *)oTw->widget); + connectWidgetUpdatesToSlot((QWidget *)oTw->widget, SLOT(widgetsContentsChanged())); } - foreach (shadow * sh, oTw->shadowsList) - { - if(sh->widget!=(QWidget*)sender()) - { - disconnectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); - checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale); - setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget*)sender(), scale, oTw->getUnits()), sh->scale); - emit widgetContentsChanged((QWidget*)sh->widget); - connectWidgetUpdatesToSlot((QWidget*)sh->widget,SLOT(widgetsContentsChanged())); + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget != (QWidget *)sender()) { + disconnectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); + checkWidgetsLimits(sh->widget, oTw->field, oTw->index, sh->isLimited, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); + setWidgetFromVariant(sh->widget, getVariantFromWidget((QWidget *)sender(), scale, oTw->getUnits()), sh->scale); + emit widgetContentsChanged((QWidget *)sh->widget); + connectWidgetUpdatesToSlot((QWidget *)sh->widget, SLOT(widgetsContentsChanged())); } } } - if(smartsave) + if (smartsave) { smartsave->resetIcons(); + } setDirty(true); } /** @@ -539,7 +533,7 @@ void ConfigTaskWidget::clearDirty() */ void ConfigTaskWidget::setDirty(bool value) { - dirty=value; + dirty = value; } /** * Checks if the form is dirty (unsaved changes) @@ -547,10 +541,11 @@ void ConfigTaskWidget::setDirty(bool value) */ bool ConfigTaskWidget::isDirty() { - if(isConnected) + if (isConnected) { return dirty; - else + } else { return false; + } } /** * SLOT function used to disable widget contents changes when related object field changes @@ -558,9 +553,10 @@ bool ConfigTaskWidget::isDirty() void ConfigTaskWidget::disableObjUpdates() { allowWidgetUpdates = false; - foreach(objectToWidget * obj,objOfInterest) - { - if(obj->object)disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*))); + foreach(objectToWidget * obj, objOfInterest) { + if (obj->object) { + disconnect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *))); + } } } /** @@ -569,10 +565,10 @@ void ConfigTaskWidget::disableObjUpdates() void ConfigTaskWidget::enableObjUpdates() { allowWidgetUpdates = true; - foreach(objectToWidget * obj,objOfInterest) - { - if(obj->object) - connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues(UAVObject*)), Qt::UniqueConnection); + foreach(objectToWidget * obj, objOfInterest) { + if (obj->object) { + connect(obj->object, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshWidgetsValues(UAVObject *)), Qt::UniqueConnection); + } } } /** @@ -581,7 +577,7 @@ void ConfigTaskWidget::enableObjUpdates() */ void ConfigTaskWidget::objectUpdated(UAVObject *obj) { - objectUpdates[obj]=true; + objectUpdates[obj] = true; } /** * Checks if all objects added to the pool have already been updated @@ -589,13 +585,12 @@ void ConfigTaskWidget::objectUpdated(UAVObject *obj) */ bool ConfigTaskWidget::allObjectsUpdated() { - qDebug()<<"ConfigTaskWidge:allObjectsUpdated called"; - bool ret=true; - foreach(UAVObject *obj, objectUpdates.keys()) - { - ret=ret & objectUpdates[obj]; + qDebug() << "ConfigTaskWidge:allObjectsUpdated called"; + bool ret = true; + foreach(UAVObject * obj, objectUpdates.keys()) { + ret = ret & objectUpdates[obj]; } - qDebug()<<"Returned:"<apply(); + } } /** * SLOT call this to save changes to uav objects */ void ConfigTaskWidget::save() { - if(smartsave) + if (smartsave) { smartsave->save(); + } } /** * Adds a new shadow widget @@ -641,50 +636,47 @@ void ConfigTaskWidget::save() * This function doesn't have to be used directly, addUAVObjectToWidgetRelation will call it if a previous relation exhists. * @return returns false if the shadow widget relation failed to be added (no previous relation exhisted) */ -bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,QList* defaultReloadGroups,quint32 instID) +bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited, + QList *defaultReloadGroups, quint32 instID) { - foreach(objectToWidget * oTw,objOfInterest) - { - if(!oTw->object || !oTw->widget || !oTw->field) + foreach(objectToWidget * oTw, objOfInterest) { + if (!oTw->object || !oTw->widget || !oTw->field) { continue; - if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index && oTw->object->getInstID()==instID) - { - shadow * sh=NULL; - //prefer anything else to QLabel - if(qobject_cast(oTw->widget) && !qobject_cast(widget)) - { - sh=new shadow; - sh->isLimited=oTw->isLimited; - sh->scale=oTw->scale; - sh->widget=oTw->widget; - oTw->isLimited=isLimited; - oTw->scale=scale; - oTw->widget=widget; + } + if (oTw->object->getName() == object && oTw->field->getName() == field && oTw->index == index && oTw->object->getInstID() == instID) { + shadow *sh = NULL; + // prefer anything else to QLabel + if (qobject_cast(oTw->widget) && !qobject_cast(widget)) { + sh = new shadow; + sh->isLimited = oTw->isLimited; + sh->scale = oTw->scale; + sh->widget = oTw->widget; + oTw->isLimited = isLimited; + oTw->scale = scale; + oTw->widget = widget; } - //prefer QDoubleSpinBox to anything else - else if(!qobject_cast(oTw->widget) && qobject_cast(widget)) - { - sh=new shadow; - sh->isLimited=oTw->isLimited; - sh->scale=oTw->scale; - sh->widget=oTw->widget; - oTw->isLimited=isLimited; - oTw->scale=scale; - oTw->widget=widget; + // prefer QDoubleSpinBox to anything else + else if (!qobject_cast(oTw->widget) && qobject_cast(widget)) { + sh = new shadow; + sh->isLimited = oTw->isLimited; + sh->scale = oTw->scale; + sh->widget = oTw->widget; + oTw->isLimited = isLimited; + oTw->scale = scale; + oTw->widget = widget; + } else { + sh = new shadow; + sh->isLimited = isLimited; + sh->scale = scale; + sh->widget = widget; } - else - { - sh=new shadow; - sh->isLimited=isLimited; - sh->scale=scale; - sh->widget=widget; - } - shadowsList.insert(widget,oTw); + shadowsList.insert(widget, oTw); oTw->shadowsList.append(sh); - connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged())); - if(defaultReloadGroups) - addWidgetToDefaultReloadGroups(widget,defaultReloadGroups); - loadWidgetLimits(widget,oTw->field,oTw->index,isLimited,scale); + connectWidgetUpdatesToSlot(widget, SLOT(widgetsContentsChanged())); + if (defaultReloadGroups) { + addWidgetToDefaultReloadGroups(widget, defaultReloadGroups); + } + loadWidgetLimits(widget, oTw->field, oTw->index, isLimited, scale); return true; } } @@ -696,118 +688,115 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w */ void ConfigTaskWidget::autoLoadWidgets() { - QPushButton * saveButtonWidget=NULL; - QPushButton * applyButtonWidget=NULL; - foreach(QWidget * widget,this->findChildren()) - { - QVariant info=widget->property("objrelation"); - if(info.isValid()) - { + QPushButton *saveButtonWidget = NULL; + QPushButton *applyButtonWidget = NULL; + + foreach(QWidget * widget, this->findChildren()) { + QVariant info = widget->property("objrelation"); + + if (info.isValid()) { uiRelationAutomation uiRelation; - uiRelation.buttonType=none; - uiRelation.scale=1; - uiRelation.element=QString(); - uiRelation.haslimits=false; - foreach(QString str, info.toStringList()) - { - QString prop=str.split(":").at(0); - QString value=str.split(":").at(1); - if(prop== "objname") - uiRelation.objname=value; - else if(prop== "fieldname") - uiRelation.fieldname=value; - else if(prop=="element") - uiRelation.element=value; - else if(prop== "scale") - { - if(value=="null") - uiRelation.scale=1; - else - uiRelation.scale=value.toDouble(); - } - else if(prop== "haslimits") - { - if(value=="yes") - uiRelation.haslimits=true; - else - uiRelation.haslimits=false; - } - else if(prop== "button") - { - if(value=="save") - uiRelation.buttonType=save_button; - else if(value=="apply") - uiRelation.buttonType=apply_button; - else if(value=="reload") - uiRelation.buttonType=reload_button; - else if(value=="default") - uiRelation.buttonType=default_button; - else if(value=="help") - uiRelation.buttonType=help_button; - } - else if(prop== "buttongroup") - { - foreach(QString s,value.split(",")) - { + uiRelation.buttonType = none; + uiRelation.scale = 1; + uiRelation.element = QString(); + uiRelation.haslimits = false; + foreach(QString str, info.toStringList()) { + QString prop = str.split(":").at(0); + QString value = str.split(":").at(1); + + if (prop == "objname") { + uiRelation.objname = value; + } else if (prop == "fieldname") { + uiRelation.fieldname = value; + } else if (prop == "element") { + uiRelation.element = value; + } else if (prop == "scale") { + if (value == "null") { + uiRelation.scale = 1; + } else { + uiRelation.scale = value.toDouble(); + } + } else if (prop == "haslimits") { + if (value == "yes") { + uiRelation.haslimits = true; + } else { + uiRelation.haslimits = false; + } + } else if (prop == "button") { + if (value == "save") { + uiRelation.buttonType = save_button; + } else if (value == "apply") { + uiRelation.buttonType = apply_button; + } else if (value == "reload") { + uiRelation.buttonType = reload_button; + } else if (value == "default") { + uiRelation.buttonType = default_button; + } else if (value == "help") { + uiRelation.buttonType = help_button; + } + } else if (prop == "buttongroup") { + foreach(QString s, value.split(",")) { uiRelation.buttonGroup.append(s.toInt()); } + } else if (prop == "url") { + uiRelation.url = str.mid(str.indexOf(":") + 1); } - else if(prop=="url") - uiRelation.url=str.mid(str.indexOf(":")+1); } - if(!uiRelation.buttonType==none) - { - QPushButton * button=NULL; - switch(uiRelation.buttonType) - { + if (!uiRelation.buttonType == none) { + QPushButton *button = NULL; + switch (uiRelation.buttonType) { case save_button: - saveButtonWidget=qobject_cast(widget); - if(saveButtonWidget) - addApplySaveButtons(NULL,saveButtonWidget); + saveButtonWidget = qobject_cast(widget); + if (saveButtonWidget) { + addApplySaveButtons(NULL, saveButtonWidget); + } break; case apply_button: - applyButtonWidget=qobject_cast(widget); - if(applyButtonWidget) - addApplySaveButtons(applyButtonWidget,NULL); + applyButtonWidget = qobject_cast(widget); + if (applyButtonWidget) { + addApplySaveButtons(applyButtonWidget, NULL); + } break; case default_button: - button=qobject_cast(widget); - if(button) - addDefaultButton(button,uiRelation.buttonGroup.at(0)); + button = qobject_cast(widget); + if (button) { + addDefaultButton(button, uiRelation.buttonGroup.at(0)); + } break; case reload_button: - button=qobject_cast(widget); - if(button) - addReloadButton(button,uiRelation.buttonGroup.at(0)); + button = qobject_cast(widget); + if (button) { + addReloadButton(button, uiRelation.buttonGroup.at(0)); + } break; case help_button: - button=qobject_cast(widget); - if(button) - addHelpButton(button,uiRelation.url); + button = qobject_cast(widget); + if (button) { + addHelpButton(button, uiRelation.url); + } break; default: break; } - } - else - { - QWidget * wid=qobject_cast(widget); - if(wid) - addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.scale,uiRelation.haslimits,&uiRelation.buttonGroup); + } else { + QWidget *wid = qobject_cast(widget); + if (wid) { + addUAVObjectToWidgetRelation(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup); + } } } } refreshWidgetsValues(); forceShadowUpdates(); - foreach(objectToWidget * ow,objOfInterest) - { - if(ow->widget) - qDebug()<<"Master:"<widget->objectName(); - foreach(shadow * sh,ow->shadowsList) - { - if(sh->widget) - qDebug()<<"Child"<widget->objectName(); + foreach(objectToWidget * ow, objOfInterest) { + if (ow->widget) { + qDebug() << "Master:" << ow->widget->objectName(); + } + foreach(shadow * sh, ow->shadowsList) { + if (sh->widget) { + qDebug() << "Child" << sh->widget->objectName(); + } } } } @@ -817,32 +806,26 @@ void ConfigTaskWidget::autoLoadWidgets() * @param widget pointer to the widget to be added to the groups * @param groups list of the groups on which to add the widget */ -void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList * groups) +void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList *groups) { - foreach(objectToWidget * oTw,objOfInterest) - { - bool addOTW=false; - if(oTw->widget==widget) - addOTW=true; - else - { - foreach(shadow * sh, oTw->shadowsList) - { - if(sh->widget==widget) - addOTW=true; + foreach(objectToWidget * oTw, objOfInterest) { + bool addOTW = false; + + if (oTw->widget == widget) { + addOTW = true; + } else { + foreach(shadow * sh, oTw->shadowsList) { + if (sh->widget == widget) { + addOTW = true; + } } } - if(addOTW) - { - foreach(int i,*groups) - { - if(defaultReloadGroups.contains(i)) - { + if (addOTW) { + foreach(int i, *groups) { + if (defaultReloadGroups.contains(i)) { defaultReloadGroups.value(i)->append(oTw); - } - else - { - defaultReloadGroups.insert(i,new QList()); + } else { + defaultReloadGroups.insert(i, new QList()); defaultReloadGroups.value(i)->append(oTw); } } @@ -856,8 +839,8 @@ void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QListsetProperty("group",buttonGroup); - connect(button,SIGNAL(clicked()),this,SLOT(defaultButtonClicked())); + button->setProperty("group", buttonGroup); + connect(button, SIGNAL(clicked()), this, SLOT(defaultButtonClicked())); } /** * Adds a button to a reload group @@ -866,24 +849,25 @@ void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup) */ void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup) { - button->setProperty("group",buttonGroup); + button->setProperty("group", buttonGroup); reloadButtonList.append(button); - connect(button,SIGNAL(clicked()),this,SLOT(reloadButtonClicked())); + connect(button, SIGNAL(clicked()), this, SLOT(reloadButtonClicked())); } /** * Called when a default button is clicked */ void ConfigTaskWidget::defaultButtonClicked() { - int group=sender()->property("group").toInt(); + int group = sender()->property("group").toInt(); emit defaultRequested(group); - QList * list=defaultReloadGroups.value(group); - foreach(objectToWidget * oTw,*list) - { - if(!oTw->object || !oTw->field) + + QList *list = defaultReloadGroups.value(group); + foreach(objectToWidget * oTw, *list) { + if (!oTw->object || !oTw->field) { continue; - UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone(); - setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale,oTw->isLimited); + } + UAVDataObject *temp = ((UAVDataObject *)oTw->object)->dirtyClone(); + setWidgetFromField(oTw->widget, temp->getField(oTw->field->getName()), oTw->index, oTw->scale, oTw->isLimited); } } /** @@ -891,145 +875,114 @@ void ConfigTaskWidget::defaultButtonClicked() */ void ConfigTaskWidget::reloadButtonClicked() { - if(timeOut) + if (timeOut) { return; - int group=sender()->property("group").toInt(); - QList * list=defaultReloadGroups.value(group,NULL); - if(!list) + } + int group = sender()->property("group").toInt(); + QList *list = defaultReloadGroups.value(group, NULL); + if (!list) { return; - ObjectPersistence* objper = dynamic_cast( getObjectManager()->getObject(ObjectPersistence::NAME) ); - timeOut=new QTimer(this); - QEventLoop * eventLoop=new QEventLoop(this); - connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); - connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); + } + ObjectPersistence *objper = dynamic_cast(getObjectManager()->getObject(ObjectPersistence::NAME)); + timeOut = new QTimer(this); + 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) - { + foreach(objectToWidget * oTw, *list) { + if (oTw->object != NULL) { temphelper value; - value.objid=oTw->object->getObjID(); - value.objinstid=oTw->object->getInstID(); - if(temp.contains(value)) + value.objid = oTw->object->getObjID(); + value.objinstid = oTw->object->getInstID(); + if (temp.contains(value)) { continue; - else + } else { temp.append(value); + } ObjectPersistence::DataFields data; - data.Operation = ObjectPersistence::OPERATION_LOAD; - data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; - data.ObjectID = oTw->object->getObjID(); + data.Operation = ObjectPersistence::OPERATION_LOAD; + data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; + data.ObjectID = oTw->object->getObjID(); data.InstanceID = oTw->object->getInstID(); objper->setData(data); objper->updated(); timeOut->start(500); eventLoop->exec(); - if(timeOut->isActive()) - { + if (timeOut->isActive()) { oTw->object->requestUpdate(); - if(oTw->widget) - setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited); + if (oTw->widget) { + setWidgetFromField(oTw->widget, oTw->field, oTw->index, oTw->scale, oTw->isLimited); + } } timeOut->stop(); } } - if(eventLoop) - { + if (eventLoop) { delete eventLoop; - eventLoop=NULL; + eventLoop = NULL; } - if(timeOut) - { + if (timeOut) { delete timeOut; - timeOut=NULL; + timeOut = NULL; } } /** * Connects widgets "contents changed" signals to a slot */ -void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* function) +void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget *widget, const char *function) { - if(!widget) + if (!widget) { return; - if(QComboBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(currentIndexChanged(int)),this,function); } - else if(QSlider * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(int)),this,function); + if (QComboBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(currentIndexChanged(int)), this, function); + } else if (QSlider * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (MixerCurveWidget * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(curveUpdated()), this, function); + } else if (QTableWidget * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(cellChanged(int, int)), this, function); + } else if (QSpinBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(valueChanged(double)), this, function); + } else if (QCheckBox * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(stateChanged(int)), this, function); + } else if (QPushButton * cb = qobject_cast(widget)) { + connect(cb, SIGNAL(clicked()), this, function); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); } - else if(MixerCurveWidget * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(curveUpdated()),this,function); - } - else if(QTableWidget * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(cellChanged(int,int)),this,function); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(int)),this,function); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(valueChanged(double)),this,function); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(stateChanged(int)),this,function); - } - else if(QPushButton * cb=qobject_cast(widget)) - { - connect(cb,SIGNAL(clicked()),this,function); - } - else - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); - } /** * Disconnects widgets "contents changed" signals to a slot */ -void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char* function) +void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function) { - if(!widget) + if (!widget) { return; - if(QComboBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(currentIndexChanged(int)),this,function); } - else if(QSlider * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(int)),this,function); + if (QComboBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(currentIndexChanged(int)), this, function); + } else if (QSlider * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (MixerCurveWidget * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(curveUpdated()), this, function); + } else if (QTableWidget * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(cellChanged(int, int)), this, function); + } else if (QSpinBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(int)), this, function); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(valueChanged(double)), this, function); + } else if (QCheckBox * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(stateChanged(int)), this, function); + } else if (QPushButton * cb = qobject_cast(widget)) { + disconnect(cb, SIGNAL(clicked()), this, function); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); } - else if(MixerCurveWidget * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(curveUpdated()),this,function); - } - else if(QTableWidget * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(cellChanged(int,int)),this,function); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(int)),this,function); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(valueChanged(double)),this,function); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(stateChanged(int)),this,function); - } - else if(QPushButton * cb=qobject_cast(widget)) - { - disconnect(cb,SIGNAL(clicked()),this,function); - } - else - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); - } /** * Sets a widget value from an UAVObject field @@ -1039,18 +992,18 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char * @param scale scale to be used on the assignement * @return returns true if the assignement was successfull */ -bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,double scale) +bool ConfigTaskWidget::setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale) { - if(!widget || !field) + if (!widget || !field) { return false; + } QVariant ret = getVariantFromWidget(widget, scale, field->getUnits()); - if(ret.isValid()) - { - field->setValue(ret,index); + if (ret.isValid()) { + field->setValue(ret, index); return true; } { - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); return false; } } @@ -1062,38 +1015,27 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel */ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units) { - if(QComboBox * cb=qobject_cast(widget)) - { + if (QComboBox * cb = qobject_cast(widget)) { return (QString)cb->currentText(); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - return (double)(cb->value()* scale); - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - return (double)(cb->value()* scale); - } - else if(QSlider * cb=qobject_cast(widget)) - { - return(double)(cb->value()* scale); - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - return (QString)(cb->isChecked()?"TRUE":"FALSE"); - } - else if(QLineEdit * cb=qobject_cast(widget)) - { + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QSpinBox * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QSlider * cb = qobject_cast(widget)) { + return (double)(cb->value() * scale); + } else if (QCheckBox * cb = qobject_cast(widget)) { + return (QString)(cb->isChecked() ? "TRUE" : "FALSE"); + } else if (QLineEdit * cb = qobject_cast(widget)) { QString value = (QString)cb->displayText(); - if(units == "hex") { + if (units == "hex") { bool ok; return value.toUInt(&ok, 16); } else { return value; } - } - else + } else { return QVariant(); + } } /** * Sets a widget from a variant @@ -1105,55 +1047,43 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q */ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units) { - if(QComboBox * cb=qobject_cast(widget)) - { + if (QComboBox * cb = qobject_cast(widget)) { cb->setCurrentIndex(cb->findText(value.toString())); return true; - } - else if(QLabel * cb=qobject_cast(widget)) - { - if(scale==0) + } else if (QLabel * cb = qobject_cast(widget)) { + if (scale == 0) { cb->setText(value.toString()); - else - cb->setText(QString::number((value.toDouble()/scale))); + } else { + cb->setText(QString::number((value.toDouble() / scale))); + } return true; - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - cb->setValue((double)(value.toDouble()/scale)); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + cb->setValue((double)(value.toDouble() / scale)); return true; - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - cb->setValue((int)qRound(value.toDouble()/scale)); + } else if (QSpinBox * cb = qobject_cast(widget)) { + cb->setValue((int)qRound(value.toDouble() / scale)); return true; - } - else if(QSlider * cb=qobject_cast(widget)) - { - cb->setValue((int)qRound(value.toDouble()/scale)); + } else if (QSlider * cb = qobject_cast(widget)) { + cb->setValue((int)qRound(value.toDouble() / scale)); return true; - } - else if(QCheckBox * cb=qobject_cast(widget)) - { - bool bvalue=value.toString()=="TRUE"; + } else if (QCheckBox * cb = qobject_cast(widget)) { + bool bvalue = value.toString() == "TRUE"; cb->setChecked(bvalue); return true; - } - else if(QLineEdit * cb=qobject_cast(widget)) - { - if ((scale== 0) || (scale == 1)) { - if(units == "hex") { + } else if (QLineEdit * cb = qobject_cast(widget)) { + if ((scale == 0) || (scale == 1)) { + if (units == "hex") { cb->setText(QString::number(value.toUInt(), 16).toUpper()); } else { cb->setText(value.toString()); } } else { - cb->setText(QString::number((value.toDouble()/scale))); + cb->setText(QString::number((value.toDouble() / scale))); } return true; - } - else + } else { return false; + } } /** @@ -1177,185 +1107,154 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou * @param hasLimits set to true if you want to limit the values (check wiki) * @return returns true if the assignement was successfull */ -bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,double scale,bool hasLimits) +bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits) { - if(!widget || !field) + if (!widget || !field) { return false; - if(QComboBox * cb=qobject_cast(widget)) - { - if(cb->count()==0) - loadWidgetLimits(cb,field,index,hasLimits,scale); } - QVariant var=field->getValue(index); - checkWidgetsLimits(widget,field,index,hasLimits,var,scale); - bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits()); - if(ret) + if (QComboBox * cb = qobject_cast(widget)) { + if (cb->count() == 0) { + loadWidgetLimits(cb, field, index, hasLimits, scale); + } + } + QVariant var = field->getValue(index); + checkWidgetsLimits(widget, field, index, hasLimits, var, scale); + bool ret = setWidgetFromVariant(widget, var, scale, field->getUnits()); + if (ret) { return true; - else - { - qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<metaObject()->className(); + } else { + qDebug() << __FUNCTION__ << "widget to uavobject relation not implemented" << widget->metaObject()->className(); return false; } } -void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, double scale) +void ConfigTaskWidget::checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale) { - if(!hasLimits) + if (!hasLimits) { return; - if(!field->isWithinLimits(value,index,currentBoard)) - { - if(!widget->property("styleBackup").isValid()) - widget->setProperty("styleBackup",widget->styleSheet()); - widget->setStyleSheet(outOfLimitsStyle); - widget->setProperty("wasOverLimits",(bool)true); - if(QComboBox * cb=qobject_cast(widget)) - { - if(cb->findText(value.toString())==-1) - cb->addItem(value.toString()); - } - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - if((double)(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((double)(value.toDouble()/scale)); - } - else if((double)(value.toDouble()/scale)minimum()) - { - cb->setMinimum((double)(value.toDouble()/scale)); - } - - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - if((int)qRound(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((int)qRound(value.toDouble()/scale)); - } - else if((int)qRound(value.toDouble()/scale)minimum()) - { - cb->setMinimum((int)qRound(value.toDouble()/scale)); - } - } - else if(QSlider * cb=qobject_cast(widget)) - { - if((int)qRound(value.toDouble()/scale)>cb->maximum()) - { - cb->setMaximum((int)qRound(value.toDouble()/scale)); - } - else if((int)qRound(value.toDouble()/scale)minimum()) - { - cb->setMinimum((int)qRound(value.toDouble()/scale)); - } - } - } - else if(widget->property("wasOverLimits").isValid()) - { - if(widget->property("wasOverLimits").toBool()) - { - widget->setProperty("wasOverLimits",(bool)false); - if(widget->property("styleBackup").isValid()) - { - QString style=widget->property("styleBackup").toString(); + if (!field->isWithinLimits(value, index, currentBoard)) { + if (!widget->property("styleBackup").isValid()) { + widget->setProperty("styleBackup", widget->styleSheet()); + } + widget->setStyleSheet(outOfLimitsStyle); + widget->setProperty("wasOverLimits", (bool)true); + if (QComboBox * cb = qobject_cast(widget)) { + if (cb->findText(value.toString()) == -1) { + cb->addItem(value.toString()); + } + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + if ((double)(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((double)(value.toDouble() / scale)); + } else if ((double)(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((double)(value.toDouble() / scale)); + } + } else if (QSpinBox * cb = qobject_cast(widget)) { + if ((int)qRound(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((int)qRound(value.toDouble() / scale)); + } else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((int)qRound(value.toDouble() / scale)); + } + } else if (QSlider * cb = qobject_cast(widget)) { + if ((int)qRound(value.toDouble() / scale) > cb->maximum()) { + cb->setMaximum((int)qRound(value.toDouble() / scale)); + } else if ((int)qRound(value.toDouble() / scale) < cb->minimum()) { + cb->setMinimum((int)qRound(value.toDouble() / scale)); + } + } + } else if (widget->property("wasOverLimits").isValid()) { + if (widget->property("wasOverLimits").toBool()) { + widget->setProperty("wasOverLimits", (bool)false); + if (widget->property("styleBackup").isValid()) { + QString style = widget->property("styleBackup").toString(); widget->setStyleSheet(style); } - loadWidgetLimits(widget,field,index,hasLimits,scale); + loadWidgetLimits(widget, field, index, hasLimits, scale); } } } -void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,double scale) -{ - if(!widget || !field) +void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double scale) +{ + if (!widget || !field) { return; - if(QComboBox * cb=qobject_cast(widget)) - { + } + if (QComboBox * cb = qobject_cast(widget)) { cb->clear(); - QStringList option=field->getOptions(); - if(hasLimits) - { - foreach(QString str,option) - { - if(field->isWithinLimits(str,index,currentBoard)) + QStringList option = field->getOptions(); + if (hasLimits) { + foreach(QString str, option) { + if (field->isWithinLimits(str, index, currentBoard)) { cb->addItem(str); + } } - } - else + } else { cb->addItems(option); + } } - if(!hasLimits) + if (!hasLimits) { return; - else if(QDoubleSpinBox * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index).isValid()) - { - cb->setMaximum((double)(field->getMaxLimit(index,currentBoard).toDouble()/scale)); + } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index).isValid()) { + cb->setMaximum((double)(field->getMaxLimit(index, currentBoard).toDouble() / scale)); } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((double)(field->getMinLimit(index,currentBoard).toDouble()/scale)); + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((double)(field->getMinLimit(index, currentBoard).toDouble() / scale)); } - } - else if(QSpinBox * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index,currentBoard).isValid()) - { - cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); + } else if (QSpinBox * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index, currentBoard).isValid()) { + cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((int)qRound(field->getMinLimit(index,currentBoard).toDouble()/scale)); + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((int)qRound(field->getMinLimit(index, currentBoard).toDouble() / scale)); } - } - else if(QSlider * cb=qobject_cast(widget)) - { - if(field->getMaxLimit(index,currentBoard).isValid()) - { - cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); + } else if (QSlider * cb = qobject_cast(widget)) { + if (field->getMaxLimit(index, currentBoard).isValid()) { + cb->setMaximum((int)qRound(field->getMaxLimit(index, currentBoard).toDouble() / scale)); } - if(field->getMinLimit(index,currentBoard).isValid()) - { - cb->setMinimum((int)(field->getMinLimit(index,currentBoard).toDouble()/scale)); + if (field->getMinLimit(index, currentBoard).isValid()) { + cb->setMinimum((int)(field->getMinLimit(index, currentBoard).toDouble() / scale)); } } } void ConfigTaskWidget::updateEnableControls() { - TelemetryManager* telMngr = pm->getObject(); + TelemetryManager *telMngr = pm->getObject(); + Q_ASSERT(telMngr); enableControls(telMngr->isConnected()); } void ConfigTaskWidget::disableMouseWheelEvents() { - //Disable mouse wheel events - foreach( QSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + // Disable mouse wheel events + foreach(QSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QDoubleSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QDoubleSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QSlider * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QSlider * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QComboBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QComboBox * sp, findChildren()) { + sp->installEventFilter(this); } } -bool ConfigTaskWidget::eventFilter( QObject * obj, QEvent * evt ) { - //Filter all wheel events, and ignore them - if ( evt->type() == QEvent::Wheel && - (qobject_cast( obj ) || - qobject_cast( obj ) || - qobject_cast( obj ) )) - { +bool ConfigTaskWidget::eventFilter(QObject *obj, QEvent *evt) +{ + // Filter all wheel events, and ignore them + if (evt->type() == QEvent::Wheel && + (qobject_cast(obj) || + qobject_cast(obj) || + qobject_cast(obj))) { evt->ignore(); return true; } - return QWidget::eventFilter( obj, evt ); + return QWidget::eventFilter(obj, evt); } /** - @} - @} - */ + @} + @} + */ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index f10670868..461366251 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -48,53 +48,49 @@ #include #include -class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget -{ +class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget : public QWidget { Q_OBJECT public: - struct shadow - { - QWidget * widget; - double scale; - bool isLimited; + struct shadow { + QWidget *widget; + double scale; + bool isLimited; }; - struct objectToWidget - { - UAVObject * object; - UAVObjectField * field; - QWidget * widget; + struct objectToWidget { + UAVObject *object; + UAVObjectField *field; + QWidget *widget; int index; - double scale; + double scale; bool isLimited; QList shadowsList; - QString getUnits() const { + QString getUnits() const + { if (field) { return field->getUnits(); } - return QString(""); + return QString(""); } }; - struct temphelper - { + struct temphelper { quint32 objid; quint32 objinstid; - bool operator==(const temphelper& lhs) + bool operator==(const temphelper & lhs) { - return (lhs.objid==this->objid && lhs.objinstid==this->objinstid); + return lhs.objid == this->objid && lhs.objinstid == this->objinstid; } }; - enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button,help_button}; - struct uiRelationAutomation - { - QString objname; - QString fieldname; - QString element; - QString url; + enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button }; + struct uiRelationAutomation { + QString objname; + QString fieldname; + QString element; + QString url; buttonTypeEnum buttonType; - QList buttonGroup; + QList buttonGroup; double scale; bool haslimits; }; @@ -103,37 +99,37 @@ public: virtual ~ConfigTaskWidget(); void disableMouseWheelEvents(); - bool eventFilter( QObject * obj, QEvent * evt ); + bool eventFilter(QObject *obj, QEvent *evt); void saveObjectToSD(UAVObject *obj); - UAVObjectManager* getObjectManager(); + UAVObjectManager *getObjectManager(); static double listMean(QList list); static double listVar(QList list); - void addUAVObject(QString objectName, QList *reloadGroups=NULL); - void addUAVObject(UAVObject * objectName, QList *reloadGroups=NULL); + void addUAVObject(QString objectName, QList *reloadGroups = NULL); + void addUAVObject(UAVObject *objectName, QList *reloadGroups = NULL); - void addWidget(QWidget * widget); + void addWidget(QWidget *widget); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, int index=0, double scale=1, bool isLimited=false, QList *defaultReloadGroups=0, quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited = false, QList *defaultReloadGroups = 0, quint32 instID = 0); void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); - void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString index); - //BUTTONS// - void addApplySaveButtons(QPushButton * update,QPushButton * save); - void addReloadButton(QPushButton * button,int buttonGroup); - void addDefaultButton(QPushButton * button,int buttonGroup); + // BUTTONS// + void addApplySaveButtons(QPushButton *update, QPushButton *save); + void addReloadButton(QPushButton *button, int buttonGroup); + void addDefaultButton(QPushButton *button, int buttonGroup); ////////// - void addWidgetToDefaultReloadGroups(QWidget * widget, QList *groups); + void addWidgetToDefaultReloadGroups(QWidget *widget, QList *groups); - bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,double shadowScale=1,bool shadowIsLimited=false); - bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false, QList *defaultReloadGroups=NULL, quint32 instID=0); + bool addShadowWidget(QWidget *masterWidget, QWidget *shadowWidget, double shadowScale = 1, bool shadowIsLimited = false); + bool addShadowWidget(QString object, QString field, QWidget *widget, int index = 0, double scale = 1, bool isLimited = false, QList *defaultReloadGroups = NULL, quint32 instID = 0); void autoLoadWidgets(); @@ -141,8 +137,11 @@ public: void setDirty(bool value); bool allObjectsUpdated(); - void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;} - void addHelpButton(QPushButton * button,QString url); + void setOutOfLimitsStyle(QString style) + { + outOfLimitsStyle = style; + } + void addHelpButton(QPushButton *button, QString url); void forceShadowUpdates(); void forceConnectedState(); public slots: @@ -152,21 +151,21 @@ public slots: void apply(); void save(); signals: - //fired when a widgets contents changes - void widgetContentsChanged(QWidget * widget); - //fired when the framework requests that the widgets values be populated, use for custom behaviour + // fired when a widgets contents changes + void widgetContentsChanged(QWidget *widget); + // fired when the framework requests that the widgets values be populated, use for custom behaviour void populateWidgetsRequested(); - //fired when the framework requests that the widgets values be refreshed, use for custom behaviour + // fired when the framework requests that the widgets values be refreshed, use for custom behaviour void refreshWidgetsValuesRequested(); - //fired when the framework requests that the UAVObject values be updated from the widgets value, use for custom behaviour + // fired when the framework requests that the UAVObject values be updated from the widgets value, use for custom behaviour void updateObjectsFromWidgetsRequested(); - //fired when the autopilot connects + // fired when the autopilot connects void autoPilotConnected(); - //fired when the autopilot disconnects + // fired when the autopilot disconnects void autoPilotDisconnected(); void defaultRequested(int group); private slots: - void objectUpdated(UAVObject*); + void objectUpdated(UAVObject *); void defaultButtonClicked(); void reloadButtonClicked(); private: @@ -174,15 +173,15 @@ private: bool isConnected; bool allowWidgetUpdates; QStringList objectsList; - QList objOfInterest; + QList objOfInterest; ExtensionSystem::PluginManager *pm; UAVObjectManager *objManager; - UAVObjectUtilManager* utilMngr; + UAVObjectUtilManager *utilMngr; smartSaveButton *smartsave; - QMap objectUpdates; - QMap *> defaultReloadGroups; - QMap shadowsList; - QMap helpButtonList; + QMap objectUpdates; + QMap *> defaultReloadGroups; + QMap shadowsList; + QMap helpButtonList; QList reloadButtonList; bool dirty; bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale); @@ -194,7 +193,7 @@ private: void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; - QTimer * timeOut; + QTimer *timeOut; protected slots: virtual void disableObjUpdates(); @@ -202,14 +201,13 @@ protected slots: virtual void clearDirty(); virtual void widgetsContentsChanged(); virtual void populateWidgets(); - virtual void refreshWidgetsValues(UAVObject * obj=NULL); + virtual void refreshWidgetsValues(UAVObject *obj = NULL); virtual void updateObjectsFromWidgets(); virtual void helpButtonPressed(); protected: virtual void enableControls(bool enable); void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale); void updateEnableControls(); - }; #endif // CONFIGTASKWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index edf00594a..6da0bcb95 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -39,8 +39,7 @@ QT_BEGIN_NAMESPACE class QGraphicsSceneMouseEvent; QT_END_NAMESPACE -class MixerNode : public QObject,public QGraphicsItem -{ +class MixerNode : public QObject, public QGraphicsItem { Q_OBJECT public: MixerNode(MixerCurveWidget *graphWidget); @@ -48,15 +47,37 @@ public: QList edges() const; enum { Type = UserType + 10 }; - int type() const { return Type; } + int type() const + { + return Type; + } void verticalMove(bool flag); - void setPositiveColor(QColor color = "#609FF2") {positiveColor = color; } - void setNegativeColor(QColor color = "#EF5F5F") {negativeColor = color; } - void setImage(QImage img) { image = img; } - void setDrawNode(bool draw) { drawNode = draw; } - void setDrawText(bool draw) { drawText = draw; } + void setPositiveColor(QColor color = "#609FF2") + { + positiveColor = color; + } + + void setNegativeColor(QColor color = "#EF5F5F") + { + negativeColor = color; + } + + void setImage(QImage img) + { + image = img; + } + + void setDrawNode(bool draw) + { + drawNode = draw; + } + + void setDrawText(bool draw) + { + drawText = draw; + } QRectF boundingRect() const; QPainterPath shape() const; @@ -69,25 +90,24 @@ protected: void mousePressEvent(QGraphicsSceneMouseEvent *event); void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); - + private: - QList edgeList; - QPointF newPos; - MixerCurveWidget* graph; + QList edgeList; + QPointF newPos; + MixerCurveWidget *graph; - QColor positiveColor; - QColor neutralColor; - QColor negativeColor; - QColor disabledColor; - QColor disabledTextColor; + QColor positiveColor; + QColor neutralColor; + QColor negativeColor; + QColor disabledColor; + QColor disabledTextColor; - QImage image; - - bool vertical; - bool drawNode; - bool drawText; - int index; + QImage image; + bool vertical; + bool drawNode; + bool drawText; + int index; }; -#endif // MIXERCURVEPOINT_H +#endif // MIXERCURVEPOINT_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index 26df6a51e..8cc64d8b5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -37,57 +37,54 @@ #include "mixercurveline.h" #include "uavobjectwidgetutils_global.h" -class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView -{ +class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView { Q_OBJECT public: MixerCurveWidget(QWidget *parent = 0); - ~MixerCurveWidget(); + ~MixerCurveWidget(); friend class MixerCurve; - void itemMoved(double itemValue); // Callback when a point is moved, to be updated - 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 setRange(double min, double max); + void itemMoved(double itemValue); // Callback when a point is moved, to be updated + 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 setRange(double min, double max); - static const int NODE_NUMELEM = 5; + static const int NODE_NUMELEM = 5; signals: - void curveUpdated(); - void curveMinChanged(double value); - void curveMaxChanged(double value); + void curveUpdated(); + void curveMinChanged(double value); + void curveMaxChanged(double value); private slots: private: - QGraphicsSvgItem *plot; + QGraphicsSvgItem *plot; - QList edgeList; - QList nodeList; + QList edgeList; + QList nodeList; - double curveMin; - double curveMax; - bool curveUpdating; + double curveMin; + double curveMax; + bool curveUpdating; - void initNodes(int numPoints); - void setPositiveColor(QString color); - void setNegativeColor(QString color); + void initNodes(int numPoints); + void setPositiveColor(QString color); + void setNegativeColor(QString color); - void resizeCommands(); + void resizeCommands(); protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); void changeEvent(QEvent *event); - - }; #endif /* MIXERCURVEWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h index 55f19956d..6f828eb67 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -12,19 +12,24 @@ namespace Ui { class PopupWidget; } -class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog -{ +class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog { Q_OBJECT 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; } -signals: - + void popUp(QWidget *widget = 0); + void setWidget(QWidget *widget); + + QWidget *getWidget() + { + return m_widget; + } + + QHBoxLayout *getLayout() + { + return m_layout; + } + public slots: bool close(); void done(int result); @@ -33,12 +38,12 @@ private slots: void closePopup(); private: - QHBoxLayout* m_layout; - QWidget* m_widget; - QWidget* m_widgetParent; - QPushButton* m_closeButton; - int m_widgetWidth; - int m_widgetHeight; + QHBoxLayout *m_layout; + QWidget *m_widget; + QWidget *m_widgetParent; + QPushButton *m_closeButton; + int m_widgetWidth; + int m_widgetHeight; }; #endif // POPUPWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h index 03b96ff39..275ea3c44 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.h @@ -37,14 +37,15 @@ #include "uavobjectutilmanager.h" #include #include -class smartSaveButton:public QObject -{ - enum buttonTypeEnum {save_button,apply_button}; + +class smartSaveButton : public QObject { + enum buttonTypeEnum { save_button, apply_button }; public: Q_OBJECT + public: smartSaveButton(); - void addButtons(QPushButton * save,QPushButton * apply); + void addButtons(QPushButton *save, QPushButton *apply); void setObjects(QList); void addObject(UAVDataObject *); void clearObjects(); @@ -53,32 +54,34 @@ public: void addApplyButton(QPushButton *apply); void addSaveButton(QPushButton *save); void resetIcons(); + signals: void preProcessOperations(); void saveSuccessfull(); void beginOp(); void endOp(); + public slots: void apply(); void save(); + private slots: void processClick(); void processOperation(QPushButton *button, bool save); - void transaction_finished(UAVObject* obj, bool result); - void saving_finished(int,bool); + void transaction_finished(UAVObject *obj, bool result); + void saving_finished(int, bool); private: quint32 current_objectID; - UAVDataObject * current_object; + UAVDataObject *current_object; bool up_result; bool sv_result; QEventLoop loop; QList objects; - QMap buttonList; -protected: + QMap buttonList; + public slots: void enableControls(bool value); - }; From a334c49151ccd317d10e7c63a24e663ecded7980 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 5 May 2013 18:48:48 +0200 Subject: [PATCH 13/39] OP-935 Fixes the Instant Update functionality on the Stabilization settings pages in the configuration plugin. --- .../src/plugins/config/configstabilizationwidget.cpp | 10 ++++++---- .../src/plugins/config/configstabilizationwidget.h | 3 +++ 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index bf390b175..caf58e694 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -116,9 +116,11 @@ void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value) ui->realTimeUpdates_8->setChecked(value); if (value && !realtimeUpdates->isActive()) { - realtimeUpdates->start(300); - } else { + realtimeUpdates->start(AUTOMATIC_UPDATE_RATE); + qDebug() << "Instant Update timer started."; + } else if (!value && realtimeUpdates->isActive()) { realtimeUpdates->stop(); + qDebug() << "Instant Update timer stopped."; } } @@ -134,7 +136,7 @@ void ConfigStabilizationWidget::linkCheckBoxes(bool value) ui->checkBox_8->setChecked(value); } else if (sender() == ui->basicResponsivenessGroupBox) { ui->advancedResponsivenessGroupBox->setChecked(!value); - if(value) { + if (value) { processLinkedWidgets(ui->AttitudeResponsivenessSlider); processLinkedWidgets(ui->RateResponsivenessSlider); } @@ -181,7 +183,7 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget) } } - if(ui->basicResponsivenessGroupBox->isChecked()) { + if (ui->basicResponsivenessGroupBox->isChecked()) { if (widget == ui->AttitudeResponsivenessSlider) { ui->ratePitchKp_4->setValue(ui->AttitudeResponsivenessSlider->value()); } else if (widget == ui->RateResponsivenessSlider) { diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 8be034790..d728a877b 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -49,6 +49,9 @@ private: Ui_StabilizationWidget *ui; QTimer * realtimeUpdates; + // Milliseconds between automatic 'Instant Updates' + static const int AUTOMATIC_UPDATE_RATE = 500; + protected slots: void refreshWidgetsValues(UAVObject *o = NULL); From daee2de9181f74b46487412f62929875ea400a6e Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 5 May 2013 21:28:34 +0200 Subject: [PATCH 14/39] OP-935 Fixes Default settings button for Responsiveness on Basic page. --- ground/openpilotgcs/src/plugins/config/stabilization.ui | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index cedace74a..2c8676c20 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -652,6 +652,13 @@ Default + + + objname:StabilizationSettings + button:default + buttongroup:6 + + From 18798470f84281f88104e9c25cf5c31ccd832d98 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 5 May 2013 22:20:48 +0200 Subject: [PATCH 15/39] OP-935 Adds a 'Instant Update' check box on Advanced tab of Stabilization configuration. --- .../config/configstabilizationwidget.cpp | 3 + .../src/plugins/config/stabilization.ui | 68 +++++++++++++++---- 2 files changed, 57 insertions(+), 14 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index caf58e694..896801f16 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -61,6 +61,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa addWidget(ui->realTimeUpdates_6); connect(ui->realTimeUpdates_8, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); addWidget(ui->realTimeUpdates_8); + connect(ui->realTimeUpdates_12, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdatesSlot(bool))); + addWidget(ui->realTimeUpdates_12); connect(ui->checkBox_7, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool))); addWidget(ui->checkBox_7); @@ -114,6 +116,7 @@ void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value) { ui->realTimeUpdates_6->setChecked(value); ui->realTimeUpdates_8->setChecked(value); + ui->realTimeUpdates_12->setChecked(value); if (value && !realtimeUpdates->isActive()) { realtimeUpdates->start(AUTOMATIC_UPDATE_RATE); diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 2c8676c20..68cbb6ec6 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -652,13 +652,13 @@ Default - - - objname:StabilizationSettings - button:default - buttongroup:6 - - + + + objname:StabilizationSettings + button:default + buttongroup:6 + + @@ -9025,13 +9025,7 @@ border-radius: 5; true - - - 9 - - - 9 - + @@ -18836,6 +18830,52 @@ border-radius: 5; + + + + + 0 + 0 + + + + + 0 + 60 + + + + Instant Update + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + Enabling this feature mean that any changes made to the sliders will be instantly sent and used by the Flight Controller, useful for two person tuning where one normally flies and ones changes the GCS. + + + + + + Update flight controller in real time + + + + + + From bb87e6390e6d8fbca05f36659eaca17259622c40 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Mon, 6 May 2013 12:00:58 +0200 Subject: [PATCH 16/39] Update ppm_fresh if we receive a new PPM packet in order to keep the rfm22b receiver supervisor happy. --- flight/pios/common/pios_rfm22b.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/pios/common/pios_rfm22b.c b/flight/pios/common/pios_rfm22b.c index 203d8b1bb..a3542d946 100644 --- a/flight/pios/common/pios_rfm22b.c +++ b/flight/pios/common/pios_rfm22b.c @@ -2017,6 +2017,7 @@ static enum pios_radio_event radio_receivePacket(struct pios_rfm22b_dev *radio_d #endif #if defined(PIOS_INCLUDE_RFM22B_RCVR) ppm_output = true; + radio_dev->ppm_fresh = true; for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i) { radio_dev->ppm_channel[i] = ppmp->channels[i]; } From 938ed589180d1cf02005c3178296b65bf7f88fdf Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Mon, 6 May 2013 14:20:53 +0200 Subject: [PATCH 17/39] Corrected timout calculation formula. --- flight/pios/common/pios_rfm22b_rcvr.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/pios/common/pios_rfm22b_rcvr.c b/flight/pios/common/pios_rfm22b_rcvr.c index 3ea942103..e718e8481 100644 --- a/flight/pios/common/pios_rfm22b_rcvr.c +++ b/flight/pios/common/pios_rfm22b_rcvr.c @@ -102,7 +102,7 @@ static void PIOS_RFM22B_RCVR_Supervisor(uint32_t rcvr_id) { } // RTC runs at 625Hz. - if (++(rfm22b_dev->ppm_supv_timer) < (PIOS_RFM22B_RCVR_TIMEOUT_MS * 1000 / 625)) { + if (++(rfm22b_dev->ppm_supv_timer) < (PIOS_RFM22B_RCVR_TIMEOUT_MS * 625 / 1000)) { return; } rfm22b_dev->ppm_supv_timer = 0; From cc38ba0bdbde5a22320d67122d65676b5362da91 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Mon, 6 May 2013 14:26:25 +0200 Subject: [PATCH 18/39] Revert 8fa793 because it's obsoleted by 938ed5. --- flight/targets/boards/revolution/pios_board.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/targets/boards/revolution/pios_board.h b/flight/targets/boards/revolution/pios_board.h index ccf1effca..ef1434754 100644 --- a/flight/targets/boards/revolution/pios_board.h +++ b/flight/targets/boards/revolution/pios_board.h @@ -228,7 +228,7 @@ extern uint32_t pios_packet_handler; #define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 #define PIOS_GCSRCVR_TIMEOUT_MS 100 -#define PIOS_RFM22B_RCVR_TIMEOUT_MS 150 +#define PIOS_RFM22B_RCVR_TIMEOUT_MS 200 //------------------------- // Receiver PPM input From 914724d8c809ac5d98dff586670ee556d0a45070 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Tue, 7 May 2013 20:39:58 +0200 Subject: [PATCH 19/39] OP-935 Adds limits to Responsiveness settings. --- .../src/plugins/config/stabilization.ui | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 68cbb6ec6..b8a34e68f 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -1263,10 +1263,10 @@ border-radius: 5; 10 - 500 + 255 - 150 + 115 @@ -1288,7 +1288,7 @@ border-radius: 5; 800 - 450 + 400 Qt::Horizontal @@ -1345,7 +1345,7 @@ border-radius: 5; 800 - 300 + 400 @@ -2510,13 +2510,13 @@ border-radius: 5; 10 - 500 + 255 1 - 255 + 115 Qt::Horizontal @@ -2547,7 +2547,7 @@ border-radius: 5; 800 - 450 + 400 Qt::Horizontal @@ -2607,7 +2607,7 @@ border-radius: 5; 800 - 300 + 400 @@ -16581,7 +16581,7 @@ border-radius: 5; 0 - 1000000.000000000000000 + 255.000000000000000 1.000000000000000 @@ -16786,7 +16786,7 @@ border-radius: 5; 0 - 1000000.000000000000000 + 255.000000000000000 1.000000000000000 @@ -18717,7 +18717,7 @@ border-radius: 5; 0 - 1000000.000000000000000 + 255.000000000000000 1.000000000000000 From 7a727f549613f58d31a90f9e274cc3c1bfe03f57 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Tue, 7 May 2013 20:56:02 +0200 Subject: [PATCH 20/39] OP-935 Changes order of setting groups on Advanced tab in Stabilization settings page. --- .../src/plugins/config/stabilization.ui | 6710 ++++++++--------- 1 file changed, 3355 insertions(+), 3355 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index b8a34e68f..7bce2f777 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -9026,6 +9026,3349 @@ border-radius: 5; true + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 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 + + + + + + + + Responsiveness + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + true + + + false + + + + 12 + + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 632 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 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 + + + QGroupBox{border: 0px;} + + + + + + true + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 255.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 + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 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 + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 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 + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 255.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 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 + + + + + + + Attitude mode response (deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 140 + 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 + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 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 + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 255.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Rate mode response (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + + @@ -9561,7 +12904,7 @@ border-radius: 5; - Rate Stabilization Coefficients (Inner Loop) + Rate Stabilization (Inner Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -9576,16 +12919,6 @@ border-radius: 5; 6 - - - - - - - Link Roll and Pitch - - - @@ -9599,6 +12932,16 @@ border-radius: 5; + + + + + + + Link Roll and Pitch + + + @@ -12889,7 +16232,7 @@ Then lower the value by 20% or so. false - Attitude Stabilization Coefficients (Outer Loop) + Attitude Stabilization (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -15487,3349 +18830,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 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 Responsiveness - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - true - - - false - - - - 12 - - - 6 - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 632 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - - - - 0 - 0 - - - - - 0 - 140 - - - - - - - - - 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 - - - QGroupBox{border: 0px;} - - - - - - true - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 255.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 - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 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 - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 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 - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 255.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 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 - - - - - - - Attitude mode response (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 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 - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 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 - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - - 0 - - - 255.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - Rate mode response (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - - - From c5cbbf1c19cd5254e309077746277d3d2fefd594 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 9 May 2013 21:26:35 +0200 Subject: [PATCH 21/39] OP-944 : Improve Extended Kalman Filter generic formula to work roughly as fast as the auto generated code, remove autogenerated code. --- flight/libraries/insgps13state.c | 1054 +++--------------------------- 1 file changed, 90 insertions(+), 964 deletions(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index 7eca68a51..fe6a2fe98 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -39,11 +39,8 @@ #define NUMV 10 // number of measurements, v is the measurement noise vector #define NUMU 6 // number of deterministic inputs, U is the input vector -#if defined(GENERAL_COV) -// This might trick people so I have a note here. There is a slower but bigger version of the -// code here but won't fit when debugging disabled (requires -Os) -#define COVARIANCE_PREDICTION_GENERAL -#endif +#define MIN(a,b) ((a)<(b)?(a):(b)) +#define MAX(a,b) ((a)>(b)?(a):(b)) // Private functions void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], @@ -60,7 +57,37 @@ void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]); // Private variables float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices - // global to init to zero and maintain zero elements +// global to init to zero and maintain zero elements + +// speed optimizations, describe matrix sparsity +// derived from state equations in +// LinearizeFG() and LinearizeH(): +// +// usage F: usage G: usage H: (TODO) +// 0123456789abc 012345678 0123456789abc +// 0...X......... ......... X............ +// 1....X........ ......... .X........... +// 2.....X....... ......... ..X.......... +// 3......XXXX... ...XXX... ...X......... +// 4......XXXX... ...XXX... ....X........ +// 5......XXXX... ...XXX... .....X....... +// 6.......XXXXXX XXX...... ......XXXX... +// 7......X.XXXXX XXX...... ......XXXX... +// 8......XX.XXXX XXX...... ......XXXX... +// 9......XXX.XXX XXX...... ..X.......... +// a............. ......X.. +// b............. .......X. +// c............. ........X + +const int8_t FrowMin[NUMX] = { 3, 4, 5, 6, 6, 6, 7, 6, 6, 6,13,13,13 }; +const int8_t FrowMax[NUMX] = { 3, 4, 5, 9, 9, 9,12,12,12,12,-1,-1,-1 }; + +const int8_t GrowMin[NUMX] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 }; +const int8_t GrowMax[NUMX] = { -1,-1,-1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 }; + +const int8_t HrowMin[NUMV] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 }; +const int8_t HrowMax[NUMV] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 }; + float Be[3]; // local magnetic unit vector in NED frame float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector float Q[NUMW], R[NUMV]; // input noise and measurement noise variances @@ -397,973 +424,72 @@ void INSCorrection(float mag_data[3], float Pos[3], float Vel[3], // The first Method is very specific to this implementation // ************************************************ -#ifdef COVARIANCE_PREDICTION_GENERAL - +__attribute__((optimize("O3"))) void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]) { - float Dummy[NUMX][NUMX], dTsq; - uint8_t i, j, k; - // Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G' = T^2[(P/T + F*P)*(I/T + F') + G*Q*G')] + // Pnew = (I+F*T)*P*(I+F*T)' + T²*G*Q*G' = T²[(P/T + F*P)*(I/T + F') + G*Q*G')] - dTsq = dT * dT; + float dT1 = 1.0f / dT; // multiplication is faster than division on fpu. + float dTsq = dT * dT; - for (i = 0; i < NUMX; i++) // Calculate Dummy = (P/T +F*P) + float Dummy[NUMX][NUMX]; + int8_t i; + for (i = 0; i < NUMX; i++) { // Calculate Dummy = (P/T +F*P) + + float *Firow = F[i]; + float *Pirow = P[i]; + float *Dirow = Dummy[i]; + int8_t Fistart = FrowMin[i]; + int8_t Fiend = FrowMax[i]; + int8_t j; for (j = 0; j < NUMX; j++) { - Dummy[i][j] = P[i][j] / dT; - for (k = 0; k < NUMX; k++) - Dummy[i][j] += F[i][k] * P[k][j]; + + Dirow[j] = Pirow[j] * dT1; // Dummy = P / T ... + int8_t k; + for (k = Fistart; k <= Fiend; k++) { + Dirow[j] += Firow[k] * P[k][j]; // [] + F * P + } } - for (i = 0; i < NUMX; i++) // Calculate Pnew = Dummy/T + Dummy*F' + G*Qw*G' - for (j = i; j < NUMX; j++) { // Use symmetry, ie only find upper triangular - P[i][j] = Dummy[i][j] / dT; - for (k = 0; k < NUMX; k++) - P[i][j] += Dummy[i][k] * F[j][k]; // P = Dummy/T + Dummy*F' - for (k = 0; k < NUMW; k++) - P[i][j] += Q[k] * G[i][k] * G[j][k]; // P = Dummy/T + Dummy*F' + G*Q*G' - P[j][i] = P[i][j] = P[i][j] * dTsq; // Pnew = T^2*P and fill in lower triangular; + } + for (i = 0; i < NUMX; i++) { // Calculate Pnew = T² [Dummy/T + Dummy*F' + G*Qw*G'] + + float *Dirow = Dummy[i]; + float *Girow = G[i]; + float *Pirow = P[i]; + int8_t Gistart = GrowMin[i]; + int8_t Giend = GrowMax[i]; + int8_t j; + for (j = i; j < NUMX; j++) { // Use symmetry, ie only find upper triangular + + float Ptmp = Dirow[j] * dT1; // Pnew = Dummy / T ... + + { + float *Fjrow = F[j]; + int8_t Fjstart = FrowMin[j]; + int8_t Fjend = FrowMax[j]; + int8_t k; + for (k = Fjstart; k <= Fjend; k++) { + Ptmp += Dirow[k] * Fjrow[k]; // [] + Dummy*F' ... + } + } + + { + float *Gjrow = G[j]; + int8_t Gjstart = MAX(Gistart, GrowMin[j]); + int8_t Gjend = MIN(Giend, GrowMax[j]); + int8_t k; + for (k = Gjstart; k <= Gjend; k++) { + Ptmp += Q[k] * Girow[k] * Gjrow[k]; // [] + G*Q*G' ... + } + } + + P[j][i] = Pirow[j] = Ptmp * dTsq; // [] * T² } + } } -#else - -void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], - float Q[NUMW], float dT, float P[NUMX][NUMX]) -{ - float D[NUMX][NUMX], T, Tsq; - uint8_t i, j; - - // Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G' = scalar expansion from symbolic manipulator - - T = dT; - Tsq = dT * dT; - - for (i = 0; i < NUMX; i++) // Create a copy of the upper triangular of P - for (j = i; j < NUMX; j++) - D[i][j] = P[i][j]; - - // Brute force calculation of the elements of P - P[0][0] = D[3][3] * Tsq + (2 * D[0][3]) * T + D[0][0]; - P[0][1] = P[1][0] = - D[3][4] * Tsq + (D[0][4] + D[1][3]) * T + D[0][1]; - P[0][2] = P[2][0] = - D[3][5] * Tsq + (D[0][5] + D[2][3]) * T + D[0][2]; - P[0][3] = P[3][0] = - (F[3][6] * D[3][6] + F[3][7] * D[3][7] + F[3][8] * D[3][8] + - F[3][9] * D[3][9]) * Tsq + (D[3][3] + F[3][6] * D[0][6] + - F[3][7] * D[0][7] + - F[3][8] * D[0][8] + - F[3][9] * D[0][9]) * T + D[0][3]; - P[0][4] = P[4][0] = - (F[4][6] * D[3][6] + F[4][7] * D[3][7] + F[4][8] * D[3][8] + - F[4][9] * D[3][9]) * Tsq + (D[3][4] + F[4][6] * D[0][6] + - F[4][7] * D[0][7] + - F[4][8] * D[0][8] + - F[4][9] * D[0][9]) * T + D[0][4]; - P[0][5] = P[5][0] = - (F[5][6] * D[3][6] + F[5][7] * D[3][7] + F[5][8] * D[3][8] + - F[5][9] * D[3][9]) * Tsq + (D[3][5] + F[5][6] * D[0][6] + - F[5][7] * D[0][7] + - F[5][8] * D[0][8] + - F[5][9] * D[0][9]) * T + D[0][5]; - P[0][6] = P[6][0] = - (F[6][7] * D[3][7] + F[6][8] * D[3][8] + F[6][9] * D[3][9] + - F[6][10] * D[3][10] + F[6][11] * D[3][11] + - F[6][12] * D[3][12]) * Tsq + (D[3][6] + F[6][7] * D[0][7] + - F[6][8] * D[0][8] + - F[6][9] * D[0][9] + - F[6][10] * D[0][10] + - F[6][11] * D[0][11] + - F[6][12] * D[0][12]) * T + - D[0][6]; - P[0][7] = P[7][0] = - (F[7][6] * D[3][6] + F[7][8] * D[3][8] + F[7][9] * D[3][9] + - F[7][10] * D[3][10] + F[7][11] * D[3][11] + - F[7][12] * D[3][12]) * Tsq + (D[3][7] + F[7][6] * D[0][6] + - F[7][8] * D[0][8] + - F[7][9] * D[0][9] + - F[7][10] * D[0][10] + - F[7][11] * D[0][11] + - F[7][12] * D[0][12]) * T + - D[0][7]; - P[0][8] = P[8][0] = - (F[8][6] * D[3][6] + F[8][7] * D[3][7] + F[8][9] * D[3][9] + - F[8][10] * D[3][10] + F[8][11] * D[3][11] + - F[8][12] * D[3][12]) * Tsq + (D[3][8] + F[8][6] * D[0][6] + - F[8][7] * D[0][7] + - F[8][9] * D[0][9] + - F[8][10] * D[0][10] + - F[8][11] * D[0][11] + - F[8][12] * D[0][12]) * T + - D[0][8]; - P[0][9] = P[9][0] = - (F[9][6] * D[3][6] + F[9][7] * D[3][7] + F[9][8] * D[3][8] + - F[9][10] * D[3][10] + F[9][11] * D[3][11] + - F[9][12] * D[3][12]) * Tsq + (D[3][9] + F[9][6] * D[0][6] + - F[9][7] * D[0][7] + - F[9][8] * D[0][8] + - F[9][10] * D[0][10] + - F[9][11] * D[0][11] + - F[9][12] * D[0][12]) * T + - D[0][9]; - P[0][10] = P[10][0] = D[3][10] * T + D[0][10]; - P[0][11] = P[11][0] = D[3][11] * T + D[0][11]; - P[0][12] = P[12][0] = D[3][12] * T + D[0][12]; - P[1][1] = D[4][4] * Tsq + (2 * D[1][4]) * T + D[1][1]; - P[1][2] = P[2][1] = - D[4][5] * Tsq + (D[1][5] + D[2][4]) * T + D[1][2]; - P[1][3] = P[3][1] = - (F[3][6] * D[4][6] + F[3][7] * D[4][7] + F[3][8] * D[4][8] + - F[3][9] * D[4][9]) * Tsq + (D[3][4] + F[3][6] * D[1][6] + - F[3][7] * D[1][7] + - F[3][8] * D[1][8] + - F[3][9] * D[1][9]) * T + D[1][3]; - P[1][4] = P[4][1] = - (F[4][6] * D[4][6] + F[4][7] * D[4][7] + F[4][8] * D[4][8] + - F[4][9] * D[4][9]) * Tsq + (D[4][4] + F[4][6] * D[1][6] + - F[4][7] * D[1][7] + - F[4][8] * D[1][8] + - F[4][9] * D[1][9]) * T + D[1][4]; - P[1][5] = P[5][1] = - (F[5][6] * D[4][6] + F[5][7] * D[4][7] + F[5][8] * D[4][8] + - F[5][9] * D[4][9]) * Tsq + (D[4][5] + F[5][6] * D[1][6] + - F[5][7] * D[1][7] + - F[5][8] * D[1][8] + - F[5][9] * D[1][9]) * T + D[1][5]; - P[1][6] = P[6][1] = - (F[6][7] * D[4][7] + F[6][8] * D[4][8] + F[6][9] * D[4][9] + - F[6][10] * D[4][10] + F[6][11] * D[4][11] + - F[6][12] * D[4][12]) * Tsq + (D[4][6] + F[6][7] * D[1][7] + - F[6][8] * D[1][8] + - F[6][9] * D[1][9] + - F[6][10] * D[1][10] + - F[6][11] * D[1][11] + - F[6][12] * D[1][12]) * T + - D[1][6]; - P[1][7] = P[7][1] = - (F[7][6] * D[4][6] + F[7][8] * D[4][8] + F[7][9] * D[4][9] + - F[7][10] * D[4][10] + F[7][11] * D[4][11] + - F[7][12] * D[4][12]) * Tsq + (D[4][7] + F[7][6] * D[1][6] + - F[7][8] * D[1][8] + - F[7][9] * D[1][9] + - F[7][10] * D[1][10] + - F[7][11] * D[1][11] + - F[7][12] * D[1][12]) * T + - D[1][7]; - P[1][8] = P[8][1] = - (F[8][6] * D[4][6] + F[8][7] * D[4][7] + F[8][9] * D[4][9] + - F[8][10] * D[4][10] + F[8][11] * D[4][11] + - F[8][12] * D[4][12]) * Tsq + (D[4][8] + F[8][6] * D[1][6] + - F[8][7] * D[1][7] + - F[8][9] * D[1][9] + - F[8][10] * D[1][10] + - F[8][11] * D[1][11] + - F[8][12] * D[1][12]) * T + - D[1][8]; - P[1][9] = P[9][1] = - (F[9][6] * D[4][6] + F[9][7] * D[4][7] + F[9][8] * D[4][8] + - F[9][10] * D[4][10] + F[9][11] * D[4][11] + - F[9][12] * D[4][12]) * Tsq + (D[4][9] + F[9][6] * D[1][6] + - F[9][7] * D[1][7] + - F[9][8] * D[1][8] + - F[9][10] * D[1][10] + - F[9][11] * D[1][11] + - F[9][12] * D[1][12]) * T + - D[1][9]; - P[1][10] = P[10][1] = D[4][10] * T + D[1][10]; - P[1][11] = P[11][1] = D[4][11] * T + D[1][11]; - P[1][12] = P[12][1] = D[4][12] * T + D[1][12]; - P[2][2] = D[5][5] * Tsq + (2 * D[2][5]) * T + D[2][2]; - P[2][3] = P[3][2] = - (F[3][6] * D[5][6] + F[3][7] * D[5][7] + F[3][8] * D[5][8] + - F[3][9] * D[5][9]) * Tsq + (D[3][5] + F[3][6] * D[2][6] + - F[3][7] * D[2][7] + - F[3][8] * D[2][8] + - F[3][9] * D[2][9]) * T + D[2][3]; - P[2][4] = P[4][2] = - (F[4][6] * D[5][6] + F[4][7] * D[5][7] + F[4][8] * D[5][8] + - F[4][9] * D[5][9]) * Tsq + (D[4][5] + F[4][6] * D[2][6] + - F[4][7] * D[2][7] + - F[4][8] * D[2][8] + - F[4][9] * D[2][9]) * T + D[2][4]; - P[2][5] = P[5][2] = - (F[5][6] * D[5][6] + F[5][7] * D[5][7] + F[5][8] * D[5][8] + - F[5][9] * D[5][9]) * Tsq + (D[5][5] + F[5][6] * D[2][6] + - F[5][7] * D[2][7] + - F[5][8] * D[2][8] + - F[5][9] * D[2][9]) * T + D[2][5]; - P[2][6] = P[6][2] = - (F[6][7] * D[5][7] + F[6][8] * D[5][8] + F[6][9] * D[5][9] + - F[6][10] * D[5][10] + F[6][11] * D[5][11] + - F[6][12] * D[5][12]) * Tsq + (D[5][6] + F[6][7] * D[2][7] + - F[6][8] * D[2][8] + - F[6][9] * D[2][9] + - F[6][10] * D[2][10] + - F[6][11] * D[2][11] + - F[6][12] * D[2][12]) * T + - D[2][6]; - P[2][7] = P[7][2] = - (F[7][6] * D[5][6] + F[7][8] * D[5][8] + F[7][9] * D[5][9] + - F[7][10] * D[5][10] + F[7][11] * D[5][11] + - F[7][12] * D[5][12]) * Tsq + (D[5][7] + F[7][6] * D[2][6] + - F[7][8] * D[2][8] + - F[7][9] * D[2][9] + - F[7][10] * D[2][10] + - F[7][11] * D[2][11] + - F[7][12] * D[2][12]) * T + - D[2][7]; - P[2][8] = P[8][2] = - (F[8][6] * D[5][6] + F[8][7] * D[5][7] + F[8][9] * D[5][9] + - F[8][10] * D[5][10] + F[8][11] * D[5][11] + - F[8][12] * D[5][12]) * Tsq + (D[5][8] + F[8][6] * D[2][6] + - F[8][7] * D[2][7] + - F[8][9] * D[2][9] + - F[8][10] * D[2][10] + - F[8][11] * D[2][11] + - F[8][12] * D[2][12]) * T + - D[2][8]; - P[2][9] = P[9][2] = - (F[9][6] * D[5][6] + F[9][7] * D[5][7] + F[9][8] * D[5][8] + - F[9][10] * D[5][10] + F[9][11] * D[5][11] + - F[9][12] * D[5][12]) * Tsq + (D[5][9] + F[9][6] * D[2][6] + - F[9][7] * D[2][7] + - F[9][8] * D[2][8] + - F[9][10] * D[2][10] + - F[9][11] * D[2][11] + - F[9][12] * D[2][12]) * T + - D[2][9]; - P[2][10] = P[10][2] = D[5][10] * T + D[2][10]; - P[2][11] = P[11][2] = D[5][11] * T + D[2][11]; - P[2][12] = P[12][2] = D[5][12] * T + D[2][12]; - P[3][3] = - (Q[3] * G[3][3] * G[3][3] + Q[4] * G[3][4] * G[3][4] + - Q[5] * G[3][5] * G[3][5] + F[3][9] * (F[3][9] * D[9][9] + - F[3][6] * D[6][9] + - F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + - F[3][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] + - F[3][8] * D[6][8] + F[3][9] * D[6][9]) + - F[3][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9]) + - F[3][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq + - (2 * F[3][6] * D[3][6] + 2 * F[3][7] * D[3][7] + - 2 * F[3][8] * D[3][8] + 2 * F[3][9] * D[3][9]) * T + D[3][3]; - P[3][4] = P[4][3] = - (F[4][9] * - (F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + F[4][6] * (F[3][6] * D[6][6] + - F[3][7] * D[6][7] + - F[3][8] * D[6][8] + - F[3][9] * D[6][9]) + - F[4][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9]) + - F[4][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9]) + - G[3][3] * G[4][3] * Q[3] + G[3][4] * G[4][4] * Q[4] + - G[3][5] * G[4][5] * Q[5]) * Tsq + (F[3][6] * D[4][6] + - F[4][6] * D[3][6] + - F[3][7] * D[4][7] + - F[4][7] * D[3][7] + - F[3][8] * D[4][8] + - F[4][8] * D[3][8] + - F[3][9] * D[4][9] + - F[4][9] * D[3][9]) * T + - D[3][4]; - P[3][5] = P[5][3] = - (F[5][9] * - (F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + F[5][6] * (F[3][6] * D[6][6] + - F[3][7] * D[6][7] + - F[3][8] * D[6][8] + - F[3][9] * D[6][9]) + - F[5][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9]) + - F[5][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9]) + - G[3][3] * G[5][3] * Q[3] + G[3][4] * G[5][4] * Q[4] + - G[3][5] * G[5][5] * Q[5]) * Tsq + (F[3][6] * D[5][6] + - F[5][6] * D[3][6] + - F[3][7] * D[5][7] + - F[5][7] * D[3][7] + - F[3][8] * D[5][8] + - F[5][8] * D[3][8] + - F[3][9] * D[5][9] + - F[5][9] * D[3][9]) * T + - D[3][5]; - P[3][6] = P[6][3] = - (F[6][9] * - (F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + F[6][10] * (F[3][9] * D[9][10] + - F[3][6] * D[6][10] + - F[3][7] * D[7][10] + - F[3][8] * D[8][10]) + - F[6][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] + - F[3][7] * D[7][11] + F[3][8] * D[8][11]) + - F[6][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] + - F[3][7] * D[7][12] + F[3][8] * D[8][12]) + - F[6][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9]) + - F[6][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq + - (F[3][6] * D[6][6] + F[3][7] * D[6][7] + F[6][7] * D[3][7] + - F[3][8] * D[6][8] + F[6][8] * D[3][8] + F[3][9] * D[6][9] + - F[6][9] * D[3][9] + F[6][10] * D[3][10] + - F[6][11] * D[3][11] + F[6][12] * D[3][12]) * T + D[3][6]; - P[3][7] = P[7][3] = - (F[7][9] * - (F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + F[7][10] * (F[3][9] * D[9][10] + - F[3][6] * D[6][10] + - F[3][7] * D[7][10] + - F[3][8] * D[8][10]) + - F[7][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] + - F[3][7] * D[7][11] + F[3][8] * D[8][11]) + - F[7][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] + - F[3][7] * D[7][12] + F[3][8] * D[8][12]) + - F[7][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] + - F[3][8] * D[6][8] + F[3][9] * D[6][9]) + - F[7][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq + - (F[3][6] * D[6][7] + F[7][6] * D[3][6] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[7][8] * D[3][8] + F[3][9] * D[7][9] + - F[7][9] * D[3][9] + F[7][10] * D[3][10] + - F[7][11] * D[3][11] + F[7][12] * D[3][12]) * T + D[3][7]; - P[3][8] = P[8][3] = - (F[8][9] * - (F[3][9] * D[9][9] + F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) + F[8][10] * (F[3][9] * D[9][10] + - F[3][6] * D[6][10] + - F[3][7] * D[7][10] + - F[3][8] * D[8][10]) + - F[8][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] + - F[3][7] * D[7][11] + F[3][8] * D[8][11]) + - F[8][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] + - F[3][7] * D[7][12] + F[3][8] * D[8][12]) + - F[8][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] + - F[3][8] * D[6][8] + F[3][9] * D[6][9]) + - F[8][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9])) * Tsq + - (F[3][6] * D[6][8] + F[3][7] * D[7][8] + F[8][6] * D[3][6] + - F[8][7] * D[3][7] + F[3][8] * D[8][8] + F[3][9] * D[8][9] + - F[8][9] * D[3][9] + F[8][10] * D[3][10] + - F[8][11] * D[3][11] + F[8][12] * D[3][12]) * T + D[3][8]; - P[3][9] = P[9][3] = - (F[9][10] * - (F[3][9] * D[9][10] + F[3][6] * D[6][10] + - F[3][7] * D[7][10] + F[3][8] * D[8][10]) + - F[9][11] * (F[3][9] * D[9][11] + F[3][6] * D[6][11] + - F[3][7] * D[7][11] + F[3][8] * D[8][11]) + - F[9][12] * (F[3][9] * D[9][12] + F[3][6] * D[6][12] + - F[3][7] * D[7][12] + F[3][8] * D[8][12]) + - F[9][6] * (F[3][6] * D[6][6] + F[3][7] * D[6][7] + - F[3][8] * D[6][8] + F[3][9] * D[6][9]) + - F[9][7] * (F[3][6] * D[6][7] + F[3][7] * D[7][7] + - F[3][8] * D[7][8] + F[3][9] * D[7][9]) + - F[9][8] * (F[3][6] * D[6][8] + F[3][7] * D[7][8] + - F[3][8] * D[8][8] + F[3][9] * D[8][9])) * Tsq + - (F[9][6] * D[3][6] + F[9][7] * D[3][7] + F[9][8] * D[3][8] + - F[3][9] * D[9][9] + F[9][10] * D[3][10] + - F[9][11] * D[3][11] + F[9][12] * D[3][12] + - F[3][6] * D[6][9] + F[3][7] * D[7][9] + - F[3][8] * D[8][9]) * T + D[3][9]; - P[3][10] = P[10][3] = - (F[3][9] * D[9][10] + F[3][6] * D[6][10] + F[3][7] * D[7][10] + - F[3][8] * D[8][10]) * T + D[3][10]; - P[3][11] = P[11][3] = - (F[3][9] * D[9][11] + F[3][6] * D[6][11] + F[3][7] * D[7][11] + - F[3][8] * D[8][11]) * T + D[3][11]; - P[3][12] = P[12][3] = - (F[3][9] * D[9][12] + F[3][6] * D[6][12] + F[3][7] * D[7][12] + - F[3][8] * D[8][12]) * T + D[3][12]; - P[4][4] = - (Q[3] * G[4][3] * G[4][3] + Q[4] * G[4][4] * G[4][4] + - Q[5] * G[4][5] * G[4][5] + F[4][9] * (F[4][9] * D[9][9] + - F[4][6] * D[6][9] + - F[4][7] * D[7][9] + - F[4][8] * D[8][9]) + - F[4][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] + - F[4][8] * D[6][8] + F[4][9] * D[6][9]) + - F[4][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[4][9] * D[7][9]) + - F[4][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] + - F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq + - (2 * F[4][6] * D[4][6] + 2 * F[4][7] * D[4][7] + - 2 * F[4][8] * D[4][8] + 2 * F[4][9] * D[4][9]) * T + D[4][4]; - P[4][5] = P[5][4] = - (F[5][9] * - (F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] + - F[4][8] * D[8][9]) + F[5][6] * (F[4][6] * D[6][6] + - F[4][7] * D[6][7] + - F[4][8] * D[6][8] + - F[4][9] * D[6][9]) + - F[5][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[4][9] * D[7][9]) + - F[5][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] + - F[4][8] * D[8][8] + F[4][9] * D[8][9]) + - G[4][3] * G[5][3] * Q[3] + G[4][4] * G[5][4] * Q[4] + - G[4][5] * G[5][5] * Q[5]) * Tsq + (F[4][6] * D[5][6] + - F[5][6] * D[4][6] + - F[4][7] * D[5][7] + - F[5][7] * D[4][7] + - F[4][8] * D[5][8] + - F[5][8] * D[4][8] + - F[4][9] * D[5][9] + - F[5][9] * D[4][9]) * T + - D[4][5]; - P[4][6] = P[6][4] = - (F[6][9] * - (F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] + - F[4][8] * D[8][9]) + F[6][10] * (F[4][9] * D[9][10] + - F[4][6] * D[6][10] + - F[4][7] * D[7][10] + - F[4][8] * D[8][10]) + - F[6][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] + - F[4][7] * D[7][11] + F[4][8] * D[8][11]) + - F[6][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] + - F[4][7] * D[7][12] + F[4][8] * D[8][12]) + - F[6][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[4][9] * D[7][9]) + - F[6][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] + - F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq + - (F[4][6] * D[6][6] + F[4][7] * D[6][7] + F[6][7] * D[4][7] + - F[4][8] * D[6][8] + F[6][8] * D[4][8] + F[4][9] * D[6][9] + - F[6][9] * D[4][9] + F[6][10] * D[4][10] + - F[6][11] * D[4][11] + F[6][12] * D[4][12]) * T + D[4][6]; - P[4][7] = P[7][4] = - (F[7][9] * - (F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] + - F[4][8] * D[8][9]) + F[7][10] * (F[4][9] * D[9][10] + - F[4][6] * D[6][10] + - F[4][7] * D[7][10] + - F[4][8] * D[8][10]) + - F[7][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] + - F[4][7] * D[7][11] + F[4][8] * D[8][11]) + - F[7][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] + - F[4][7] * D[7][12] + F[4][8] * D[8][12]) + - F[7][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] + - F[4][8] * D[6][8] + F[4][9] * D[6][9]) + - F[7][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] + - F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq + - (F[4][6] * D[6][7] + F[7][6] * D[4][6] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[7][8] * D[4][8] + F[4][9] * D[7][9] + - F[7][9] * D[4][9] + F[7][10] * D[4][10] + - F[7][11] * D[4][11] + F[7][12] * D[4][12]) * T + D[4][7]; - P[4][8] = P[8][4] = - (F[8][9] * - (F[4][9] * D[9][9] + F[4][6] * D[6][9] + F[4][7] * D[7][9] + - F[4][8] * D[8][9]) + F[8][10] * (F[4][9] * D[9][10] + - F[4][6] * D[6][10] + - F[4][7] * D[7][10] + - F[4][8] * D[8][10]) + - F[8][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] + - F[4][7] * D[7][11] + F[4][8] * D[8][11]) + - F[8][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] + - F[4][7] * D[7][12] + F[4][8] * D[8][12]) + - F[8][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] + - F[4][8] * D[6][8] + F[4][9] * D[6][9]) + - F[8][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[4][9] * D[7][9])) * Tsq + - (F[4][6] * D[6][8] + F[4][7] * D[7][8] + F[8][6] * D[4][6] + - F[8][7] * D[4][7] + F[4][8] * D[8][8] + F[4][9] * D[8][9] + - F[8][9] * D[4][9] + F[8][10] * D[4][10] + - F[8][11] * D[4][11] + F[8][12] * D[4][12]) * T + D[4][8]; - P[4][9] = P[9][4] = - (F[9][10] * - (F[4][9] * D[9][10] + F[4][6] * D[6][10] + - F[4][7] * D[7][10] + F[4][8] * D[8][10]) + - F[9][11] * (F[4][9] * D[9][11] + F[4][6] * D[6][11] + - F[4][7] * D[7][11] + F[4][8] * D[8][11]) + - F[9][12] * (F[4][9] * D[9][12] + F[4][6] * D[6][12] + - F[4][7] * D[7][12] + F[4][8] * D[8][12]) + - F[9][6] * (F[4][6] * D[6][6] + F[4][7] * D[6][7] + - F[4][8] * D[6][8] + F[4][9] * D[6][9]) + - F[9][7] * (F[4][6] * D[6][7] + F[4][7] * D[7][7] + - F[4][8] * D[7][8] + F[4][9] * D[7][9]) + - F[9][8] * (F[4][6] * D[6][8] + F[4][7] * D[7][8] + - F[4][8] * D[8][8] + F[4][9] * D[8][9])) * Tsq + - (F[9][6] * D[4][6] + F[9][7] * D[4][7] + F[9][8] * D[4][8] + - F[4][9] * D[9][9] + F[9][10] * D[4][10] + - F[9][11] * D[4][11] + F[9][12] * D[4][12] + - F[4][6] * D[6][9] + F[4][7] * D[7][9] + - F[4][8] * D[8][9]) * T + D[4][9]; - P[4][10] = P[10][4] = - (F[4][9] * D[9][10] + F[4][6] * D[6][10] + F[4][7] * D[7][10] + - F[4][8] * D[8][10]) * T + D[4][10]; - P[4][11] = P[11][4] = - (F[4][9] * D[9][11] + F[4][6] * D[6][11] + F[4][7] * D[7][11] + - F[4][8] * D[8][11]) * T + D[4][11]; - P[4][12] = P[12][4] = - (F[4][9] * D[9][12] + F[4][6] * D[6][12] + F[4][7] * D[7][12] + - F[4][8] * D[8][12]) * T + D[4][12]; - P[5][5] = - (Q[3] * G[5][3] * G[5][3] + Q[4] * G[5][4] * G[5][4] + - Q[5] * G[5][5] * G[5][5] + F[5][9] * (F[5][9] * D[9][9] + - F[5][6] * D[6][9] + - F[5][7] * D[7][9] + - F[5][8] * D[8][9]) + - F[5][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] + - F[5][8] * D[6][8] + F[5][9] * D[6][9]) + - F[5][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] + - F[5][8] * D[7][8] + F[5][9] * D[7][9]) + - F[5][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] + - F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq + - (2 * F[5][6] * D[5][6] + 2 * F[5][7] * D[5][7] + - 2 * F[5][8] * D[5][8] + 2 * F[5][9] * D[5][9]) * T + D[5][5]; - P[5][6] = P[6][5] = - (F[6][9] * - (F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] + - F[5][8] * D[8][9]) + F[6][10] * (F[5][9] * D[9][10] + - F[5][6] * D[6][10] + - F[5][7] * D[7][10] + - F[5][8] * D[8][10]) + - F[6][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] + - F[5][7] * D[7][11] + F[5][8] * D[8][11]) + - F[6][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] + - F[5][7] * D[7][12] + F[5][8] * D[8][12]) + - F[6][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] + - F[5][8] * D[7][8] + F[5][9] * D[7][9]) + - F[6][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] + - F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq + - (F[5][6] * D[6][6] + F[5][7] * D[6][7] + F[6][7] * D[5][7] + - F[5][8] * D[6][8] + F[6][8] * D[5][8] + F[5][9] * D[6][9] + - F[6][9] * D[5][9] + F[6][10] * D[5][10] + - F[6][11] * D[5][11] + F[6][12] * D[5][12]) * T + D[5][6]; - P[5][7] = P[7][5] = - (F[7][9] * - (F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] + - F[5][8] * D[8][9]) + F[7][10] * (F[5][9] * D[9][10] + - F[5][6] * D[6][10] + - F[5][7] * D[7][10] + - F[5][8] * D[8][10]) + - F[7][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] + - F[5][7] * D[7][11] + F[5][8] * D[8][11]) + - F[7][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] + - F[5][7] * D[7][12] + F[5][8] * D[8][12]) + - F[7][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] + - F[5][8] * D[6][8] + F[5][9] * D[6][9]) + - F[7][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] + - F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq + - (F[5][6] * D[6][7] + F[7][6] * D[5][6] + F[5][7] * D[7][7] + - F[5][8] * D[7][8] + F[7][8] * D[5][8] + F[5][9] * D[7][9] + - F[7][9] * D[5][9] + F[7][10] * D[5][10] + - F[7][11] * D[5][11] + F[7][12] * D[5][12]) * T + D[5][7]; - P[5][8] = P[8][5] = - (F[8][9] * - (F[5][9] * D[9][9] + F[5][6] * D[6][9] + F[5][7] * D[7][9] + - F[5][8] * D[8][9]) + F[8][10] * (F[5][9] * D[9][10] + - F[5][6] * D[6][10] + - F[5][7] * D[7][10] + - F[5][8] * D[8][10]) + - F[8][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] + - F[5][7] * D[7][11] + F[5][8] * D[8][11]) + - F[8][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] + - F[5][7] * D[7][12] + F[5][8] * D[8][12]) + - F[8][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] + - F[5][8] * D[6][8] + F[5][9] * D[6][9]) + - F[8][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] + - F[5][8] * D[7][8] + F[5][9] * D[7][9])) * Tsq + - (F[5][6] * D[6][8] + F[5][7] * D[7][8] + F[8][6] * D[5][6] + - F[8][7] * D[5][7] + F[5][8] * D[8][8] + F[5][9] * D[8][9] + - F[8][9] * D[5][9] + F[8][10] * D[5][10] + - F[8][11] * D[5][11] + F[8][12] * D[5][12]) * T + D[5][8]; - P[5][9] = P[9][5] = - (F[9][10] * - (F[5][9] * D[9][10] + F[5][6] * D[6][10] + - F[5][7] * D[7][10] + F[5][8] * D[8][10]) + - F[9][11] * (F[5][9] * D[9][11] + F[5][6] * D[6][11] + - F[5][7] * D[7][11] + F[5][8] * D[8][11]) + - F[9][12] * (F[5][9] * D[9][12] + F[5][6] * D[6][12] + - F[5][7] * D[7][12] + F[5][8] * D[8][12]) + - F[9][6] * (F[5][6] * D[6][6] + F[5][7] * D[6][7] + - F[5][8] * D[6][8] + F[5][9] * D[6][9]) + - F[9][7] * (F[5][6] * D[6][7] + F[5][7] * D[7][7] + - F[5][8] * D[7][8] + F[5][9] * D[7][9]) + - F[9][8] * (F[5][6] * D[6][8] + F[5][7] * D[7][8] + - F[5][8] * D[8][8] + F[5][9] * D[8][9])) * Tsq + - (F[9][6] * D[5][6] + F[9][7] * D[5][7] + F[9][8] * D[5][8] + - F[5][9] * D[9][9] + F[9][10] * D[5][10] + - F[9][11] * D[5][11] + F[9][12] * D[5][12] + - F[5][6] * D[6][9] + F[5][7] * D[7][9] + - F[5][8] * D[8][9]) * T + D[5][9]; - P[5][10] = P[10][5] = - (F[5][9] * D[9][10] + F[5][6] * D[6][10] + F[5][7] * D[7][10] + - F[5][8] * D[8][10]) * T + D[5][10]; - P[5][11] = P[11][5] = - (F[5][9] * D[9][11] + F[5][6] * D[6][11] + F[5][7] * D[7][11] + - F[5][8] * D[8][11]) * T + D[5][11]; - P[5][12] = P[12][5] = - (F[5][9] * D[9][12] + F[5][6] * D[6][12] + F[5][7] * D[7][12] + - F[5][8] * D[8][12]) * T + D[5][12]; - P[6][6] = - (Q[0] * G[6][0] * G[6][0] + Q[1] * G[6][1] * G[6][1] + - Q[2] * G[6][2] * G[6][2] + F[6][9] * (F[6][9] * D[9][9] + - F[6][10] * D[9][10] + - F[6][11] * D[9][11] + - F[6][12] * D[9][12] + - F[6][7] * D[7][9] + - F[6][8] * D[8][9]) + - F[6][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] + - F[6][11] * D[10][11] + F[6][12] * D[10][12] + - F[6][7] * D[7][10] + F[6][8] * D[8][10]) + - F[6][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] + - F[6][11] * D[11][11] + F[6][12] * D[11][12] + - F[6][7] * D[7][11] + F[6][8] * D[8][11]) + - F[6][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] + - F[6][11] * D[11][12] + F[6][12] * D[12][12] + - F[6][7] * D[7][12] + F[6][8] * D[8][12]) + - F[6][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] + - F[6][9] * D[7][9] + F[6][10] * D[7][10] + - F[6][11] * D[7][11] + F[6][12] * D[7][12]) + - F[6][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] + - F[6][9] * D[8][9] + F[6][10] * D[8][10] + - F[6][11] * D[8][11] + F[6][12] * D[8][12])) * Tsq + - (2 * F[6][7] * D[6][7] + 2 * F[6][8] * D[6][8] + - 2 * F[6][9] * D[6][9] + 2 * F[6][10] * D[6][10] + - 2 * F[6][11] * D[6][11] + 2 * F[6][12] * D[6][12]) * T + - D[6][6]; - P[6][7] = P[7][6] = - (F[7][9] * - (F[6][9] * D[9][9] + F[6][10] * D[9][10] + - F[6][11] * D[9][11] + F[6][12] * D[9][12] + - F[6][7] * D[7][9] + F[6][8] * D[8][9]) + - F[7][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] + - F[6][11] * D[10][11] + F[6][12] * D[10][12] + - F[6][7] * D[7][10] + F[6][8] * D[8][10]) + - F[7][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] + - F[6][11] * D[11][11] + F[6][12] * D[11][12] + - F[6][7] * D[7][11] + F[6][8] * D[8][11]) + - F[7][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] + - F[6][11] * D[11][12] + F[6][12] * D[12][12] + - F[6][7] * D[7][12] + F[6][8] * D[8][12]) + - F[7][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] + - F[6][9] * D[6][9] + F[6][10] * D[6][10] + - F[6][11] * D[6][11] + F[6][12] * D[6][12]) + - F[7][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] + - F[6][9] * D[8][9] + F[6][10] * D[8][10] + - F[6][11] * D[8][11] + F[6][12] * D[8][12]) + - G[6][0] * G[7][0] * Q[0] + G[6][1] * G[7][1] * Q[1] + - G[6][2] * G[7][2] * Q[2]) * Tsq + (F[7][6] * D[6][6] + - F[6][7] * D[7][7] + - F[6][8] * D[7][8] + - F[7][8] * D[6][8] + - F[6][9] * D[7][9] + - F[7][9] * D[6][9] + - F[6][10] * D[7][10] + - F[7][10] * D[6][10] + - F[6][11] * D[7][11] + - F[7][11] * D[6][11] + - F[6][12] * D[7][12] + - F[7][12] * D[6][12]) * T + - D[6][7]; - P[6][8] = P[8][6] = - (F[8][9] * - (F[6][9] * D[9][9] + F[6][10] * D[9][10] + - F[6][11] * D[9][11] + F[6][12] * D[9][12] + - F[6][7] * D[7][9] + F[6][8] * D[8][9]) + - F[8][10] * (F[6][9] * D[9][10] + F[6][10] * D[10][10] + - F[6][11] * D[10][11] + F[6][12] * D[10][12] + - F[6][7] * D[7][10] + F[6][8] * D[8][10]) + - F[8][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] + - F[6][11] * D[11][11] + F[6][12] * D[11][12] + - F[6][7] * D[7][11] + F[6][8] * D[8][11]) + - F[8][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] + - F[6][11] * D[11][12] + F[6][12] * D[12][12] + - F[6][7] * D[7][12] + F[6][8] * D[8][12]) + - F[8][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] + - F[6][9] * D[6][9] + F[6][10] * D[6][10] + - F[6][11] * D[6][11] + F[6][12] * D[6][12]) + - F[8][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] + - F[6][9] * D[7][9] + F[6][10] * D[7][10] + - F[6][11] * D[7][11] + F[6][12] * D[7][12]) + - G[6][0] * G[8][0] * Q[0] + G[6][1] * G[8][1] * Q[1] + - G[6][2] * G[8][2] * Q[2]) * Tsq + (F[6][7] * D[7][8] + - F[8][6] * D[6][6] + - F[8][7] * D[6][7] + - F[6][8] * D[8][8] + - F[6][9] * D[8][9] + - F[8][9] * D[6][9] + - F[6][10] * D[8][10] + - F[8][10] * D[6][10] + - F[6][11] * D[8][11] + - F[8][11] * D[6][11] + - F[6][12] * D[8][12] + - F[8][12] * D[6][12]) * T + - D[6][8]; - P[6][9] = P[9][6] = - (F[9][10] * - (F[6][9] * D[9][10] + F[6][10] * D[10][10] + - F[6][11] * D[10][11] + F[6][12] * D[10][12] + - F[6][7] * D[7][10] + F[6][8] * D[8][10]) + - F[9][11] * (F[6][9] * D[9][11] + F[6][10] * D[10][11] + - F[6][11] * D[11][11] + F[6][12] * D[11][12] + - F[6][7] * D[7][11] + F[6][8] * D[8][11]) + - F[9][12] * (F[6][9] * D[9][12] + F[6][10] * D[10][12] + - F[6][11] * D[11][12] + F[6][12] * D[12][12] + - F[6][7] * D[7][12] + F[6][8] * D[8][12]) + - F[9][6] * (F[6][7] * D[6][7] + F[6][8] * D[6][8] + - F[6][9] * D[6][9] + F[6][10] * D[6][10] + - F[6][11] * D[6][11] + F[6][12] * D[6][12]) + - F[9][7] * (F[6][7] * D[7][7] + F[6][8] * D[7][8] + - F[6][9] * D[7][9] + F[6][10] * D[7][10] + - F[6][11] * D[7][11] + F[6][12] * D[7][12]) + - F[9][8] * (F[6][7] * D[7][8] + F[6][8] * D[8][8] + - F[6][9] * D[8][9] + F[6][10] * D[8][10] + - F[6][11] * D[8][11] + F[6][12] * D[8][12]) + - G[9][0] * G[6][0] * Q[0] + G[9][1] * G[6][1] * Q[1] + - G[9][2] * G[6][2] * Q[2]) * Tsq + (F[9][6] * D[6][6] + - F[9][7] * D[6][7] + - F[9][8] * D[6][8] + - F[6][9] * D[9][9] + - F[9][10] * D[6][10] + - F[6][10] * D[9][10] + - F[9][11] * D[6][11] + - F[6][11] * D[9][11] + - F[9][12] * D[6][12] + - F[6][12] * D[9][12] + - F[6][7] * D[7][9] + - F[6][8] * D[8][9]) * T + - D[6][9]; - P[6][10] = P[10][6] = - (F[6][9] * D[9][10] + F[6][10] * D[10][10] + - F[6][11] * D[10][11] + F[6][12] * D[10][12] + - F[6][7] * D[7][10] + F[6][8] * D[8][10]) * T + D[6][10]; - P[6][11] = P[11][6] = - (F[6][9] * D[9][11] + F[6][10] * D[10][11] + - F[6][11] * D[11][11] + F[6][12] * D[11][12] + - F[6][7] * D[7][11] + F[6][8] * D[8][11]) * T + D[6][11]; - P[6][12] = P[12][6] = - (F[6][9] * D[9][12] + F[6][10] * D[10][12] + - F[6][11] * D[11][12] + F[6][12] * D[12][12] + - F[6][7] * D[7][12] + F[6][8] * D[8][12]) * T + D[6][12]; - P[7][7] = - (Q[0] * G[7][0] * G[7][0] + Q[1] * G[7][1] * G[7][1] + - Q[2] * G[7][2] * G[7][2] + F[7][9] * (F[7][9] * D[9][9] + - F[7][10] * D[9][10] + - F[7][11] * D[9][11] + - F[7][12] * D[9][12] + - F[7][6] * D[6][9] + - F[7][8] * D[8][9]) + - F[7][10] * (F[7][9] * D[9][10] + F[7][10] * D[10][10] + - F[7][11] * D[10][11] + F[7][12] * D[10][12] + - F[7][6] * D[6][10] + F[7][8] * D[8][10]) + - F[7][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] + - F[7][11] * D[11][11] + F[7][12] * D[11][12] + - F[7][6] * D[6][11] + F[7][8] * D[8][11]) + - F[7][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] + - F[7][11] * D[11][12] + F[7][12] * D[12][12] + - F[7][6] * D[6][12] + F[7][8] * D[8][12]) + - F[7][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] + - F[7][9] * D[6][9] + F[7][10] * D[6][10] + - F[7][11] * D[6][11] + F[7][12] * D[6][12]) + - F[7][8] * (F[7][6] * D[6][8] + F[7][8] * D[8][8] + - F[7][9] * D[8][9] + F[7][10] * D[8][10] + - F[7][11] * D[8][11] + F[7][12] * D[8][12])) * Tsq + - (2 * F[7][6] * D[6][7] + 2 * F[7][8] * D[7][8] + - 2 * F[7][9] * D[7][9] + 2 * F[7][10] * D[7][10] + - 2 * F[7][11] * D[7][11] + 2 * F[7][12] * D[7][12]) * T + - D[7][7]; - P[7][8] = P[8][7] = - (F[8][9] * - (F[7][9] * D[9][9] + F[7][10] * D[9][10] + - F[7][11] * D[9][11] + F[7][12] * D[9][12] + - F[7][6] * D[6][9] + F[7][8] * D[8][9]) + - F[8][10] * (F[7][9] * D[9][10] + F[7][10] * D[10][10] + - F[7][11] * D[10][11] + F[7][12] * D[10][12] + - F[7][6] * D[6][10] + F[7][8] * D[8][10]) + - F[8][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] + - F[7][11] * D[11][11] + F[7][12] * D[11][12] + - F[7][6] * D[6][11] + F[7][8] * D[8][11]) + - F[8][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] + - F[7][11] * D[11][12] + F[7][12] * D[12][12] + - F[7][6] * D[6][12] + F[7][8] * D[8][12]) + - F[8][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] + - F[7][9] * D[6][9] + F[7][10] * D[6][10] + - F[7][11] * D[6][11] + F[7][12] * D[6][12]) + - F[8][7] * (F[7][6] * D[6][7] + F[7][8] * D[7][8] + - F[7][9] * D[7][9] + F[7][10] * D[7][10] + - F[7][11] * D[7][11] + F[7][12] * D[7][12]) + - G[7][0] * G[8][0] * Q[0] + G[7][1] * G[8][1] * Q[1] + - G[7][2] * G[8][2] * Q[2]) * Tsq + (F[7][6] * D[6][8] + - F[8][6] * D[6][7] + - F[8][7] * D[7][7] + - F[7][8] * D[8][8] + - F[7][9] * D[8][9] + - F[8][9] * D[7][9] + - F[7][10] * D[8][10] + - F[8][10] * D[7][10] + - F[7][11] * D[8][11] + - F[8][11] * D[7][11] + - F[7][12] * D[8][12] + - F[8][12] * D[7][12]) * T + - D[7][8]; - P[7][9] = P[9][7] = - (F[9][10] * - (F[7][9] * D[9][10] + F[7][10] * D[10][10] + - F[7][11] * D[10][11] + F[7][12] * D[10][12] + - F[7][6] * D[6][10] + F[7][8] * D[8][10]) + - F[9][11] * (F[7][9] * D[9][11] + F[7][10] * D[10][11] + - F[7][11] * D[11][11] + F[7][12] * D[11][12] + - F[7][6] * D[6][11] + F[7][8] * D[8][11]) + - F[9][12] * (F[7][9] * D[9][12] + F[7][10] * D[10][12] + - F[7][11] * D[11][12] + F[7][12] * D[12][12] + - F[7][6] * D[6][12] + F[7][8] * D[8][12]) + - F[9][6] * (F[7][6] * D[6][6] + F[7][8] * D[6][8] + - F[7][9] * D[6][9] + F[7][10] * D[6][10] + - F[7][11] * D[6][11] + F[7][12] * D[6][12]) + - F[9][7] * (F[7][6] * D[6][7] + F[7][8] * D[7][8] + - F[7][9] * D[7][9] + F[7][10] * D[7][10] + - F[7][11] * D[7][11] + F[7][12] * D[7][12]) + - F[9][8] * (F[7][6] * D[6][8] + F[7][8] * D[8][8] + - F[7][9] * D[8][9] + F[7][10] * D[8][10] + - F[7][11] * D[8][11] + F[7][12] * D[8][12]) + - G[9][0] * G[7][0] * Q[0] + G[9][1] * G[7][1] * Q[1] + - G[9][2] * G[7][2] * Q[2]) * Tsq + (F[9][6] * D[6][7] + - F[9][7] * D[7][7] + - F[9][8] * D[7][8] + - F[7][9] * D[9][9] + - F[9][10] * D[7][10] + - F[7][10] * D[9][10] + - F[9][11] * D[7][11] + - F[7][11] * D[9][11] + - F[9][12] * D[7][12] + - F[7][12] * D[9][12] + - F[7][6] * D[6][9] + - F[7][8] * D[8][9]) * T + - D[7][9]; - P[7][10] = P[10][7] = - (F[7][9] * D[9][10] + F[7][10] * D[10][10] + - F[7][11] * D[10][11] + F[7][12] * D[10][12] + - F[7][6] * D[6][10] + F[7][8] * D[8][10]) * T + D[7][10]; - P[7][11] = P[11][7] = - (F[7][9] * D[9][11] + F[7][10] * D[10][11] + - F[7][11] * D[11][11] + F[7][12] * D[11][12] + - F[7][6] * D[6][11] + F[7][8] * D[8][11]) * T + D[7][11]; - P[7][12] = P[12][7] = - (F[7][9] * D[9][12] + F[7][10] * D[10][12] + - F[7][11] * D[11][12] + F[7][12] * D[12][12] + - F[7][6] * D[6][12] + F[7][8] * D[8][12]) * T + D[7][12]; - P[8][8] = - (Q[0] * G[8][0] * G[8][0] + Q[1] * G[8][1] * G[8][1] + - Q[2] * G[8][2] * G[8][2] + F[8][9] * (F[8][9] * D[9][9] + - F[8][10] * D[9][10] + - F[8][11] * D[9][11] + - F[8][12] * D[9][12] + - F[8][6] * D[6][9] + - F[8][7] * D[7][9]) + - F[8][10] * (F[8][9] * D[9][10] + F[8][10] * D[10][10] + - F[8][11] * D[10][11] + F[8][12] * D[10][12] + - F[8][6] * D[6][10] + F[8][7] * D[7][10]) + - F[8][11] * (F[8][9] * D[9][11] + F[8][10] * D[10][11] + - F[8][11] * D[11][11] + F[8][12] * D[11][12] + - F[8][6] * D[6][11] + F[8][7] * D[7][11]) + - F[8][12] * (F[8][9] * D[9][12] + F[8][10] * D[10][12] + - F[8][11] * D[11][12] + F[8][12] * D[12][12] + - F[8][6] * D[6][12] + F[8][7] * D[7][12]) + - F[8][6] * (F[8][6] * D[6][6] + F[8][7] * D[6][7] + - F[8][9] * D[6][9] + F[8][10] * D[6][10] + - F[8][11] * D[6][11] + F[8][12] * D[6][12]) + - F[8][7] * (F[8][6] * D[6][7] + F[8][7] * D[7][7] + - F[8][9] * D[7][9] + F[8][10] * D[7][10] + - F[8][11] * D[7][11] + F[8][12] * D[7][12])) * Tsq + - (2 * F[8][6] * D[6][8] + 2 * F[8][7] * D[7][8] + - 2 * F[8][9] * D[8][9] + 2 * F[8][10] * D[8][10] + - 2 * F[8][11] * D[8][11] + 2 * F[8][12] * D[8][12]) * T + - D[8][8]; - P[8][9] = P[9][8] = - (F[9][10] * - (F[8][9] * D[9][10] + F[8][10] * D[10][10] + - F[8][11] * D[10][11] + F[8][12] * D[10][12] + - F[8][6] * D[6][10] + F[8][7] * D[7][10]) + - F[9][11] * (F[8][9] * D[9][11] + F[8][10] * D[10][11] + - F[8][11] * D[11][11] + F[8][12] * D[11][12] + - F[8][6] * D[6][11] + F[8][7] * D[7][11]) + - F[9][12] * (F[8][9] * D[9][12] + F[8][10] * D[10][12] + - F[8][11] * D[11][12] + F[8][12] * D[12][12] + - F[8][6] * D[6][12] + F[8][7] * D[7][12]) + - F[9][6] * (F[8][6] * D[6][6] + F[8][7] * D[6][7] + - F[8][9] * D[6][9] + F[8][10] * D[6][10] + - F[8][11] * D[6][11] + F[8][12] * D[6][12]) + - F[9][7] * (F[8][6] * D[6][7] + F[8][7] * D[7][7] + - F[8][9] * D[7][9] + F[8][10] * D[7][10] + - F[8][11] * D[7][11] + F[8][12] * D[7][12]) + - F[9][8] * (F[8][6] * D[6][8] + F[8][7] * D[7][8] + - F[8][9] * D[8][9] + F[8][10] * D[8][10] + - F[8][11] * D[8][11] + F[8][12] * D[8][12]) + - G[9][0] * G[8][0] * Q[0] + G[9][1] * G[8][1] * Q[1] + - G[9][2] * G[8][2] * Q[2]) * Tsq + (F[9][6] * D[6][8] + - F[9][7] * D[7][8] + - F[9][8] * D[8][8] + - F[8][9] * D[9][9] + - F[9][10] * D[8][10] + - F[8][10] * D[9][10] + - F[9][11] * D[8][11] + - F[8][11] * D[9][11] + - F[9][12] * D[8][12] + - F[8][12] * D[9][12] + - F[8][6] * D[6][9] + - F[8][7] * D[7][9]) * T + - D[8][9]; - P[8][10] = P[10][8] = - (F[8][9] * D[9][10] + F[8][10] * D[10][10] + - F[8][11] * D[10][11] + F[8][12] * D[10][12] + - F[8][6] * D[6][10] + F[8][7] * D[7][10]) * T + D[8][10]; - P[8][11] = P[11][8] = - (F[8][9] * D[9][11] + F[8][10] * D[10][11] + - F[8][11] * D[11][11] + F[8][12] * D[11][12] + - F[8][6] * D[6][11] + F[8][7] * D[7][11]) * T + D[8][11]; - P[8][12] = P[12][8] = - (F[8][9] * D[9][12] + F[8][10] * D[10][12] + - F[8][11] * D[11][12] + F[8][12] * D[12][12] + - F[8][6] * D[6][12] + F[8][7] * D[7][12]) * T + D[8][12]; - P[9][9] = - (Q[0] * G[9][0] * G[9][0] + Q[1] * G[9][1] * G[9][1] + - Q[2] * G[9][2] * G[9][2] + F[9][10] * (F[9][10] * D[10][10] + - F[9][11] * D[10][11] + - F[9][12] * D[10][12] + - F[9][6] * D[6][10] + - F[9][7] * D[7][10] + - F[9][8] * D[8][10]) + - F[9][11] * (F[9][10] * D[10][11] + F[9][11] * D[11][11] + - F[9][12] * D[11][12] + F[9][6] * D[6][11] + - F[9][7] * D[7][11] + F[9][8] * D[8][11]) + - F[9][12] * (F[9][10] * D[10][12] + F[9][11] * D[11][12] + - F[9][12] * D[12][12] + F[9][6] * D[6][12] + - F[9][7] * D[7][12] + F[9][8] * D[8][12]) + - F[9][6] * (F[9][6] * D[6][6] + F[9][7] * D[6][7] + - F[9][8] * D[6][8] + F[9][10] * D[6][10] + - F[9][11] * D[6][11] + F[9][12] * D[6][12]) + - F[9][7] * (F[9][6] * D[6][7] + F[9][7] * D[7][7] + - F[9][8] * D[7][8] + F[9][10] * D[7][10] + - F[9][11] * D[7][11] + F[9][12] * D[7][12]) + - F[9][8] * (F[9][6] * D[6][8] + F[9][7] * D[7][8] + - F[9][8] * D[8][8] + F[9][10] * D[8][10] + - F[9][11] * D[8][11] + F[9][12] * D[8][12])) * Tsq + - (2 * F[9][10] * D[9][10] + 2 * F[9][11] * D[9][11] + - 2 * F[9][12] * D[9][12] + 2 * F[9][6] * D[6][9] + - 2 * F[9][7] * D[7][9] + 2 * F[9][8] * D[8][9]) * T + D[9][9]; - P[9][10] = P[10][9] = - (F[9][10] * D[10][10] + F[9][11] * D[10][11] + - F[9][12] * D[10][12] + F[9][6] * D[6][10] + - F[9][7] * D[7][10] + F[9][8] * D[8][10]) * T + D[9][10]; - P[9][11] = P[11][9] = - (F[9][10] * D[10][11] + F[9][11] * D[11][11] + - F[9][12] * D[11][12] + F[9][6] * D[6][11] + - F[9][7] * D[7][11] + F[9][8] * D[8][11]) * T + D[9][11]; - P[9][12] = P[12][9] = - (F[9][10] * D[10][12] + F[9][11] * D[11][12] + - F[9][12] * D[12][12] + F[9][6] * D[6][12] + - F[9][7] * D[7][12] + F[9][8] * D[8][12]) * T + D[9][12]; - P[10][10] = Q[6] * Tsq + D[10][10]; - P[10][11] = P[11][10] = D[10][11]; - P[10][12] = P[12][10] = D[10][12]; - P[11][11] = Q[7] * Tsq + D[11][11]; - P[11][12] = P[12][11] = D[11][12]; - P[12][12] = Q[8] * Tsq + D[12][12]; -} -#endif - // ************* SerialUpdate ******************* // Does the update step of the Kalman filter for the covariance and estimate // Outputs are Xnew & Pnew, and are written over P and X @@ -1393,11 +519,11 @@ void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], for (j = 0; j < NUMX; j++) { // Find Hp = H*P HP[j] = 0; - for (k = 0; k < NUMX; k++) + for (k = HrowMin[m] ; k <= HrowMax[m]; k++) HP[j] += H[m][k] * P[k][j]; } HPHR = R[m]; // Find HPHR = H*P*H' + R - for (k = 0; k < NUMX; k++) + for (k = HrowMin[m]; k <= HrowMax[m]; k++) HPHR += HP[k] * H[m][k]; for (k = 0; k < NUMX; k++) From b76df471ee5bc0dace9b78383f78b457ff6283c7 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Fri, 10 May 2013 19:53:51 +0200 Subject: [PATCH 22/39] bugfix on revo proto. STM32F4 A revision has a hardware bug and cannot do flash prefetching properly --- .../Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c b/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c index f98b4a14b..bb7776d4b 100644 --- a/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c +++ b/flight/pios/stm32f4xx/libraries/CMSIS2/Device/ST/STM32F4xx/Source/revoproto/system_stm32f4xx.c @@ -393,7 +393,7 @@ static void SetSysClock(void) } /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ - FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; + FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; /* Select the main PLL as system clock source */ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); From 0a3b59ddeaf6b7a57b48e3b3093b95a91d70cbfc Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Fri, 10 May 2013 20:23:16 +0200 Subject: [PATCH 23/39] ManualControl: Initialize scaledChannel to 0, - required to not fail compilation with -O3 (GCC claims about potentially uninitialized use) --- flight/modules/ManualControl/manualcontrol.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index eff39dcae..c746adc88 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -203,7 +203,7 @@ static void manualControlTask(__attribute__((unused)) void *parameters) // Main task loop lastSysTime = xTaskGetTickCount(); while (1) { - float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM]; + static float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM] = {0}; // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); From e3147eed1abf36c2e98356b66748275e5d8f98a3 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 11 May 2013 01:33:56 +0200 Subject: [PATCH 24/39] some changes as suggested in review --- flight/libraries/insgps13state.c | 30 ++++++++++++++---------------- 1 file changed, 14 insertions(+), 16 deletions(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index fe6a2fe98..d0b7aee43 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -32,6 +32,7 @@ #include "insgps.h" #include #include +#include // constants/macros/typdefs #define NUMX 13 // number of states, X is the state vector @@ -39,9 +40,6 @@ #define NUMV 10 // number of measurements, v is the measurement noise vector #define NUMU 6 // number of deterministic inputs, U is the input vector -#define MIN(a,b) ((a)<(b)?(a):(b)) -#define MAX(a,b) ((a)>(b)?(a):(b)) - // Private functions void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]); @@ -56,14 +54,14 @@ void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV]); void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]); // Private variables -float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices +static float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices // global to init to zero and maintain zero elements // speed optimizations, describe matrix sparsity // derived from state equations in // LinearizeFG() and LinearizeH(): // -// usage F: usage G: usage H: (TODO) +// usage F: usage G: usage H: // 0123456789abc 012345678 0123456789abc // 0...X......... ......... X............ // 1....X........ ......... .X........... @@ -79,19 +77,19 @@ float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices // b............. .......X. // c............. ........X -const int8_t FrowMin[NUMX] = { 3, 4, 5, 6, 6, 6, 7, 6, 6, 6,13,13,13 }; -const int8_t FrowMax[NUMX] = { 3, 4, 5, 9, 9, 9,12,12,12,12,-1,-1,-1 }; +static const int8_t FrowMin[NUMX] = { 3, 4, 5, 6, 6, 6, 7, 6, 6, 6,13,13,13 }; +static const int8_t FrowMax[NUMX] = { 3, 4, 5, 9, 9, 9,12,12,12,12,-1,-1,-1 }; -const int8_t GrowMin[NUMX] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 }; -const int8_t GrowMax[NUMX] = { -1,-1,-1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 }; +static const int8_t GrowMin[NUMX] = { 9, 9, 9, 3, 3, 3, 0, 0, 0, 0, 6, 7, 8 }; +static const int8_t GrowMax[NUMX] = { -1,-1,-1, 5, 5, 5, 2, 2, 2, 2, 6, 7, 8 }; -const int8_t HrowMin[NUMV] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 }; -const int8_t HrowMax[NUMV] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 }; +static const int8_t HrowMin[NUMV] = { 0, 1, 2, 3, 4, 5, 6, 6, 6, 2 }; +static const int8_t HrowMax[NUMV] = { 0, 1, 2, 3, 4, 5, 9, 9, 9, 2 }; -float Be[3]; // local magnetic unit vector in NED frame -float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector -float Q[NUMW], R[NUMV]; // input noise and measurement noise variances -float K[NUMX][NUMV]; // feedback gain matrix +static float Be[3]; // local magnetic unit vector in NED frame +static float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector +static float Q[NUMW], R[NUMV]; // input noise and measurement noise variances +static float K[NUMX][NUMV]; // feedback gain matrix // Global variables struct NavStruct Nav; @@ -434,7 +432,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float dT1 = 1.0f / dT; // multiplication is faster than division on fpu. float dTsq = dT * dT; - float Dummy[NUMX][NUMX]; + static float Dummy[NUMX][NUMX]; int8_t i; for (i = 0; i < NUMX; i++) { // Calculate Dummy = (P/T +F*P) From 92d73e0e73ed05e64c0b8d361b34cfc41c54ad0c Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 11 May 2013 01:56:57 +0200 Subject: [PATCH 25/39] keep on stack for now --- flight/libraries/insgps13state.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index d0b7aee43..a3216e131 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -432,7 +432,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float dT1 = 1.0f / dT; // multiplication is faster than division on fpu. float dTsq = dT * dT; - static float Dummy[NUMX][NUMX]; + float Dummy[NUMX][NUMX]; int8_t i; for (i = 0; i < NUMX; i++) { // Calculate Dummy = (P/T +F*P) From 336a50f7e406135515cd021268d5f503d86f5806 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 11 May 2013 02:02:04 +0200 Subject: [PATCH 26/39] dynamic is better than static --- flight/modules/ManualControl/manualcontrol.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index c746adc88..9cb937fd3 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -202,8 +202,10 @@ static void manualControlTask(__attribute__((unused)) void *parameters) // Main task loop lastSysTime = xTaskGetTickCount(); + + float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM] = {0}; + while (1) { - static float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM] = {0}; // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); From 04f59d59101093d3e863758bd52d2dd569bef914 Mon Sep 17 00:00:00 2001 From: "Richard Flay (Hyper)" Date: Sat, 11 May 2013 16:18:34 +0930 Subject: [PATCH 27/39] OP-950: Adds "higher priority task woken" logic to SPI and SPI bus resident sensor device drivers. Based partly on code contributed by lilvinz. +review OPReview --- flight/pios/common/pios_bma180.c | 65 ++++++++---- flight/pios/common/pios_l3gd20.c | 92 ++++++++++++----- flight/pios/common/pios_mpu6000.c | 162 +++++++++++++++++++----------- flight/pios/inc/pios_spi.h | 4 +- flight/pios/stm32f10x/pios_spi.c | 43 +++++--- flight/pios/stm32f4xx/pios_spi.c | 57 +++++++++-- 6 files changed, 291 insertions(+), 132 deletions(-) diff --git a/flight/pios/common/pios_bma180.c b/flight/pios/common/pios_bma180.c index 35fd09d2f..d908fd0e3 100644 --- a/flight/pios/common/pios_bma180.c +++ b/flight/pios/common/pios_bma180.c @@ -128,10 +128,11 @@ int32_t PIOS_BMA180_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_ */ int32_t PIOS_BMA180_ClaimBus() { - if(PIOS_BMA180_Validate(dev) != 0) + if (PIOS_BMA180_Validate(dev) != 0) { return -1; + } - if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) { + if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) { return -1; } @@ -141,19 +142,22 @@ int32_t PIOS_BMA180_ClaimBus() } /** - * @brief Claim the SPI bus for the accel communications and select this chip + * @brief Claim the SPI bus for the accel communications and select this chip. Call from an ISR. + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * @return 0 if successful, -1 if unable to claim bus */ -int32_t PIOS_BMA180_ClaimBusISR() +int32_t PIOS_BMA180_ClaimBusISR(bool *woken) { - if(PIOS_BMA180_Validate(dev) != 0) - return -1; - - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) { + if (PIOS_BMA180_Validate(dev) != 0) { return -1; } - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { + return -1; + } + + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } @@ -162,13 +166,29 @@ int32_t PIOS_BMA180_ClaimBusISR() * @return 0 if successful */ int32_t PIOS_BMA180_ReleaseBus() +{ + if (PIOS_BMA180_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction. Call from an ISR + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return 0 if successful + */ +int32_t PIOS_BMA180_ReleaseBusISR(bool *woken) { if(PIOS_BMA180_Validate(dev) != 0) return -1; - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); - return PIOS_SPI_ReleaseBus(dev->spi_id); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); } /** @@ -431,19 +451,21 @@ int32_t PIOS_BMA180_Test() } /** - * @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. + * @brief EXTI IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. + * @return a boolean to the EXTI IRQ Handler wrapper indicating if a + * higher priority task is now eligible to run */ int32_t bma180_irqs = 0; bool PIOS_BMA180_IRQHandler(void) { - bma180_irqs++; - + bool woken = false; static const uint8_t pios_bma180_req_buf[7] = {BMA_X_LSB_ADDR | 0x80,0,0,0,0,0}; uint8_t pios_bma180_dmabuf[8]; - + bma180_irqs++; + // If we can't get the bus then just move on for efficiency - if(PIOS_BMA180_ClaimBusISR() != 0) { - return false; // Something else is using bus, miss this data + if (PIOS_BMA180_ClaimBusISR(&woken) != 0) { + return woken; // Something else is using bus, miss this data } PIOS_SPI_TransferBlock(dev->spi_id,pios_bma180_req_buf,(uint8_t *) pios_bma180_dmabuf, @@ -453,11 +475,12 @@ bool PIOS_BMA180_IRQHandler(void) struct pios_bma180_data data; // Don't release bus till data has copied - PIOS_BMA180_ReleaseBus(); + PIOS_BMA180_ReleaseBusISR(&woken); // Must not return before releasing bus - if(fifoBuf_getFree(&dev->fifo) < sizeof(data)) - return false; + if (fifoBuf_getFree(&dev->fifo) < sizeof(data)) { + return woken; + } // Bottom two bits indicate new data and are constant zeros. Don't right // shift because it drops sign bit @@ -471,7 +494,7 @@ bool PIOS_BMA180_IRQHandler(void) fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); - return false; + return woken; } #endif /* PIOS_INCLUDE_BMA180 */ diff --git a/flight/pios/common/pios_l3gd20.c b/flight/pios/common/pios_l3gd20.c index 6ca37a2d1..a9ebf7cbe 100644 --- a/flight/pios/common/pios_l3gd20.c +++ b/flight/pios/common/pios_l3gd20.c @@ -60,9 +60,11 @@ static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev); static void PIOS_L3GD20_Config(struct pios_l3gd20_cfg const * cfg); static int32_t PIOS_L3GD20_SetReg(uint8_t address, uint8_t buffer); static int32_t PIOS_L3GD20_GetReg(uint8_t address); +static int32_t PIOS_L3GD20_GetRegISR(uint8_t address, bool *woken); static int32_t PIOS_L3GD20_ClaimBus(); -static int32_t PIOS_L3GD20_ClaimBusIsr(); +static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken); static int32_t PIOS_L3GD20_ReleaseBus(); +static int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken); volatile bool l3gd20_configured = false; @@ -191,17 +193,19 @@ static int32_t PIOS_L3GD20_ClaimBus() /** * @brief Claim the SPI bus for the accel communications and select this chip + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus */ -static int32_t PIOS_L3GD20_ClaimBusIsr() +static int32_t PIOS_L3GD20_ClaimBusISR(bool *woken) { - if(PIOS_L3GD20_Validate(dev) != 0) + if(PIOS_L3GD20_Validate(dev) != 0) { return -1; - - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) + } + if(PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { return -2; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } @@ -211,14 +215,28 @@ static int32_t PIOS_L3GD20_ClaimBusIsr() */ int32_t PIOS_L3GD20_ReleaseBus() { - if(PIOS_L3GD20_Validate(dev) != 0) + if(PIOS_L3GD20_Validate(dev) != 0) { return -1; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); - + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); return PIOS_SPI_ReleaseBus(dev->spi_id); } +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return 0 if successful, -1 for invalid device + */ +int32_t PIOS_L3GD20_ReleaseBusISR(bool *woken) +{ + if(PIOS_L3GD20_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); +} + /** * @brief Read a register from L3GD20 * @returns The register value or -1 if failure to get bus @@ -238,6 +256,26 @@ static int32_t PIOS_L3GD20_GetReg(uint8_t reg) return data; } +/** + * @brief Read a register from L3GD20 in an ISR context + * @param reg[in] Register address to be read + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + * @return The register value or -1 if failure to get bus + */ +static int32_t PIOS_L3GD20_GetRegISR(uint8_t reg, bool *woken) +{ + uint8_t data; + + if(PIOS_L3GD20_ClaimBusISR(woken) != 0) { + return -1; + } + PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte + data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response + PIOS_L3GD20_ReleaseBusISR(woken); + return data; +} + /** * @brief Writes one byte to the L3GD20 * \param[in] reg Register address @@ -349,34 +387,38 @@ uint8_t PIOS_L3GD20_Test(void) } /** -* @brief IRQ Handler. Read all the data from onboard buffer +* @brief EXTI IRQ Handler. Read all the data from onboard buffer + * @return a boolean to the EXTI IRQ Handler wrapper indicating if a + * higher priority task is now eligible to run */ bool PIOS_L3GD20_IRQHandler(void) { - l3gd20_irq++; - + bool woken = false; struct pios_l3gd20_data data; uint8_t buf[7] = {PIOS_L3GD20_GYRO_X_OUT_LSB | 0x80 | 0x40, 0, 0, 0, 0, 0, 0}; uint8_t rec[7]; + l3gd20_irq++; + /* This code duplicates ReadGyros above but uses ClaimBusIsr */ - if(PIOS_L3GD20_ClaimBusIsr() != 0) - return false; - - if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { - PIOS_L3GD20_ReleaseBus(); - return false; + if (PIOS_L3GD20_ClaimBusISR(&woken) != 0) { + return woken; } - PIOS_L3GD20_ReleaseBus(); + if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { + PIOS_L3GD20_ReleaseBusISR(&woken); + return woken; + } + + PIOS_L3GD20_ReleaseBusISR(&woken); memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6); - data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); + data.temperature = PIOS_L3GD20_GetRegISR(PIOS_L3GD20_OUT_TEMP, &woken); - portBASE_TYPE xHigherPriorityTaskWoken; - xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); + signed portBASE_TYPE higherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken); - return xHigherPriorityTaskWoken == pdTRUE; + return (woken || higherPriorityTaskWoken == pdTRUE); } #endif /* PIOS_INCLUDE_L3GD20 */ diff --git a/flight/pios/common/pios_mpu6000.c b/flight/pios/common/pios_mpu6000.c index 2b2d06b0b..384a49393 100644 --- a/flight/pios/common/pios_mpu6000.c +++ b/flight/pios/common/pios_mpu6000.c @@ -197,7 +197,12 @@ int32_t PIOS_MPU6000_ConfigureRanges( { if(dev == NULL) return -1; + + // TODO: check that changing the SPI clock speed is safe + // to do here given that interrupts are enabled and the bus has + // not been claimed/is not claimed during this call PIOS_SPI_SetClockSpeed(dev->spi_id, PIOS_SPI_PRESCALER_256); + // update filter settings while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0); @@ -225,39 +230,63 @@ int32_t PIOS_MPU6000_ConfigureRanges( /** * @brief Claim the SPI bus for the accel communications and select this chip * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus - * @param fromIsr[in] Tells if the function is being called from a ISR or not */ -static int32_t PIOS_MPU6000_ClaimBus(bool fromIsr) +static int32_t PIOS_MPU6000_ClaimBus() { - if(PIOS_MPU6000_Validate(dev) != 0) + if(PIOS_MPU6000_Validate(dev) != 0) { return -1; - if(fromIsr){ - if(PIOS_SPI_ClaimBusISR(dev->spi_id) != 0) - return -2; - } else { - if(PIOS_SPI_ClaimBus(dev->spi_id) != 0) - return -2; } - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,0); + if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) { + return -2; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); + return 0; +} + +/** + * @brief Claim the SPI bus for the accel communications and select this chip + * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + */ +static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken) +{ + if (PIOS_MPU6000_Validate(dev) != 0) { + return -1; + } + if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) { + return -2; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0); return 0; } /** * @brief Release the SPI bus for the accel communications and end the transaction * @return 0 if successful - * @param fromIsr[in] Tells if the function is being called from a ISR or not */ -int32_t PIOS_MPU6000_ReleaseBus(bool fromIsr) +static int32_t PIOS_MPU6000_ReleaseBus() { - if(PIOS_MPU6000_Validate(dev) != 0) + if(PIOS_MPU6000_Validate(dev) != 0) { return -1; - - PIOS_SPI_RC_PinSet(dev->spi_id,dev->slave_num,1); - if(fromIsr){ - return PIOS_SPI_ReleaseBusISR(dev->spi_id); - } else { - return PIOS_SPI_ReleaseBus(dev->spi_id); } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBus(dev->spi_id); +} + +/** + * @brief Release the SPI bus for the accel communications and end the transaction + * @return 0 if successful + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged + */ +static int32_t PIOS_MPU6000_ReleaseBusISR(bool *woken) +{ + if(PIOS_MPU6000_Validate(dev) != 0) { + return -1; + } + PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1); + return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken); } /** @@ -269,13 +298,14 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) { uint8_t data; - if(PIOS_MPU6000_ClaimBus(false) != 0) + if(PIOS_MPU6000_ClaimBus() != 0) { return -1; + } PIOS_SPI_TransferByte(dev->spi_id,(0x80 | reg) ); // request byte data = PIOS_SPI_TransferByte(dev->spi_id,0 ); // receive response - PIOS_MPU6000_ReleaseBus(false); + PIOS_MPU6000_ReleaseBus(); return data; } @@ -289,20 +319,21 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) */ static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data) { - if(PIOS_MPU6000_ClaimBus(false) != 0) + if (PIOS_MPU6000_ClaimBus() != 0) { return -1; + } - if(PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { - PIOS_MPU6000_ReleaseBus(false); + if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) { + PIOS_MPU6000_ReleaseBus(); return -2; } - if(PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { - PIOS_MPU6000_ReleaseBus(false); + if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) { + PIOS_MPU6000_ReleaseBus(); return -3; } - - PIOS_MPU6000_ReleaseBus(false); + + PIOS_MPU6000_ReleaseBus(); return 0; } @@ -318,13 +349,15 @@ int32_t PIOS_MPU6000_ReadGyros(struct pios_mpu6000_data * data) uint8_t buf[7] = {PIOS_MPU6000_GYRO_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0}; uint8_t rec[7]; - if(PIOS_MPU6000_ClaimBus(false) != 0) + if (PIOS_MPU6000_ClaimBus() != 0) { return -1; + } - if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) + if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { return -2; - - PIOS_MPU6000_ReleaseBus(false); + } + + PIOS_MPU6000_ReleaseBus(); data->gyro_x = rec[1] << 8 | rec[2]; data->gyro_y = rec[3] << 8 | rec[4]; @@ -407,31 +440,34 @@ int32_t PIOS_MPU6000_Test(void) } /** - * @brief Run self-test operation. - * \return 0 if test succeeded - * \return non-zero value if test succeeded - * @param fromIsr[in] Tells if the function is being called from a ISR or not + * @brief Obtains the number of bytes in the FIFO. Call from ISR only. + * @return the number of bytes in the FIFO + * @param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged */ -static int32_t PIOS_MPU6000_FifoDepth(bool fromIsr) +static int32_t PIOS_MPU6000_FifoDepthISR(bool *woken) { uint8_t mpu6000_send_buf[3] = {PIOS_MPU6000_FIFO_CNT_MSB | 0x80, 0, 0}; uint8_t mpu6000_rec_buf[3]; - if(PIOS_MPU6000_ClaimBus(fromIsr) != 0) - return -1; - - if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(fromIsr); + if(PIOS_MPU6000_ClaimBusISR(woken) != 0) { return -1; } - PIOS_MPU6000_ReleaseBus(fromIsr); + if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { + PIOS_MPU6000_ReleaseBusISR(woken); + return -1; + } + + PIOS_MPU6000_ReleaseBusISR(woken); return (mpu6000_rec_buf[1] << 8) | mpu6000_rec_buf[2]; } /** -* @brief IRQ Handler. Read all the data from onboard buffer +* @brief EXTI IRQ Handler. Read all the data from onboard buffer +* @return a boolean to the EXTI IRQ Handler wrapper indicating if a +* higher priority task is now eligible to run */ uint32_t mpu6000_irq = 0; int32_t mpu6000_count; @@ -446,46 +482,50 @@ uint32_t mpu6000_transfer_size; bool PIOS_MPU6000_IRQHandler(void) { + bool woken = false; static uint32_t timeval; mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); timeval = PIOS_DELAY_GetRaw(); - if (!mpu6000_configured) + if (!mpu6000_configured) { return false; + } - mpu6000_count = PIOS_MPU6000_FifoDepth(true); - if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) - return false; + mpu6000_count = PIOS_MPU6000_FifoDepthISR(&woken); + if (mpu6000_count < (int32_t)sizeof(struct pios_mpu6000_data)) { + return woken; + } - if (PIOS_MPU6000_ClaimBus(true) != 0) - return false; + if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) { + return woken; + } static uint8_t mpu6000_send_buf[1 + sizeof(struct pios_mpu6000_data) ] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; static uint8_t mpu6000_rec_buf[1 + sizeof(struct pios_mpu6000_data) ]; if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); mpu6000_fails++; - return false; + return woken; } - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); static struct pios_mpu6000_data data; // In the case where extras samples backed up grabbed an extra if (mpu6000_count >= (int32_t)(sizeof(data) * 2)) { mpu6000_fifo_backup++; - if (PIOS_MPU6000_ClaimBus(true) != 0) - return false; + if (PIOS_MPU6000_ClaimBusISR(&woken) != 0) + return woken; if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); mpu6000_fails++; - return false; + return woken; } - PIOS_MPU6000_ReleaseBus(true); + PIOS_MPU6000_ReleaseBusISR(&woken); } // Rotate the sensor to OP convention. The datasheet defines X as towards the right @@ -548,14 +588,14 @@ bool PIOS_MPU6000_IRQHandler(void) data.temperature = mpu6000_rec_buf[1] << 8 | mpu6000_rec_buf[2]; #endif - portBASE_TYPE xHigherPriorityTaskWoken; - xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); + signed portBASE_TYPE higherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &higherPriorityTaskWoken); mpu6000_irq++; mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); - return xHigherPriorityTaskWoken == pdTRUE; + return (woken || higherPriorityTaskWoken == pdTRUE); } #endif /* PIOS_INCLUDE_MPU6000 */ diff --git a/flight/pios/inc/pios_spi.h b/flight/pios/inc/pios_spi.h index 951459b94..5740e1e67 100644 --- a/flight/pios/inc/pios_spi.h +++ b/flight/pios/inc/pios_spi.h @@ -49,9 +49,9 @@ extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b); extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); extern int32_t PIOS_SPI_Busy(uint32_t spi_id); extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id); -extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id); +extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken); extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id); -extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id); +extern int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken); extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id); extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); diff --git a/flight/pios/stm32f10x/pios_spi.c b/flight/pios/stm32f10x/pios_spi.c index 4e001b775..6b8d2c88e 100644 --- a/flight/pios/stm32f10x/pios_spi.c +++ b/flight/pios/stm32f10x/pios_spi.c @@ -265,22 +265,33 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) /** * Claim the SPI bus semaphore from an ISR. Has no timeout. * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error * \return -1 if timeout before claiming semaphore */ -int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; + bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ + if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){ return -1; } -#endif + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ClaimBus(spi_id); +#endif } /** @@ -302,7 +313,6 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) PIOS_IRQ_Disable(); spi_dev->busy = 0; PIOS_IRQ_Enable(); - #endif return 0; } @@ -310,25 +320,30 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) /** * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error */ -int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - xSemaphoreGiveFromISR(spi_dev->busy, NULL); + xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken); + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } + return 0; #else - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - PIOS_IRQ_Disable(); - spi_dev->busy = 0; - PIOS_IRQ_Enable(); - + if (woken) { + *woken = false; + } + return PIOS_SPI_ReleaseBus(spi_id); #endif - return 0; } diff --git a/flight/pios/stm32f4xx/pios_spi.c b/flight/pios/stm32f4xx/pios_spi.c index 56134c165..bc8304596 100644 --- a/flight/pios/stm32f4xx/pios_spi.c +++ b/flight/pios/stm32f4xx/pios_spi.c @@ -257,6 +257,18 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) return -1; +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + uint32_t timeout = 0xffff; + while((PIOS_SPI_Busy(spi_id) || spi_dev->busy) && --timeout); + if(timeout == 0) //timed out + return -1; + + PIOS_IRQ_Disable(); + if(spi_dev->busy) + return -1; + spi_dev->busy = 1; + PIOS_IRQ_Enable(); #endif return 0; } @@ -264,25 +276,35 @@ int32_t PIOS_SPI_ClaimBus(uint32_t spi_id) /** * Claim the SPI bus semaphore from an ISR. Has no timeout. * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error * \return -1 if timeout before claiming semaphore */ -int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) - struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; - + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; + bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - if (xSemaphoreTakeFromISR(spi_dev->busy, NULL) != pdTRUE){ + if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE){ return -1; } -#endif + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ClaimBus(spi_id); +#endif } - /** * Release the SPI bus semaphore. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) @@ -297,6 +319,11 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) PIOS_Assert(valid) xSemaphoreGive(spi_dev->busy); +#else + struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + PIOS_IRQ_Disable(); + spi_dev->busy = 0; + PIOS_IRQ_Enable(); #endif return 0; } @@ -304,21 +331,33 @@ int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id) /** * Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this * \param[in] spi SPI number (0 or 1) + * \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority + * task has is now eligible to run, else unchanged * \return 0 if no error */ -int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id) +int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken) { #if defined(PIOS_INCLUDE_FREERTOS) struct pios_spi_dev * spi_dev = (struct pios_spi_dev *)spi_id; + signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE; bool valid = PIOS_SPI_validate(spi_dev); PIOS_Assert(valid) - xSemaphoreGiveFromISR(spi_dev->busy, NULL); + xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken); + if (woken) { + *woken = *woken || (higherPriorityTaskWoken == pdTRUE); + } + return 0; +#else + if (woken) { + *woken = false; + } + return PIOS_SPI_ReleaseBus(spi_id); #endif - return 0; } + /** * Controls the RC (Register Clock alias Chip Select) pin of a SPI port * \param[in] spi SPI number (0 or 1) From e5970ed25d1eb9233051340430b90fc4064766a8 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 12 May 2013 03:51:00 +0300 Subject: [PATCH 28/39] logfs: fix unit tests (requires MIN declaration from pios_math.h) --- flight/pios/common/pios_flashfs_logfs.c | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/flight/pios/common/pios_flashfs_logfs.c b/flight/pios/common/pios_flashfs_logfs.c index 0e54dd9e9..ed6b95131 100644 --- a/flight/pios/common/pios_flashfs_logfs.c +++ b/flight/pios/common/pios_flashfs_logfs.c @@ -29,13 +29,12 @@ #ifdef PIOS_INCLUDE_FLASH -#include "openpilot.h" +#include +#include +#include #include "pios_flashfs_logfs_priv.h" -#include - - /* * Filesystem state data tracked in RAM */ From 3b7c274c785850abeef92b15bb6915fbc41242a8 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 12 May 2013 11:27:12 +0200 Subject: [PATCH 29/39] OP-935 Renames 'Camera stab' to 'Gimbal'. Adds functionality to store-clear and recall board rotation during calibration. --- .../src/plugins/config/configgadgetwidget.cpp | 4 +- .../src/plugins/config/configrevowidget.cpp | 898 ++++++++++-------- .../src/plugins/config/configrevowidget.h | 26 +- .../src/plugins/config/revosensors.ui | 456 +++++++-- 4 files changed, 887 insertions(+), 497 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 74dfea483..5f2f268ba 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -104,7 +104,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigCameraStabilizationWidget(this); - ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab")); + ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal")); icon = new QIcon(); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); @@ -192,7 +192,7 @@ void ConfigGadgetWidget::onAutopilotConnect() // First of all, check what Board type we are talking to, and // if necessary, remove/add tabs in the config gadget: ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager *utilMngr = pm->getObject(); + UAVObjectUtilManager *utilMngr = pm->getObject(); if (utilMngr) { int selectedIndex = ftw->currentIndex(); int board = utilMngr->getBoardModel(); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index c346f5f97..86f6e6c83 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -61,8 +61,7 @@ const double ConfigRevoWidget::maxVarValue = 0.1; // ***************** -class Thread : public QThread -{ +class Thread : public QThread { public: static void usleep(unsigned long usecs) { @@ -74,9 +73,10 @@ public: ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : ConfigTaskWidget(parent), - collectingData(false), m_ui(new Ui_RevoSensorsWidget()), - position(-1) + collectingData(false), + position(-1), + isBoardRotationStored(false) { m_ui->setupUi(this); @@ -105,9 +105,9 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // Initialize the 9 bargraph values: QMatrix lineMatrix = renderer->matrixForElement("accel_x"); - QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); + QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x")); qreal startX = rect.x(); - qreal startY = rect.y()+ rect.height(); + qreal startY = rect.y() + rect.height(); // maxBarHeight will be used for scaling it later. maxBarHeight = rect.height(); // Then once we have the initial location, we can put it @@ -119,101 +119,103 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : accel_x->setElementId("accel_x"); m_ui->sensorsBargraph->scene()->addItem(accel_x); accel_x->setPos(startX, startY); - accel_x->setTransform(QTransform::fromScale(1,0),true); + accel_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("accel_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_y = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + accel_y = new QGraphicsSvgItem(); accel_y->setSharedRenderer(renderer); accel_y->setElementId("accel_y"); m_ui->sensorsBargraph->scene()->addItem(accel_y); - accel_y->setPos(startX,startY); - accel_y->setTransform(QTransform::fromScale(1,0),true); + accel_y->setPos(startX, startY); + accel_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("accel_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - accel_z = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + accel_z = new QGraphicsSvgItem(); accel_z->setSharedRenderer(renderer); accel_z->setElementId("accel_z"); m_ui->sensorsBargraph->scene()->addItem(accel_z); - accel_z->setPos(startX,startY); - accel_z->setTransform(QTransform::fromScale(1,0),true); + accel_z->setPos(startX, startY); + accel_z->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_x"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_x = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_x = new QGraphicsSvgItem(); gyro_x->setSharedRenderer(renderer); gyro_x->setElementId("gyro_x"); m_ui->sensorsBargraph->scene()->addItem(gyro_x); - gyro_x->setPos(startX,startY); - gyro_x->setTransform(QTransform::fromScale(1,0),true); + gyro_x->setPos(startX, startY); + gyro_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_y = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_y = new QGraphicsSvgItem(); gyro_y->setSharedRenderer(renderer); gyro_y->setElementId("gyro_y"); m_ui->sensorsBargraph->scene()->addItem(gyro_y); - gyro_y->setPos(startX,startY); - gyro_y->setTransform(QTransform::fromScale(1,0),true); + gyro_y->setPos(startX, startY); + gyro_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("gyro_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); - gyro_z = new QGraphicsSvgItem(); + startX = rect.x(); + startY = rect.y() + rect.height(); + gyro_z = new QGraphicsSvgItem(); gyro_z->setSharedRenderer(renderer); gyro_z->setElementId("gyro_z"); m_ui->sensorsBargraph->scene()->addItem(gyro_z); - gyro_z->setPos(startX,startY); - gyro_z->setTransform(QTransform::fromScale(1,0),true); + gyro_z->setPos(startX, startY); + gyro_z->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_x"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_x")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_x = new QGraphicsSvgItem(); mag_x->setSharedRenderer(renderer); mag_x->setElementId("mag_x"); m_ui->sensorsBargraph->scene()->addItem(mag_x); - mag_x->setPos(startX,startY); - mag_x->setTransform(QTransform::fromScale(1,0),true); + mag_x->setPos(startX, startY); + mag_x->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_y"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_y")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_y = new QGraphicsSvgItem(); mag_y->setSharedRenderer(renderer); mag_y->setElementId("mag_y"); m_ui->sensorsBargraph->scene()->addItem(mag_y); - mag_y->setPos(startX,startY); - mag_y->setTransform(QTransform::fromScale(1,0),true); + mag_y->setPos(startX, startY); + mag_y->setTransform(QTransform::fromScale(1, 0), true); lineMatrix = renderer->matrixForElement("mag_z"); rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_z")); - startX = rect.x(); - startY = rect.y()+ rect.height(); + startX = rect.x(); + startY = rect.y() + rect.height(); mag_z = new QGraphicsSvgItem(); mag_z->setSharedRenderer(renderer); mag_z->setElementId("mag_z"); m_ui->sensorsBargraph->scene()->addItem(mag_z); - mag_z->setPos(startX,startY); - mag_z->setTransform(QTransform::fromScale(1,0),true); + mag_z->setPos(startX, startY); + mag_z->setTransform(QTransform::fromScale(1, 0), true); // Must set up the UI (above) before setting up the UAVO mappings or refreshWidgetValues // will be dealing with some null pointers addUAVObject("RevoCalibration"); addUAVObject("EKFConfiguration"); + addUAVObject("HomeLocation"); + addUAVObject("AttitudeSettings"); autoLoadWidgets(); // Connect the signals @@ -222,10 +224,17 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData())); connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement())); + connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation())); + addUAVObjectToWidgetRelation("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH); + addUAVObjectToWidgetRelation("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW); + populateWidgets(); refreshWidgetsValues(); + m_ui->tabWidget->setCurrentIndex(0); } ConfigRevoWidget::~ConfigRevoWidget() @@ -241,25 +250,29 @@ void ConfigRevoWidget::showEvent(QShowEvent *event) // widget is shown, otherwise it cannot compute its values and // the result is usually a sensorsBargraph that is way too small. m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); } void ConfigRevoWidget::resizeEvent(QResizeEvent *event) { Q_UNUSED(event) m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); } /** - * Starts an accelerometer bias calibration. - */ + * Starts an accelerometer bias calibration. + */ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() { + // Store and reset board rotation before calibration starts + isBoardRotationStored = false; + storeAndClearBoardRotation(); + m_ui->accelBiasStart->setEnabled(false); m_ui->accelBiasProgress->setValue(0); - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE; @@ -267,7 +280,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() revoCalibration->updated(); // Disable gyro bias correction while calibrating - AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); Q_ASSERT(attitudeSettings); AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; @@ -284,7 +297,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() UAVObject::Metadata mdata; /* Need to get as many accel updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); mdata = initialAccelsMdata; @@ -292,7 +305,7 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() mdata.flightTelemetryUpdatePeriod = 100; accels->setMetadata(mdata); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); initialGyrosMdata = gyros->getMetadata(); mdata = initialGyrosMdata; @@ -302,22 +315,23 @@ void ConfigRevoWidget::doStartAccelGyroBiasCalibration() // Now connect to the accels and mag updates, gather for 100 samples collectingData = true; - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); - connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetAccelGyroBiasData(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); + connect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); } /** - Updates the accel bias raw values - */ + Updates the accel bias raw values + */ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); - switch(obj->getObjID()) { + switch (obj->getObjID()) { case Accels::OBJID: { - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); @@ -328,7 +342,7 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) } case Gyros::OBJID: { - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); Gyros::DataFields gyrosData = gyros->getData(); @@ -342,25 +356,24 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) } // Work out the progress based on whichever has less - double p1 = (double) accel_accum_x.size() / (double) NOISE_SAMPLES; - double p2 = (double) accel_accum_y.size() / (double) NOISE_SAMPLES; + double p1 = (double)accel_accum_x.size() / (double)NOISE_SAMPLES; + double p2 = (double)accel_accum_y.size() / (double)NOISE_SAMPLES; m_ui->accelBiasProgress->setValue(((p1 < p2) ? p1 : p2) * 100); - if(accel_accum_x.size() >= NOISE_SAMPLES && - gyro_accum_y.size() >= NOISE_SAMPLES && - collectingData == true) { - + if (accel_accum_x.size() >= NOISE_SAMPLES && + gyro_accum_y.size() >= NOISE_SAMPLES && + collectingData == true) { collectingData = false; - Accels * accels = Accels::GetInstance(getObjectManager()); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); - disconnect(gyros,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetAccelGyroBiasData(UAVObject*))); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); + disconnect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *))); m_ui->accelBiasStart->setEnabled(true); - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE; @@ -368,15 +381,15 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) // Update the biases based on collected data revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] += listMean(accel_accum_x); revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] += listMean(accel_accum_y); - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += ( listMean(accel_accum_z) + GRAVITY ); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_X] += listMean(gyro_accum_x); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Y] += listMean(gyro_accum_y); - revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Z] += listMean(gyro_accum_z); + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] += (listMean(accel_accum_z) + GRAVITY); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_X] += listMean(gyro_accum_x); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Y] += listMean(gyro_accum_y); + revoCalibrationData.gyro_bias[RevoCalibration::GYRO_BIAS_Z] += listMean(gyro_accum_z); revoCalibration->setData(revoCalibrationData); revoCalibration->updated(); - AttitudeSettings * attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); Q_ASSERT(attitudeSettings); AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData(); attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; @@ -385,132 +398,132 @@ void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj) accels->setMetadata(initialAccelsMdata); gyros->setMetadata(initialGyrosMdata); + + // Recall saved board rotation + recallBoardRotation(); } } - -int LinearEquationsSolving(int nDim, double* pfMatr, double* pfVect, double* pfSolution) +int LinearEquationsSolving(int nDim, double *pfMatr, double *pfVect, double *pfSolution) { - double fMaxElem; - double fAcc; + double fMaxElem; + double fAcc; - int i , j, k, m; + int i, j, k, m; - for(k=0; k<(nDim-1); k++) // base row of matrix - { - // search of line with max element - fMaxElem = fabs( pfMatr[k*nDim + k] ); - m = k; - for(i=k+1; i= 0; k--) { + pfSolution[k] = pfVect[k]; + for (i = (k + 1); i < nDim; i++) { + pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]); + } + pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k]; + } - for(k=(nDim-1); k>=0; k--) - { - pfSolution[k] = pfVect[k]; - for(i=(k+1); igetData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); - //check if Homelocation is set - if(!homeLocationData.Set) - { + // check if Homelocation is set + if (!homeLocationData.Set) { QMessageBox msgBox; msgBox.setInformativeText(tr("

HomeLocation not SET.

Please set your HomeLocation and try again. Aborting calibration!

")); msgBox.setStandardButtons(QMessageBox::Ok); @@ -525,9 +538,9 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = 1; revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = 1; revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = 1; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = 0; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = 0; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = 0; accel_accum_x.clear(); accel_accum_y.clear(); @@ -538,9 +551,9 @@ void ConfigRevoWidget::doStartSixPointCalibration() revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = 1; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = 1; revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = 1; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0; // Disable adaptive mag nulling initialMagCorrectionRate = revoCalibrationData.MagBiasNullingRate; @@ -561,7 +574,7 @@ void ConfigRevoWidget::doStartSixPointCalibration() #ifdef SIX_POINT_CAL_ACCEL /* Need to get as many accel updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); initialAccelsMdata = accels->getMetadata(); @@ -572,7 +585,7 @@ void ConfigRevoWidget::doStartSixPointCalibration() #endif /* Need to get as many mag updates as possible */ - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); initialMagMdata = mag->getMetadata(); mdata = initialMagMdata; @@ -590,13 +603,14 @@ void ConfigRevoWidget::doStartSixPointCalibration() } /** - * Saves the data from the aircraft in one of six positions. - * This is called when they click "save position" and starts - * averaging data for this position. - */ + * Saves the data from the aircraft in one of six positions. + * This is called when they click "save position" and starts + * averaging data for this position. + */ void ConfigRevoWidget::savePositionData() { QMutexLocker lock(&sensorsUpdateLock); + m_ui->sixPointsSave->setEnabled(false); accel_accum_x.clear(); @@ -608,39 +622,39 @@ void ConfigRevoWidget::savePositionData() collectingData = true; - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); + connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); m_ui->sixPointCalibInstructions->append("Hold..."); } /** - * Grab a sample of mag (optionally accel) data while in this position and - * store it for averaging. When sufficient points are collected advance - * to the next position (give message to user) or compute the scale and bias - */ -void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) + * Grab a sample of mag (optionally accel) data while in this position and + * store it for averaging. When sufficient points are collected advance + * to the next position (give message to user) or compute the scale and bias + */ +void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); // This is necessary to prevent a race condition on disconnect signal and another update if (collectingData == true) { - if( obj->getObjID() == Accels::OBJID ) { + if (obj->getObjID() == Accels::OBJID) { #ifdef SIX_POINT_CAL_ACCEL - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); accel_accum_x.append(accelsData.x); accel_accum_y.append(accelsData.y); accel_accum_z.append(accelsData.z); #endif - } else if( obj->getObjID() == Magnetometer::OBJID ) { - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + } else if (obj->getObjID() == Magnetometer::OBJID) { + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); Magnetometer::DataFields magData = mag->getData(); mag_accum_x.append(magData.x); @@ -652,9 +666,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) } #ifdef SIX_POINT_CAL_ACCEL - if(accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { + if (accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) { #else - if(mag_accum_x.size() >= 20 && collectingData == true) { + if (mag_accum_x.size() >= 20 && collectingData == true) { #endif collectingData = false; @@ -662,44 +676,44 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) #ifdef SIX_POINT_CAL_ACCEL // Store the mean for this position for the accel - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - disconnect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); accel_data_x[position] = listMean(accel_accum_x); accel_data_y[position] = listMean(accel_accum_y); accel_data_z[position] = listMean(accel_accum_z); #endif // Store the mean for this position for the mag - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); - disconnect(mag,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(doGetSixPointCalibrationMeasurement(UAVObject*))); + disconnect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *))); mag_data_x[position] = listMean(mag_accum_x); mag_data_y[position] = listMean(mag_accum_y); mag_data_z[position] = listMean(mag_accum_z); position = (position + 1) % 6; - if(position == 1) { + if (position == 1) { m_ui->sixPointCalibInstructions->append("Place with left side down and click save position..."); displayPlane("plane-left"); } - if(position == 2) { + if (position == 2) { m_ui->sixPointCalibInstructions->append("Place upside down and click save position..."); displayPlane("plane-flip"); } - if(position == 3) { + if (position == 3) { m_ui->sixPointCalibInstructions->append("Place with right side down and click save position..."); displayPlane("plane-right"); } - if(position == 4) { + if (position == 4) { m_ui->sixPointCalibInstructions->append("Place with nose up and click save position..."); displayPlane("plane-up"); } - if(position == 5) { + if (position == 5) { m_ui->sixPointCalibInstructions->append("Place with nose down and click save position..."); displayPlane("plane-down"); } - if(position == 0) { + if (position == 0) { computeScaleBias(); m_ui->sixPointsStart->setEnabled(true); m_ui->sixPointsSave->setEnabled(false); @@ -709,144 +723,187 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject * obj) accels->setMetadata(initialAccelsMdata); #endif mag->setMetadata(initialMagMdata); + + // Recall saved board rotation + recallBoardRotation(); } } } /** - * Computes the scale and bias for the magnetomer and (compile option) - * for the accel once all the data has been collected in 6 positions. - */ + * Computes the scale and bias for the magnetomer and (compile option) + * for the accel once all the data has been collected in 6 positions. + */ void ConfigRevoWidget::computeScaleBias() { - double S[3], b[3]; - double Be_length; - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); - Q_ASSERT(revoCalibration); - Q_ASSERT(homeLocation); - RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); - HomeLocation::DataFields homeLocationData = homeLocation->getData(); + double S[3], b[3]; + double Be_length; + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); -#ifdef SIX_POINT_CAL_ACCEL - // Calibration accel - SixPointInConstFieldCal( homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; -#endif - - // Calibration mag - Be_length = sqrt(pow(homeLocationData.Be[0],2)+pow(homeLocationData.Be[1],2)+pow(homeLocationData.Be[2],2)); - SixPointInConstFieldCal( Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); - - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; - - // Restore the previous setting - revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate; - -#ifdef SIX_POINT_CAL_ACCEL - bool good_calibration = true; - - // Check the mag calibration is good - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; - - // Check the accel calibration is good - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X]; - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y]; - good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] == - revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y]; - good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] == - revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z]; - if (good_calibration) { - revoCalibration->setData(revoCalibrationData); - m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); - } else { - revoCalibrationData = revoCalibration->getData(); - m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); - } -#else - bool good_calibration = true; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; - good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == - revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; - good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == - revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; - if (good_calibration) { - revoCalibration->setData(revoCalibrationData); - m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); - } else { - revoCalibrationData = revoCalibration->getData(); - m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); - } -#endif - - position = -1; //set to run again -} - -/** - Rotate the paper plane - */ -void ConfigRevoWidget::displayPlane(QString elementID) -{ - paperplane->setElementId(elementID); - m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); - m_ui->sixPointsHelp->fitInView(paperplane,Qt::KeepAspectRatio); - -} - -/*********** Noise measurement functions **************/ -/** - * Connect sensor updates and timeout for measuring the noise - */ -void ConfigRevoWidget::doStartNoiseMeasurement() -{ - QMutexLocker lock(&sensorsUpdateLock); - Q_UNUSED(lock); - - RevoCalibration * revoCalibration = RevoCalibration::GetInstance(getObjectManager()); - HomeLocation * homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); Q_ASSERT(homeLocation); RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); - //check if Homelocation is set - if(!homeLocationData.Set) - { +#ifdef SIX_POINT_CAL_ACCEL + // Calibration accel + SixPointInConstFieldCal(homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] = fabs(S[0]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] = fabs(S[1]); + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] = -sign(S[2]) * b[2]; +#endif + + // Calibration mag + Be_length = sqrt(pow(homeLocationData.Be[0], 2) + pow(homeLocationData.Be[1], 2) + pow(homeLocationData.Be[2], 2)); + SixPointInConstFieldCal(Be_length, mag_data_x, mag_data_y, mag_data_z, S, b); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] = fabs(S[0]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] = fabs(S[1]); + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] = fabs(S[2]); + + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1]; + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2]; + + // Restore the previous setting + revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate; + +#ifdef SIX_POINT_CAL_ACCEL + bool good_calibration = true; + + // Check the mag calibration is good + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + + // Check the accel calibration is good + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_X]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Y]; + good_calibration &= revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z] == + revoCalibrationData.accel_scale[RevoCalibration::ACCEL_SCALE_Z]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_X]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Y]; + good_calibration &= revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z] == + revoCalibrationData.accel_bias[RevoCalibration::ACCEL_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed accel and mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } +#else // ifdef SIX_POINT_CAL_ACCEL + bool good_calibration = true; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_X]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Y]; + good_calibration &= revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z] == + revoCalibrationData.mag_scale[RevoCalibration::MAG_SCALE_Z]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y]; + good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] == + revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z]; + if (good_calibration) { + revoCalibration->setData(revoCalibrationData); + m_ui->sixPointCalibInstructions->append("Computed mag scale and bias..."); + } else { + revoCalibrationData = revoCalibration->getData(); + m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat."); + } +#endif // ifdef SIX_POINT_CAL_ACCEL + + position = -1; // set to run again +} + +void ConfigRevoWidget::storeAndClearBoardRotation() +{ + if(!isBoardRotationStored) { + // Store current board rotation + isBoardRotationStored = true; + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields data = attitudeSettings->getData(); + storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW] = data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW]; + storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL]; + storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH]; + + // Set board rotation to no rotation + data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0; + data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0; + data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0; + attitudeSettings->setData(data); + } +} + +void ConfigRevoWidget::recallBoardRotation() +{ + if(isBoardRotationStored) { + // Recall current board rotation + isBoardRotationStored = false; + + AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager()); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields data = attitudeSettings->getData(); + data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW]; + data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL]; + data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH]; + attitudeSettings->setData(data); + } +} + +/** + Rotate the paper plane + */ +void ConfigRevoWidget::displayPlane(QString elementID) +{ + paperplane->setElementId(elementID); + m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect()); + m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio); +} + +/*********** Noise measurement functions **************/ +/** + * Connect sensor updates and timeout for measuring the noise + */ +void ConfigRevoWidget::doStartNoiseMeasurement() +{ + QMutexLocker lock(&sensorsUpdateLock); + + // Store and reset board rotation before calibration starts + isBoardRotationStored = false; + storeAndClearBoardRotation(); + + Q_UNUSED(lock); + + RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager()); + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(revoCalibration); + Q_ASSERT(homeLocation); + RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + + // check if Homelocation is set + if (!homeLocationData.Set) { QMessageBox msgBox; msgBox.setInformativeText(tr("

HomeLocation not SET.

Please set your HomeLocation and try again. Aborting calibration!

")); msgBox.setStandardButtons(QMessageBox::Ok); @@ -867,11 +924,11 @@ void ConfigRevoWidget::doStartNoiseMeasurement() mag_accum_z.clear(); /* Need to get as many accel, mag and gyro updates as possible */ - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); - Magnetometer * mag = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mag = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mag); UAVObject::Metadata mdata; @@ -895,26 +952,27 @@ void ConfigRevoWidget::doStartNoiseMeasurement() mag->setMetadata(mdata); /* Connect for updates */ - connect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - connect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - connect(mag, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + connect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + connect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); } /** - * Called when any of the sensors are updated. Stores the sample for measuring the - * variance at the end - */ -void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) + * Called when any of the sensors are updated. Stores the sample for measuring the + * variance at the end + */ +void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj) { QMutexLocker lock(&sensorsUpdateLock); + Q_UNUSED(lock); Q_ASSERT(obj); - switch(obj->getObjID()) { + switch (obj->getObjID()) { case Gyros::OBJID: { - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); Q_ASSERT(gyros); Gyros::DataFields gyroData = gyros->getData(); gyro_accum_x.append(gyroData.x); @@ -924,7 +982,7 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) } case Accels::OBJID: { - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); Q_ASSERT(accels); Accels::DataFields accelsData = accels->getData(); accel_accum_x.append(accelsData.x); @@ -934,7 +992,7 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) } case Magnetometer::OBJID: { - Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); + Magnetometer *mags = Magnetometer::GetInstance(getObjectManager()); Q_ASSERT(mags); Magnetometer::DataFields magData = mags->getData(); mag_accum_x.append(magData.x); @@ -946,95 +1004,109 @@ void ConfigRevoWidget::doGetNoiseSample(UAVObject * obj) Q_ASSERT(0); } - float p1 = (float) mag_accum_x.length() / (float) NOISE_SAMPLES; - float p2 = (float) gyro_accum_x.length() / (float) NOISE_SAMPLES; - float p3 = (float) accel_accum_x.length() / (float) NOISE_SAMPLES; + float p1 = (float)mag_accum_x.length() / (float)NOISE_SAMPLES; + float p2 = (float)gyro_accum_x.length() / (float)NOISE_SAMPLES; + float p3 = (float)accel_accum_x.length() / (float)NOISE_SAMPLES; float prog = (p1 < p2) ? p1 : p2; prog = (prog < p3) ? prog : p3; m_ui->noiseMeasurementProgress->setValue(prog * 100); - if(mag_accum_x.length() >= NOISE_SAMPLES && - gyro_accum_x.length() >= NOISE_SAMPLES && - accel_accum_x.length() >= NOISE_SAMPLES) { + if (mag_accum_x.length() >= NOISE_SAMPLES && + gyro_accum_x.length() >= NOISE_SAMPLES && + accel_accum_x.length() >= NOISE_SAMPLES) { // No need to for more updates - Magnetometer * mags = Magnetometer::GetInstance(getObjectManager()); - Accels * accels = Accels::GetInstance(getObjectManager()); - Gyros * gyros = Gyros::GetInstance(getObjectManager()); - disconnect(accels, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - disconnect(gyros, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); - disconnect(mags, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(doGetNoiseSample(UAVObject*))); + Magnetometer *mags = Magnetometer::GetInstance(getObjectManager()); + Accels *accels = Accels::GetInstance(getObjectManager()); + Gyros *gyros = Gyros::GetInstance(getObjectManager()); + disconnect(accels, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + disconnect(gyros, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); + disconnect(mags, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *))); EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); Q_ASSERT(ekfConfiguration); - if(ekfConfiguration) { + if (ekfConfiguration) { EKFConfiguration::DataFields revoCalData = ekfConfiguration->getData(); revoCalData.Q[EKFConfiguration::Q_ACCELX] = listVar(accel_accum_x); revoCalData.Q[EKFConfiguration::Q_ACCELY] = listVar(accel_accum_y); revoCalData.Q[EKFConfiguration::Q_ACCELZ] = listVar(accel_accum_z); - revoCalData.Q[EKFConfiguration::Q_GYROX] = listVar(gyro_accum_x); - revoCalData.Q[EKFConfiguration::Q_GYROY] = listVar(gyro_accum_y); - revoCalData.Q[EKFConfiguration::Q_GYROZ] = listVar(gyro_accum_z); - revoCalData.R[EKFConfiguration::R_MAGX] = listVar(mag_accum_x); - revoCalData.R[EKFConfiguration::R_MAGY] = listVar(mag_accum_y); - revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z); + revoCalData.Q[EKFConfiguration::Q_GYROX] = listVar(gyro_accum_x); + revoCalData.Q[EKFConfiguration::Q_GYROY] = listVar(gyro_accum_y); + revoCalData.Q[EKFConfiguration::Q_GYROZ] = listVar(gyro_accum_z); + revoCalData.R[EKFConfiguration::R_MAGX] = listVar(mag_accum_x); + revoCalData.R[EKFConfiguration::R_MAGY] = listVar(mag_accum_y); + revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z); ekfConfiguration->setData(revoCalData); } + + // Recall saved board rotation + recallBoardRotation(); } } /********** UI Functions *************/ /** - Draws the sensor variances bargraph - */ + Draws the sensor variances bargraph + */ void ConfigRevoWidget::drawVariancesGraph() { - EKFConfiguration * ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); + EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager()); + Q_ASSERT(ekfConfiguration); - if(!ekfConfiguration) + if (!ekfConfiguration) { return; + } EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData(); // The expected range is from 1E-6 to 1E-1 double steps = 6; // 6 bars on the graph - float accel_x_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX])); - if(accel_x) - accel_x->setTransform(QTransform::fromScale(1,accel_x_var),false); - float accel_y_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY])); - if(accel_y) - accel_y->setTransform(QTransform::fromScale(1,accel_y_var),false); - float accel_z_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ])); - if(accel_z) - accel_z->setTransform(QTransform::fromScale(1,accel_z_var),false); + float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX])); + if (accel_x) { + accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false); + } + float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY])); + if (accel_y) { + accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false); + } + float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ])); + if (accel_z) { + accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false); + } - float gyro_x_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX])); - if(gyro_x) - gyro_x->setTransform(QTransform::fromScale(1,gyro_x_var),false); - float gyro_y_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY])); - if(gyro_y) - gyro_y->setTransform(QTransform::fromScale(1,gyro_y_var),false); - float gyro_z_var = -1/steps*(1+steps+log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ])); - if(gyro_z) - gyro_z->setTransform(QTransform::fromScale(1,gyro_z_var),false); + float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX])); + if (gyro_x) { + gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false); + } + float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY])); + if (gyro_y) { + gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false); + } + float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ])); + if (gyro_z) { + gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false); + } // Scale by 1e-3 because mag vars are much higher. - float mag_x_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGX])); - if(mag_x) - mag_x->setTransform(QTransform::fromScale(1,mag_x_var),false); - float mag_y_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGY])); - if(mag_y) - mag_y->setTransform(QTransform::fromScale(1,mag_y_var),false); - float mag_z_var = -1/steps*(1+steps+log10(1e-3*ekfConfigurationData.R[EKFConfiguration::R_MAGZ])); - if(mag_z) - mag_z->setTransform(QTransform::fromScale(1,mag_z_var),false); + float mag_x_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGX])); + if (mag_x) { + mag_x->setTransform(QTransform::fromScale(1, mag_x_var), false); + } + float mag_y_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGY])); + if (mag_y) { + mag_y->setTransform(QTransform::fromScale(1, mag_y_var), false); + } + float mag_z_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGZ])); + if (mag_z) { + mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false); + } } /** - * Called by the ConfigTaskWidget parent when RevoCalibration is updated - * to update the UI - */ + * Called by the ConfigTaskWidget parent when RevoCalibration is updated + * to update the UI + */ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object) { ConfigTaskWidget::refreshWidgetsValues(object); @@ -1045,11 +1117,31 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object) m_ui->sixPointsStart->setEnabled(true); m_ui->accelBiasStart->setEnabled(true); m_ui->startDriftCalib->setEnabled(true); - m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); + + m_ui->isSetCheckBox->setEnabled(false); + + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + Q_ASSERT(homeLocation); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); + + QString beStr = QString("%1:%2:%3").arg(QString::number(homeLocationData.Be[0]), QString::number(homeLocationData.Be[1]), QString::number(homeLocationData.Be[2])); + m_ui->beBox->setText(beStr); } -/** - @} - @} - */ +void ConfigRevoWidget::clearHomeLocation() +{ + HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); + + Q_ASSERT(homeLocation); + HomeLocation::DataFields homeLocationData; + homeLocationData.Latitude = 0; + homeLocationData.Longitude = 0; + homeLocationData.Altitude = 0; + homeLocationData.Be[0] = 0; + homeLocationData.Be[1] = 0; + homeLocationData.Be[2] = 0; + homeLocationData.g_e = 9.81f; + homeLocationData.Set = HomeLocation::SET_FALSE; + homeLocation->setData(homeLocationData); +} diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 9bc35004c..9eb349612 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -43,19 +43,18 @@ class Ui_Widget; -class ConfigRevoWidget: public ConfigTaskWidget -{ +class ConfigRevoWidget : public ConfigTaskWidget { Q_OBJECT public: ConfigRevoWidget(QWidget *parent = 0); ~ConfigRevoWidget(); - + private: void drawVariancesGraph(); void displayPlane(QString elementID); - //! Computes the scale and bias of the mag based on collected data + // ! Computes the scale and bias of the mag based on collected data void computeScaleBias(); Ui_RevoSensorsWidget *m_ui; @@ -101,27 +100,36 @@ private: static const int NOISE_SAMPLES = 100; + // Board rotation store/recall + qint16 storedBoardRotation[3]; + bool isBoardRotationStored; + void storeAndClearBoardRotation(); + void recallBoardRotation(); + + private slots: - //! Overriden method from the configTaskWidget to update UI - virtual void refreshWidgetsValues(UAVObject *object=NULL); + // ! Overriden method from the configTaskWidget to update UI + virtual void refreshWidgetsValues(UAVObject *object = NULL); // Slots for calibrating the mags void doStartSixPointCalibration(); - void doGetSixPointCalibrationMeasurement(UAVObject * obj); + void doGetSixPointCalibrationMeasurement(UAVObject *obj); void savePositionData(); // Slots for calibrating the accel and gyro void doStartAccelGyroBiasCalibration(); - void doGetAccelGyroBiasData(UAVObject*); + void doGetAccelGyroBiasData(UAVObject *); // Slots for measuring the sensor noise void doStartNoiseMeasurement(); void doGetNoiseSample(UAVObject *); + // Slot for clearing home location + void clearHomeLocation(); + protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); - }; #endif // ConfigRevoWidget_H diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 2ecf1ee04..6c6e68aca 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -6,8 +6,8 @@ 0 0 - 720 - 567 + 643 + 531 @@ -16,8 +16,11 @@ + + false + - 0 + 1 @@ -499,104 +502,394 @@ p, li { white-space: pre-wrap; } + + 6 + - - - - 75 - true - + + + + 0 + 0 + - - Attitude Algorithm: + + Attitude Estimation Algorithm + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + + + + + 0 + 0 + + + + Selects the sensor integration algorithm to be used by the Revolution board. + + + + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 0 + + + + + - - - Selects the sensor integration algorithm to be used by the Revolution board. + + + + 0 + 0 + - - - - - - Qt::Horizontal + + Home Location - - - 40 - 20 - + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - - - - - 75 - true - - - - Home Location: - - - - - - - false - - - Saves the Home Location. This is only enabled -if the Home Location is set, i.e. if the GPS fix is -successful. - -Disabled if there is no GPS fix. - - - Set - - - true - - - buttonGroup - - - - - - - true - - - Clears the HomeLocation: only makes sense if you save -to SD. This will force the INS to use the next GPS fix as the -new home location unless it is in indoor mode. - - - Clear - - - buttonGroup - + + + QLayout::SetDefaultConstraint + + + + + Gravity acceleration: + + + + + + + Latitude: + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:g_e + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Latitude + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + + + + Altitude: + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Altitude + + + + + + + + Magnetic field vector: + + + + + + + <html><head/><body><p>This information must be set to enable calibration the Revolution controllers sensors. <br/>Set home location using context menu in the map widget.</p></body></html> + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + objname:HomeLocation + fieldname:Longitude + + + + + + + + false + + + Is Set + + + true + + + + objname:HomeLocation + fieldname:Set + + + + + + + + Longitude: + + + + + + + + 0 + 0 + + + + Clear + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + + + + + Rotate virtual attitude relative to board + + + + + + 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 + + + + + + + -180 + + + 180 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + -180 + + + 180 + + + + + + + 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::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; + + + Pitch + + + Qt::AlignCenter + + + + + + + -90 + + + 90 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + Qt::Vertical + + QSizePolicy::Expanding + 20 - 40 + 100 @@ -716,7 +1009,4 @@ specific calibration button on top of the screen. - - - From ddf2ccf72060c3d65db63d4a0751c44b78b29856 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 12 May 2013 11:28:09 +0200 Subject: [PATCH 30/39] OP-935 Fixes some gui issues. --- .../src/plugins/config/revosensors.ui | 34 +++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 6c6e68aca..1ffa4a345 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -20,7 +20,7 @@ false - 1 + 0 @@ -49,8 +49,8 @@ - 75 - true + 50 + false @@ -135,8 +135,8 @@ - 75 - true + 50 + false @@ -238,8 +238,8 @@ Hint: run this with engines at cruising speed. - 75 - true + 50 + false @@ -311,8 +311,8 @@ Hint: run this with engines at cruising speed. - 75 - true + 50 + false @@ -476,20 +476,20 @@ 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:11pt; font-weight:600;">Help</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:'Ubuntu'; font-size:11pt; font-weight:600;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</span></p> -<p align="center" 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; font-weight:600;"><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; font-weight:600;">#1: Multi-Point calibration:</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:11pt;">Help</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:'Ubuntu'; font-size:11pt;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</span></p> +<p align="center" 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;">#1: Multi-Point calibration:</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:'Ubuntu'; font-size:11pt;">This calibration will compute the scale for all sensors on the INS. Press &quot;Start&quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#2: Sensor noise calibration:</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:'Ubuntu'; font-size:11pt;">#2: Sensor noise calibration:</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:'Ubuntu'; font-size:11pt;">This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &quot;Start&quot;.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#3: Accelerometer bias calibration:</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:'Ubuntu'; font-size:11pt;">#3: Accelerometer bias calibration:</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:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">#4 Gyro temp drift calibration:</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; font-weight:600;"><br /></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:'Ubuntu'; font-size:11pt;">#4 Gyro temp drift calibration:</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></td></tr></table></body></html>
From fee4e1009bef08bc17eebda25bef81df3107d33f Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 12 May 2013 11:53:21 +0200 Subject: [PATCH 31/39] OP-935 Removes gui for unimplemented temperature compensation calibration. --- .../src/plugins/config/configrevowidget.cpp | 1 - .../src/plugins/config/revosensors.ui | 174 +----------------- 2 files changed, 2 insertions(+), 173 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 86f6e6c83..b28693c09 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -1116,7 +1116,6 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object) m_ui->noiseMeasurementStart->setEnabled(true); m_ui->sixPointsStart->setEnabled(true); m_ui->accelBiasStart->setEnabled(true); - m_ui->startDriftCalib->setEnabled(true); m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate.")); m_ui->isSetCheckBox->setEnabled(false); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 1ffa4a345..5827a385f 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -291,173 +291,6 @@ Hint: run this with engines at cruising speed.
- - - - QFrame::StyledPanel - - - QFrame::Raised - - - - 3 - - - - - - - - - - 50 - false - - - - #4 Gyro temperature drift calibration - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Temp: - - - - - - - - 9 - - - - Min - - - - - - - Currently measured temperature on the system. This is actually the -MB temperature, be careful if somehow you know that your INS -temperature is very different from your MB temp... - - - Qt::Horizontal - - - QSlider::TicksBelow - - - - - - - - 9 - - - - Max - - - - - - - - - - - Current drift: - - - - - - - - - - - Saved drift: - - - - - - - - - - - false - - - Start gathering data for temperature drift calibration. -Avoid sudden moves once you have started gathering! - - - Start - - - - - - - false - - - Launch drift measurement based on gathered data. - -TODO: is this necessary? Measurement could be auto updated every second or so, or done when we stop measuring... - - - Measure - - - - - - - false - - - Updates the XYZ drift values into the AHRS (saves to SD) - - - Save - - - - - - - - - -
@@ -477,7 +310,7 @@ 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:11pt;">Help</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:'Ubuntu'; font-size:11pt;">Step #1 and #2 are really necessary. Steps #3 and #4 will help you achieve the best possible results.</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:'Ubuntu'; font-size:11pt;">Step #1 and #2 are really necessary. Step #3 will help you achieve the best possible results.</span></p> <p align="center" 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;">#1: Multi-Point calibration:</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:'Ubuntu'; font-size:11pt;">This calibration will compute the scale for all sensors on the INS. Press &quot;Start&quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> @@ -486,10 +319,7 @@ p, li { white-space: pre-wrap; } <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;">This calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &quot;Start&quot;.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">#3: Accelerometer bias calibration:</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:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">#4 Gyro temp drift calibration:</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></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:'Ubuntu'; font-size:11pt;">This step will ensure that accelerometer bias is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p></td></tr></table></body></html> From b9601c3ad6485b93d4763505ef660f8a4232c23b Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 12 May 2013 15:13:39 +0300 Subject: [PATCH 32/39] Add fake board name to display unit test names with make all_ut_run --- Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/Makefile b/Makefile index 25142441b..58f849bf7 100644 --- a/Makefile +++ b/Makefile @@ -654,6 +654,7 @@ ut_$(1)_%: $$(UT_OUT_DIR) $(V1) cd $(ROOT_DIR)/flight/tests/$(1) && \ $$(MAKE) -r --no-print-directory \ BUILD_TYPE=ut \ + BOARD_SHORT_NAME=$(1) \ TOPDIR=$(ROOT_DIR)/flight/tests/$(1) \ OUTDIR="$(UT_OUT_DIR)/$(1)" \ TARGET=$(1) \ From 49af941813c0b1dee4284b6fccd4f3d2c97320c9 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 12 May 2013 15:44:15 +0200 Subject: [PATCH 33/39] OP-935 Sets the correct background color of some configuration pages. --- .../src/plugins/config/configrevohwwidget.ui | 15 +++++++++------ .../src/plugins/config/revosensors.ui | 12 +++++++++--- 2 files changed, 18 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui index fb81114bd..a8b3f65dd 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui +++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui @@ -20,6 +20,9 @@ 0 + + true + HW settings @@ -119,7 +122,7 @@ 12 - + @@ -399,11 +402,11 @@ - - - - - + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 5827a385f..6741c20da 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -17,12 +17,15 @@ - false + true 0 + + true + Calibration @@ -309,7 +312,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:11pt;">Help</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:'Ubuntu'; font-size:11pt; font-weight:600;">Help</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:'Ubuntu'; font-size:11pt;">Step #1 and #2 are really necessary. Step #3 will help you achieve the best possible results.</span></p> <p align="center" 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;">#1: Multi-Point calibration:</span></p> @@ -326,6 +329,9 @@ p, li { white-space: pre-wrap; } + + true + Settings @@ -338,7 +344,7 @@ p, li { white-space: pre-wrap; } - + 0 0 From 0bc589956b8db80a7908cbb97a7df472f8d3783a Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 12 May 2013 16:00:02 +0200 Subject: [PATCH 34/39] OP-935 Removed a chewing gum that was stuck under the about dialog ;) --- .../openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml index 98ccf4ef3..1fe8934cf 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml @@ -38,9 +38,7 @@ ** ****************************************************************************/ - import QtQuick 1.1 - import QtWebKit 1.0 - + import QtQuick 1.1 // This is a tabbed pane element. Add a nested Rectangle to add a tab. TabWidget { From c4adede7ac83018f215963adbe75160ff6d546bf Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Mon, 13 May 2013 21:24:19 +0200 Subject: [PATCH 35/39] OP-952 Adds settings per scope-plot if to draw the plot anti-aliased. Default setting is true. Adds a fix to not render the plots when they are not visible. Saves CPU. --- .../src/plugins/scope/scopegadget.cpp | 70 +- .../scope/scopegadgetconfiguration.cpp | 156 ++-- .../plugins/scope/scopegadgetconfiguration.h | 131 +++- .../plugins/scope/scopegadgetoptionspage.cpp | 327 ++++----- .../plugins/scope/scopegadgetoptionspage.h | 21 +- .../plugins/scope/scopegadgetoptionspage.ui | 102 ++- .../src/plugins/scope/scopegadgetwidget.cpp | 686 +++++++++--------- .../src/plugins/scope/scopegadgetwidget.h | 14 +- 8 files changed, 764 insertions(+), 743 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp index d9b33b185..ec7c01113 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp @@ -33,52 +33,47 @@ #include ScopeGadget::ScopeGadget(QString classId, ScopeGadgetWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget), - configLoaded(false) + IUAVGadget(classId, parent), + m_widget(widget), + configLoaded(false) +{} + +void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration *config) { - -} - -void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) -{ - - ScopeGadgetConfiguration *sgConfig = qobject_cast(config); - ScopeGadgetWidget* widget = qobject_cast(m_widget); + ScopeGadgetConfiguration *sgConfig = qobject_cast(config); + ScopeGadgetWidget *widget = qobject_cast(m_widget); widget->setXWindowSize(sgConfig->dataSize()); widget->setRefreshInterval(sgConfig->refreshInterval()); - if(sgConfig->plotType() == SequentialPlot ) + if (sgConfig->plotType() == SequentialPlot) { widget->setupSequentialPlot(); - else if(sgConfig->plotType() == ChronoPlot) + } else if (sgConfig->plotType() == ChronoPlot) { widget->setupChronoPlot(); - // else if(sgConfig->plotType() == UAVObjectPlot) - // widget->setupUAVObjectPlot(); + } - foreach (PlotCurveConfiguration* plotCurveConfig, sgConfig->plotCurveConfigs()) { - - QString uavObject = plotCurveConfig->uavObject; - QString uavField = plotCurveConfig->uavField; + foreach(PlotCurveConfiguration * plotCurveConfig, sgConfig->plotCurveConfigs()) { + QString uavObject = plotCurveConfig->uavObject; + QString uavField = plotCurveConfig->uavField; int scale = plotCurveConfig->yScalePower; int mean = plotCurveConfig->yMeanSamples; QString mathFunction = plotCurveConfig->mathFunction; QRgb color = plotCurveConfig->color; - + bool antialiased = plotCurveConfig->drawAntialiased; widget->addCurvePlot( - uavObject, - uavField, - scale, - mean, - mathFunction, - QPen( QBrush(QColor(color),Qt::SolidPattern), -// (qreal)2, - (qreal)1, - Qt::SolidLine, - Qt::SquareCap, - Qt::BevelJoin) - ); - } + uavObject, + uavField, + scale, + mean, + mathFunction, + QPen(QBrush(QColor(color), Qt::SolidPattern), + (qreal)1, + Qt::SolidLine, + Qt::SquareCap, + Qt::BevelJoin), + antialiased + ); + } widget->setLoggingEnabled(sgConfig->getLoggingEnabled()); widget->setLoggingNewFileOnConnect(sgConfig->getLoggingNewFileOnConnect()); @@ -87,14 +82,13 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) widget->csvLoggingStop(); widget->csvLoggingSetName(sgConfig->name()); widget->csvLoggingStart(); - } /** - Scope gadget destructor: should delete the associated - scope gadget widget too! - */ + Scope gadget destructor: should delete the associated + scope gadget widget too! + */ ScopeGadget::~ScopeGadget() { - delete m_widget; + delete m_widget; } diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp index 57b1c134f..cc1095cfc 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp @@ -27,75 +27,63 @@ #include "scopegadgetconfiguration.h" -ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent), - m_plotType((int)ChronoPlot), - m_dataSize(60), - m_refreshInterval(1000), - m_mathFunctionType(0) +ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings *qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent), + m_plotType((int)ChronoPlot), + m_dataSize(60), + m_refreshInterval(1000), + m_mathFunctionType(0) { uint currentStreamVersion = 0; int plotCurveCount = 0; - //if a saved configuration exists load it - if(qSettings != 0) { + // If a saved configuration exists load it + if (qSettings != 0) { currentStreamVersion = qSettings->value("configurationStreamVersion").toUInt(); - if(currentStreamVersion != m_configurationStreamVersion) + if (currentStreamVersion != m_configurationStreamVersion) { return; + } - m_plotType = qSettings->value("plotType").toInt(); - m_dataSize = qSettings->value("dataSize").toInt(); + m_plotType = qSettings->value("plotType").toInt(); + m_dataSize = qSettings->value("dataSize").toInt(); m_refreshInterval = qSettings->value("refreshInterval").toInt(); - plotCurveCount = qSettings->value("plotCurveCount").toInt(); - - for(int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { - QString uavObject; - QString uavField; - QRgb color; + plotCurveCount = qSettings->value("plotCurveCount").toInt(); + for (int plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); - PlotCurveConfiguration* plotCurveConf = new PlotCurveConfiguration(); - uavObject = qSettings->value("uavObject").toString(); - plotCurveConf->uavObject = uavObject; - uavField = qSettings->value("uavField").toString(); - plotCurveConf->uavField = uavField; - color = qSettings->value("color").value(); - plotCurveConf->color = color; - plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); + PlotCurveConfiguration *plotCurveConf = new PlotCurveConfiguration(); + plotCurveConf->uavObject = qSettings->value("uavObject").toString(); + plotCurveConf->uavField = qSettings->value("uavField").toString(); + plotCurveConf->color = qSettings->value("color").value(); + plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); plotCurveConf->mathFunction = qSettings->value("mathFunction").toString(); - plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples").toInt(); - - if (!plotCurveConf->yMeanSamples) plotCurveConf->yMeanSamples = 1; // fallback for backward compatibility with earlier versions //IS THIS STILL NECESSARY? - + plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt(); + plotCurveConf->yMeanSamples = qSettings->value("yMeanSamples", 1).toInt(); + plotCurveConf->drawAntialiased = qSettings->value("drawAntialiased", true).toBool(); plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble(); plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble(); - - m_PlotCurveConfigs.append(plotCurveConf); + m_plotCurveConfigs.append(plotCurveConf); qSettings->endGroup(); } - m_LoggingEnabled = qSettings->value("LoggingEnabled").toBool(); - m_LoggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool(); - m_LoggingPath = qSettings->value("LoggingPath").toString(); - + m_loggingEnabled = qSettings->value("LoggingEnabled").toBool(); + m_loggingNewFileOnConnect = qSettings->value("LoggingNewFileOnConnect").toBool(); + m_loggingPath = qSettings->value("LoggingPath").toString(); } } void ScopeGadgetConfiguration::clearPlotData() { - PlotCurveConfiguration* poltCurveConfig; + PlotCurveConfiguration *plotCurveConfig; - while(m_PlotCurveConfigs.size() > 0) - { - poltCurveConfig = m_PlotCurveConfigs.first(); - m_PlotCurveConfigs.pop_front(); - - delete poltCurveConfig; + while (m_plotCurveConfigs.size() > 0) { + plotCurveConfig = m_plotCurveConfigs.first(); + m_plotCurveConfigs.pop_front(); + delete plotCurveConfig; } } @@ -105,40 +93,38 @@ void ScopeGadgetConfiguration::clearPlotData() */ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() { - int plotCurveCount = 0; + int plotCurveCount = 0; int plotDatasLoadIndex = 0; ScopeGadgetConfiguration *m = new ScopeGadgetConfiguration(this->classId()); - m->setPlotType( m_plotType); - m->setDataSize( m_dataSize); - m->setMathFunctionType( m_mathFunctionType); - m->setRefreashInterval( m_refreshInterval); - plotCurveCount = m_PlotCurveConfigs.size(); + m->setPlotType(m_plotType); + m->setDataSize(m_dataSize); + m->setMathFunctionType(m_mathFunctionType); + m->setRefreashInterval(m_refreshInterval); - for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { - PlotCurveConfiguration* currentPlotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex); + plotCurveCount = m_plotCurveConfigs.size(); - PlotCurveConfiguration* newPlotCurveConf = new PlotCurveConfiguration(); - newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject; - newPlotCurveConf->uavField = currentPlotCurveConf->uavField; - newPlotCurveConf->color = currentPlotCurveConf->color; - newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; + for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { + PlotCurveConfiguration *currentPlotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex); + + PlotCurveConfiguration *newPlotCurveConf = new PlotCurveConfiguration(); + newPlotCurveConf->uavObject = currentPlotCurveConf->uavObject; + newPlotCurveConf->uavField = currentPlotCurveConf->uavField; + newPlotCurveConf->color = currentPlotCurveConf->color; + newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; newPlotCurveConf->yMeanSamples = currentPlotCurveConf->yMeanSamples; newPlotCurveConf->mathFunction = currentPlotCurveConf->mathFunction; - - newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; - newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; + newPlotCurveConf->drawAntialiased = currentPlotCurveConf->drawAntialiased; + newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; + newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; m->addPlotCurveConfig(newPlotCurveConf); } - m->setLoggingEnabled(m_LoggingEnabled); - m->setLoggingNewFileOnConnect(m_LoggingNewFileOnConnect); - m->setLoggingPath(m_LoggingPath); - - + m->setLoggingEnabled(m_loggingEnabled); + m->setLoggingNewFileOnConnect(m_loggingNewFileOnConnect); + m->setLoggingPath(m_loggingPath); return m; } @@ -148,9 +134,9 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() * Saves a configuration. //REDEFINES saveConfig CHILD BEHAVIOR? * */ -void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { - - int plotCurveCount = m_PlotCurveConfigs.size(); +void ScopeGadgetConfiguration::saveConfig(QSettings *qSettings) const +{ + int plotCurveCount = m_plotCurveConfigs.size(); int plotDatasLoadIndex = 0; qSettings->setValue("configurationStreamVersion", m_configurationStreamVersion); @@ -159,35 +145,33 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("refreshInterval", m_refreshInterval); qSettings->setValue("plotCurveCount", plotCurveCount); - for(plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) - { + for (plotDatasLoadIndex = 0; plotDatasLoadIndex < plotCurveCount; plotDatasLoadIndex++) { qSettings->beginGroup(QString("plotCurve") + QString().number(plotDatasLoadIndex)); - PlotCurveConfiguration* plotCurveConf = m_PlotCurveConfigs.at(plotDatasLoadIndex); - qSettings->setValue("uavObject", plotCurveConf->uavObject); - qSettings->setValue("uavField", plotCurveConf->uavField); - qSettings->setValue("color", plotCurveConf->color); - qSettings->setValue("mathFunction", plotCurveConf->mathFunction); - qSettings->setValue("yScalePower", plotCurveConf->yScalePower); - qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); - qSettings->setValue("yMinimum", plotCurveConf->yMinimum); - qSettings->setValue("yMaximum", plotCurveConf->yMaximum); + PlotCurveConfiguration *plotCurveConf = m_plotCurveConfigs.at(plotDatasLoadIndex); + qSettings->setValue("uavObject", plotCurveConf->uavObject); + qSettings->setValue("uavField", plotCurveConf->uavField); + qSettings->setValue("color", plotCurveConf->color); + qSettings->setValue("mathFunction", plotCurveConf->mathFunction); + qSettings->setValue("yScalePower", plotCurveConf->yScalePower); + qSettings->setValue("yMeanSamples", plotCurveConf->yMeanSamples); + qSettings->setValue("yMinimum", plotCurveConf->yMinimum); + qSettings->setValue("yMaximum", plotCurveConf->yMaximum); + qSettings->setValue("drawAntialiased", plotCurveConf->drawAntialiased); qSettings->endGroup(); } - qSettings->setValue("LoggingEnabled", m_LoggingEnabled); - qSettings->setValue("LoggingNewFileOnConnect", m_LoggingNewFileOnConnect); - qSettings->setValue("LoggingPath", m_LoggingPath); - - + qSettings->setValue("LoggingEnabled", m_loggingEnabled); + qSettings->setValue("LoggingNewFileOnConnect", m_loggingNewFileOnConnect); + qSettings->setValue("LoggingPath", m_loggingPath); } -void ScopeGadgetConfiguration::replacePlotCurveConfig(QList newPlotCurveConfigs) +void ScopeGadgetConfiguration::replacePlotCurveConfig(QList newPlotCurveConfigs) { clearPlotData(); - m_PlotCurveConfigs.append(newPlotCurveConfigs); + m_plotCurveConfigs.append(newPlotCurveConfigs); } ScopeGadgetConfiguration::~ScopeGadgetConfiguration() diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h index 5fcb488e2..924a6786c 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h @@ -35,66 +35,117 @@ using namespace Core; -struct PlotCurveConfiguration -{ +struct PlotCurveConfiguration { QString uavObject; QString uavField; - int yScalePower; //This is the power to which each value must be raised - QRgb color; - int yMeanSamples; + int yScalePower; // This is the power to which each value must be raised + QRgb color; + int yMeanSamples; QString mathFunction; - double yMinimum; - double yMaximum; + double yMinimum; + double yMaximum; + bool drawAntialiased; }; -class ScopeGadgetConfiguration : public IUAVGadgetConfiguration -{ +class ScopeGadgetConfiguration : public IUAVGadgetConfiguration { Q_OBJECT public: - explicit ScopeGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + explicit ScopeGadgetConfiguration(QString classId, QSettings *qSettings = 0, QObject *parent = 0); ~ScopeGadgetConfiguration(); - //configuration setter functions - void setPlotType(int value){m_plotType = value;} - void setMathFunctionType(int value){m_mathFunctionType = value;} - void setDataSize(int value){m_dataSize = value;} - void setRefreashInterval(int value){m_refreshInterval = value;} - void addPlotCurveConfig(PlotCurveConfiguration* value){m_PlotCurveConfigs.append(value);} - void replacePlotCurveConfig(QList m_PlotCurveConfigs); + // configuration setter functions + void setPlotType(int value) + { + m_plotType = value; + } + void setMathFunctionType(int value) + { + m_mathFunctionType = value; + } + void setDataSize(int value) + { + m_dataSize = value; + } + void setRefreashInterval(int value) + { + m_refreshInterval = value; + } + void addPlotCurveConfig(PlotCurveConfiguration *value) + { + m_plotCurveConfigs.append(value); + } + void replacePlotCurveConfig(QList m_plotCurveConfigs); - //configurations getter functions - int plotType(){return m_plotType;} - int mathFunctionType(){return m_mathFunctionType;} - int dataSize(){return m_dataSize;} - int refreshInterval(){return m_refreshInterval;} - QList plotCurveConfigs(){return m_PlotCurveConfigs;} + // Configurations getter functions + int plotType() + { + return m_plotType; + } + int mathFunctionType() + { + return m_mathFunctionType; + } + int dataSize() + { + return m_dataSize; + } + int refreshInterval() + { + return m_refreshInterval; + } + QList plotCurveConfigs() + { + return m_plotCurveConfigs; + } - void saveConfig(QSettings* settings) const; //THIS SEEMS TO BE UNUSED + void saveConfig(QSettings *settings) const; // THIS SEEMS TO BE UNUSED IUAVGadgetConfiguration *clone(); - bool getLoggingEnabled(){return m_LoggingEnabled;}; - bool getLoggingNewFileOnConnect(){return m_LoggingNewFileOnConnect;}; - QString getLoggingPath(){return m_LoggingPath;}; - void setLoggingEnabled(bool value){m_LoggingEnabled=value;}; - void setLoggingNewFileOnConnect(bool value){m_LoggingNewFileOnConnect=value;}; - void setLoggingPath(QString value){m_LoggingPath=value;}; + bool getLoggingEnabled() + { + return m_loggingEnabled; + } + bool getLoggingNewFileOnConnect() + { + return m_loggingNewFileOnConnect; + } + QString getLoggingPath() + { + return m_loggingPath; + } + void setLoggingEnabled(bool value) + { + m_loggingEnabled = value; + } + void setLoggingNewFileOnConnect(bool value) + { + m_loggingNewFileOnConnect = value; + } + void setLoggingPath(QString value) + { + m_loggingPath = value; + } private: - static const uint m_configurationStreamVersion = 1000;//Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded. - int m_plotType; //The type of the plot - int m_dataSize; //The size of the data buffer to render in the curve plot - int m_refreshInterval; //The interval to replot the curve widget. The data buffer is refresh as the data comes in. - int m_mathFunctionType; //The type of math function to be used in the scope analysis - QList m_PlotCurveConfigs; + // Increment this if the stream format is not compatible with previous versions. This would cause existing configs to be discarded. + static const uint m_configurationStreamVersion = 1000; + // The type of the plot + int m_plotType; + // The size of the data buffer to render in the curve plot + int m_dataSize; + // The interval to replot the curve widget. The data buffer is refresh as the data comes in. + int m_refreshInterval; + // The type of math function to be used in the scope analysis + int m_mathFunctionType; + QList m_plotCurveConfigs; void clearPlotData(); - bool m_LoggingEnabled; - bool m_LoggingNewFileOnConnect; - QString m_LoggingPath; - + bool m_loggingEnabled; + bool m_loggingNewFileOnConnect; + QString m_loggingPath; }; #endif // SCOPEGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp index 06111931f..e0c0a0143 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp @@ -36,96 +36,98 @@ ScopeGadgetOptionsPage::ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - m_config(config) + IOptionsPage(parent), + m_config(config) { - //nothing to do here... + // nothing to do here... } -//creates options page widget (uses the UI file) -QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) +// creates options page widget (uses the UI file) +QWidget *ScopeGadgetOptionsPage::createPage(QWidget *parent) { Q_UNUSED(parent); options_page = new Ui::ScopeGadgetOptionsPage(); - //main widget + // main widget QWidget *optionsPageWidget = new QWidget; - //main layout + // main layout options_page->setupUi(optionsPageWidget); - options_page->cmbPlotType->addItem("Sequential Plot",""); - options_page->cmbPlotType->addItem("Chronological Plot",""); + options_page->cmbPlotType->addItem("Sequential Plot", ""); + options_page->cmbPlotType->addItem("Chronological Plot", ""); // Fills the combo boxes for the UAVObjects ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { + QList< QList > objList = objManager->getDataObjects(); + foreach(QList list, objList) { + foreach(UAVDataObject * obj, list) { options_page->cmbUAVObjects->addItem(obj->getName()); } } - //Connect signals to slots cmbUAVObjects.currentIndexChanged + // Connect signals to slots cmbUAVObjects.currentIndexChanged connect(options_page->cmbUAVObjects, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_cmbUAVObjects_currentIndexChanged(QString))); options_page->mathFunctionComboBox->addItem("None"); options_page->mathFunctionComboBox->addItem("Boxcar average"); options_page->mathFunctionComboBox->addItem("Standard deviation"); - if(options_page->cmbUAVObjects->currentIndex() >= 0) + if (options_page->cmbUAVObjects->currentIndex() >= 0) { on_cmbUAVObjects_currentIndexChanged(options_page->cmbUAVObjects->currentText()); + } options_page->cmbScale->addItem("10^-9", -9); options_page->cmbScale->addItem("10^-6", -6); - options_page->cmbScale->addItem("10^-5",-5); - options_page->cmbScale->addItem("10^-4",-4); - options_page->cmbScale->addItem("10^-3",-3); - options_page->cmbScale->addItem("10^-2",-2); - options_page->cmbScale->addItem("10^-1",-1); - options_page->cmbScale->addItem("1",0); - options_page->cmbScale->addItem("10^1",1); - options_page->cmbScale->addItem("10^2",2); - options_page->cmbScale->addItem("10^3",3); - options_page->cmbScale->addItem("10^4",4); - options_page->cmbScale->addItem("10^5",5); - options_page->cmbScale->addItem("10^6",6); - options_page->cmbScale->addItem("10^9",9); - options_page->cmbScale->addItem("10^12",12); + options_page->cmbScale->addItem("10^-5", -5); + options_page->cmbScale->addItem("10^-4", -4); + options_page->cmbScale->addItem("10^-3", -3); + options_page->cmbScale->addItem("10^-2", -2); + options_page->cmbScale->addItem("10^-1", -1); + options_page->cmbScale->addItem("1", 0); + options_page->cmbScale->addItem("10^1", 1); + options_page->cmbScale->addItem("10^2", 2); + options_page->cmbScale->addItem("10^3", 3); + options_page->cmbScale->addItem("10^4", 4); + options_page->cmbScale->addItem("10^5", 5); + options_page->cmbScale->addItem("10^6", 6); + options_page->cmbScale->addItem("10^9", 9); + options_page->cmbScale->addItem("10^12", 12); options_page->cmbScale->setCurrentIndex(7); - //Set widget values from settings + // Set widget values from settings options_page->cmbPlotType->setCurrentIndex(m_config->plotType()); options_page->mathFunctionComboBox->setCurrentIndex(m_config->mathFunctionType()); options_page->spnDataSize->setValue(m_config->dataSize()); options_page->spnRefreshInterval->setValue(m_config->refreshInterval()); - //add the configured curves - foreach (PlotCurveConfiguration* plotData, m_config->plotCurveConfigs()) { - + // add the configured curves + foreach(PlotCurveConfiguration * plotData, m_config->plotCurveConfigs()) { QString uavObject = plotData->uavObject; QString uavField = plotData->uavField; int scale = plotData->yScalePower; int mean = plotData->yMeanSamples; QString mathFunction = plotData->mathFunction; QVariant varColor = plotData->color; + bool antialiased = plotData->drawAntialiased; - addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); + addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); } - if(m_config->plotCurveConfigs().count() > 0) + if (m_config->plotCurveConfigs().count() > 0) { options_page->lstCurves->setCurrentRow(0, QItemSelectionModel::ClearAndSelect); + } connect(options_page->btnAddCurve, SIGNAL(clicked()), this, SLOT(on_btnAddCurve_clicked())); connect(options_page->btnRemoveCurve, SIGNAL(clicked()), this, SLOT(on_btnRemoveCurve_clicked())); connect(options_page->lstCurves, SIGNAL(currentRowChanged(int)), this, SLOT(on_lstCurves_currentRowChanged(int))); connect(options_page->btnColor, SIGNAL(clicked()), this, SLOT(on_btnColor_clicked())); connect(options_page->mathFunctionComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(on_mathFunctionComboBox_currentIndexChanged(int))); - connect(options_page->spnRefreshInterval, SIGNAL(valueChanged(int )), this, SLOT(on_spnRefreshInterval_valueChanged(int))); + connect(options_page->spnRefreshInterval, SIGNAL(valueChanged(int)), this, SLOT(on_spnRefreshInterval_valueChanged(int))); setYAxisWidgetFromPlotCurve(); - //logging path setup + // logging path setup options_page->LoggingPath->setExpectedKind(Utils::PathChooser::Directory); options_page->LoggingPath->setPromptDialogTitle(tr("Choose Logging Directory")); options_page->LoggingPath->setPath(m_config->getLoggingPath()); @@ -134,89 +136,91 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) connect(options_page->LoggingEnable, SIGNAL(clicked()), this, SLOT(on_loggingEnable_clicked())); on_loggingEnable_clicked(); - //Disable mouse wheel events - foreach( QSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + // Disable mouse wheel events + foreach(QSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QDoubleSpinBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QDoubleSpinBox * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QSlider * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QSlider * sp, findChildren()) { + sp->installEventFilter(this); } - foreach( QComboBox * sp, findChildren() ) { - sp->installEventFilter( this ); + foreach(QComboBox * sp, findChildren()) { + sp->installEventFilter(this); } - return optionsPageWidget; } -bool ScopeGadgetOptionsPage::eventFilter( QObject * obj, QEvent * evt ) { - //Filter all wheel events, and ignore them - if ( evt->type() == QEvent::Wheel && - (qobject_cast( obj ) || - qobject_cast( obj ) || - qobject_cast( obj ) )) - { +bool ScopeGadgetOptionsPage::eventFilter(QObject *obj, QEvent *evt) +{ + // Filter all wheel events, and ignore them + if (evt->type() == QEvent::Wheel && + (qobject_cast(obj) || + qobject_cast(obj) || + qobject_cast(obj))) { evt->ignore(); return true; } - return ScopeGadgetOptionsPage::eventFilter( obj, evt ); + return ScopeGadgetOptionsPage::eventFilter(obj, evt); } -void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex){ - if (currentIndex > 0){ +void ScopeGadgetOptionsPage::on_mathFunctionComboBox_currentIndexChanged(int currentIndex) +{ + if (currentIndex > 0) { options_page->spnMeanSamples->setEnabled(true); - } - else{ + } else { options_page->spnMeanSamples->setEnabled(false); } - } void ScopeGadgetOptionsPage::on_btnColor_clicked() - { - QColor color = QColorDialog::getColor( QColor(options_page->btnColor->text())); - if (color.isValid()) { - setButtonColor(color); - } - } +{ + QColor color = QColorDialog::getColor(QColor(options_page->btnColor->text())); + + if (color.isValid()) { + setButtonColor(color); + } +} /*! - \brief Populate the widgets that containts the configs for the Y-Axis from - the selected plot curve - */ + \brief Populate the widgets that containts the configs for the Y-Axis from + the selected plot curve + */ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve() { bool parseOK = false; - QListWidgetItem* listItem = options_page->lstCurves->currentItem(); + QListWidgetItem *listItem = options_page->lstCurves->currentItem(); - if(listItem == 0) + if (listItem == 0) { return; + } - //WHAT IS UserRole DOING? - int currentIndex = options_page->cmbUAVObjects->findText( listItem->data(Qt::UserRole + 0).toString()); + // WHAT IS UserRole DOING? + int currentIndex = options_page->cmbUAVObjects->findText(listItem->data(Qt::UserRole + 0).toString()); options_page->cmbUAVObjects->setCurrentIndex(currentIndex); - currentIndex = options_page->cmbUAVField->findText( listItem->data(Qt::UserRole + 1).toString()); + currentIndex = options_page->cmbUAVField->findText(listItem->data(Qt::UserRole + 1).toString()); options_page->cmbUAVField->setCurrentIndex(currentIndex); - currentIndex = options_page->cmbScale->findData( listItem->data(Qt::UserRole + 2), Qt::UserRole, Qt::MatchExactly); + currentIndex = options_page->cmbScale->findData(listItem->data(Qt::UserRole + 2), Qt::UserRole, Qt::MatchExactly); options_page->cmbScale->setCurrentIndex(currentIndex); - QVariant varColor = listItem->data(Qt::UserRole + 3); + QVariant varColor = listItem->data(Qt::UserRole + 3); int rgb = varColor.toInt(&parseOK); setButtonColor(QColor((QRgb)rgb)); int mean = listItem->data(Qt::UserRole + 4).toInt(&parseOK); - if(!parseOK) mean = 1; + if (!parseOK) { + mean = 1; + } options_page->spnMeanSamples->setValue(mean); - currentIndex = options_page->mathFunctionComboBox->findText( listItem->data(Qt::UserRole + 5).toString()); + currentIndex = options_page->mathFunctionComboBox->findText(listItem->data(Qt::UserRole + 5).toString()); options_page->mathFunctionComboBox->setCurrentIndex(currentIndex); - + options_page->drawAntialiasedCheckBox->setChecked(listItem->data(Qt::UserRole + 6).toBool()); } void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) @@ -227,33 +231,32 @@ void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) } /*! - \brief When a new UAVObject is selected, populate the UAVObject field combo box with the correct values. - */ + \brief When a new UAVObject is selected, populate the UAVObject field combo box with the correct values. + */ void ScopeGadgetOptionsPage::on_cmbUAVObjects_currentIndexChanged(QString val) { options_page->cmbUAVField->clear(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast( objManager->getObject(val) ); + UAVDataObject *obj = dynamic_cast(objManager->getObject(val)); - if (obj == NULL) + if (obj == NULL) { return; // Rare case: the config contained a UAVObject name which does not exist anymore. - - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if(field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM ) + } + QList fieldList = obj->getFields(); + foreach(UAVObjectField * field, fieldList) { + if (field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM) { continue; + } - if(field->getElementNames().count() > 1) - { - foreach(QString elemName , field->getElementNames()) - { + if (field->getElementNames().count() > 1) { + foreach(QString elemName, field->getElementNames()) { options_page->cmbUAVField->addItem(field->getName() + "-" + elemName); } - } - else + } else { options_page->cmbUAVField->addItem(field->getName()); + } } } @@ -267,130 +270,131 @@ void ScopeGadgetOptionsPage::apply() { bool parseOK = false; - //Apply configuration changes + // Apply configuration changes m_config->setPlotType(options_page->cmbPlotType->currentIndex()); m_config->setMathFunctionType(options_page->mathFunctionComboBox->currentIndex()); m_config->setDataSize(options_page->spnDataSize->value()); m_config->setRefreashInterval(options_page->spnRefreshInterval->value()); - QList plotCurveConfigs; - for(int iIndex = 0; iIndex < options_page->lstCurves->count();iIndex++) { - QListWidgetItem* listItem = options_page->lstCurves->item(iIndex); + QList plotCurveConfigs; + for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) { + QListWidgetItem *listItem = options_page->lstCurves->item(iIndex); - PlotCurveConfiguration* newPlotCurveConfigs = new PlotCurveConfiguration(); - newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString(); - newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString(); - newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK); - if(!parseOK) + PlotCurveConfiguration *newPlotCurveConfigs = new PlotCurveConfiguration(); + newPlotCurveConfigs->uavObject = listItem->data(Qt::UserRole + 0).toString(); + newPlotCurveConfigs->uavField = listItem->data(Qt::UserRole + 1).toString(); + newPlotCurveConfigs->yScalePower = listItem->data(Qt::UserRole + 2).toInt(&parseOK); + if (!parseOK) { newPlotCurveConfigs->yScalePower = 0; + } - QVariant varColor = listItem->data(Qt::UserRole + 3); + QVariant varColor = listItem->data(Qt::UserRole + 3); int rgb = varColor.toInt(&parseOK); - if(!parseOK) + if (!parseOK) { newPlotCurveConfigs->color = QColor(Qt::black).rgb(); - else + } else { newPlotCurveConfigs->color = (QRgb)rgb; + } newPlotCurveConfigs->yMeanSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); - if(!parseOK) + if (!parseOK) { newPlotCurveConfigs->yMeanSamples = 1; + } - newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString(); - + newPlotCurveConfigs->mathFunction = listItem->data(Qt::UserRole + 5).toString(); + newPlotCurveConfigs->drawAntialiased = listItem->data(Qt::UserRole + 6).toBool(); plotCurveConfigs.append(newPlotCurveConfigs); } m_config->replacePlotCurveConfig(plotCurveConfigs); - //save the logging config + // save the logging config m_config->setLoggingPath(options_page->LoggingPath->path()); m_config->setLoggingNewFileOnConnect(options_page->LoggingConnect->isChecked()); m_config->setLoggingEnabled(options_page->LoggingEnable->isChecked()); - } /*! - \brief Add a new curve to the plot. -*/ + \brief Add a new curve to the plot. + */ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() { - bool parseOK = false; + bool parseOK = false; QString uavObject = options_page->cmbUAVObjects->currentText(); - QString uavField = options_page->cmbUAVField->currentText(); + QString uavField = options_page->cmbUAVField->currentText(); int scale = options_page->cmbScale->itemData(options_page->cmbScale->currentIndex()).toInt(&parseOK); - if(!parseOK) - scale = 0; + if (!parseOK) { + scale = 0; + } int mean = options_page->spnMeanSamples->value(); QString mathFunction = options_page->mathFunctionComboBox->currentText(); - QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); + QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); - //Find an existing plot curve config based on the uavobject and uav field. If it - //exists, update it, else add a new one. - if(options_page->lstCurves->count() && - options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) - { + bool antialiased = options_page->drawAntialiasedCheckBox->isChecked(); + // Find an existing plot curve config based on the uavobject and uav field. If it + // exists, update it, else add a new one. + if (options_page->lstCurves->count() && + options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) { QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem(); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); - }else - { - addPlotCurveConfig(uavObject,uavField,scale,mean,mathFunction,varColor); + setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); + } else { + addPlotCurveConfig(uavObject, uavField, scale, mean, mathFunction, varColor, antialiased); options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1); } } -void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) +void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias) { - //Add a new curve config to the list - QString listItemDisplayText = uavObject + "." + uavField; + // Add a new curve config to the list + QString listItemDisplayText = uavObject + "." + uavField; + options_page->lstCurves->addItem(listItemDisplayText); QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,mean,mathFunction,varColor); - + setCurvePlotProperties(listWidgetItem, uavObject, uavField, scale, mean, mathFunction, varColor, antialias); } -void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor) +void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, + int mean, QString mathFunction, QVariant varColor, bool antialias) { bool parseOK = false; - //Set the properties of the newly added list item - QString listItemDisplayText = uavObject + "." + uavField; + // Set the properties of the newly added list item QRgb rgbColor = (QRgb)varColor.toInt(&parseOK); - QColor color = QColor( rgbColor ); - //listWidgetItem->setText(listItemDisplayText); - listWidgetItem->setTextColor( color ); + QColor color = QColor(rgbColor); - //Store some additional data for the plot curve on the list item - listWidgetItem->setData(Qt::UserRole + 0,QVariant(uavObject)); - listWidgetItem->setData(Qt::UserRole + 1,QVariant(uavField)); - listWidgetItem->setData(Qt::UserRole + 2,QVariant(scale)); - listWidgetItem->setData(Qt::UserRole + 3,varColor); - listWidgetItem->setData(Qt::UserRole + 4,QVariant(mean)); - listWidgetItem->setData(Qt::UserRole + 5,QVariant(mathFunction)); + listWidgetItem->setTextColor(color); + + // Store some additional data for the plot curve on the list item + listWidgetItem->setData(Qt::UserRole + 0, QVariant(uavObject)); + listWidgetItem->setData(Qt::UserRole + 1, QVariant(uavField)); + listWidgetItem->setData(Qt::UserRole + 2, QVariant(scale)); + listWidgetItem->setData(Qt::UserRole + 3, varColor); + listWidgetItem->setData(Qt::UserRole + 4, QVariant(mean)); + listWidgetItem->setData(Qt::UserRole + 5, QVariant(mathFunction)); + listWidgetItem->setData(Qt::UserRole + 6, QVariant(antialias)); } /*! - Remove a curve config from the plot. - */ + Remove a curve config from the plot. + */ void ScopeGadgetOptionsPage::on_btnRemoveCurve_clicked() { options_page->lstCurves->takeItem(options_page->lstCurves->currentIndex().row()); } void ScopeGadgetOptionsPage::finish() -{ - -} +{} /*! - When a different plot curve config is selected, populate its values into the widgets. - */ + When a different plot curve config is selected, populate its values into the widgets. + */ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow) { Q_UNUSED(currentRow); @@ -398,15 +402,15 @@ void ScopeGadgetOptionsPage::on_lstCurves_currentRowChanged(int currentRow) } void ScopeGadgetOptionsPage::on_loggingEnable_clicked() - { +{ bool en = options_page->LoggingEnable->isChecked(); + options_page->LoggingPath->setEnabled(en); options_page->LoggingConnect->setEnabled(en); options_page->LoggingLabel->setEnabled(en); +} - } - -void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int ) +void ScopeGadgetOptionsPage::on_spnRefreshInterval_valueChanged(int) { validateRefreshInterval(); } @@ -415,19 +419,19 @@ void ScopeGadgetOptionsPage::validateRefreshInterval() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - for(int iIndex = 0; iIndex < options_page->lstCurves->count();iIndex++) { - QListWidgetItem* listItem = options_page->lstCurves->item(iIndex); - QString uavObject = listItem->data(Qt::UserRole + 0).toString(); + for (int iIndex = 0; iIndex < options_page->lstCurves->count(); iIndex++) { + QListWidgetItem *listItem = options_page->lstCurves->item(iIndex); - UAVDataObject* obj = dynamic_cast(objManager->getObject((uavObject))); - if(!obj) { + QString uavObject = listItem->data(Qt::UserRole + 0).toString(); + + UAVDataObject *obj = dynamic_cast(objManager->getObject((uavObject))); + if (!obj) { qDebug() << "Object " << uavObject << " is missing"; continue; } - if(options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod) - { + if (options_page->spnRefreshInterval->value() < obj->getMetadata().flightTelemetryUpdatePeriod) { options_page->lblWarnings->setText("The refresh interval is faster than some or all telemetry objects."); return; } @@ -435,4 +439,3 @@ void ScopeGadgetOptionsPage::validateRefreshInterval() options_page->lblWarnings->setText(""); } - diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h index 009f02337..e02c897bd 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h @@ -38,22 +38,19 @@ #include #include -namespace Core -{ +namespace Core { class IUAVGadgetConfiguration; } class ScopeGadgetConfiguration; -namespace Ui -{ +namespace Ui { class ScopeGadgetOptionsPage; } using namespace Core; -class ScopeGadgetOptionsPage : public IOptionsPage -{ +class ScopeGadgetOptionsPage : public IOptionsPage { Q_OBJECT public: explicit ScopeGadgetOptionsPage(ScopeGadgetConfiguration *config, QObject *parent = 0); @@ -66,23 +63,23 @@ private: Ui::ScopeGadgetOptionsPage *options_page; ScopeGadgetConfiguration *m_config; - void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); - void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor); + void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int mean, QString mathFunction, QVariant varColor, bool antialias); + void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int mean, + QString mathFunction, QVariant varColor, bool antialias); void setYAxisWidgetFromPlotCurve(); void setButtonColor(const QColor &color); void validateRefreshInterval(); - bool eventFilter( QObject * obj, QEvent * evt ); + bool eventFilter(QObject *obj, QEvent *evt); private slots: - void on_spnRefreshInterval_valueChanged(int ); + void on_spnRefreshInterval_valueChanged(int); void on_lstCurves_currentRowChanged(int currentRow); void on_btnRemoveCurve_clicked(); void on_btnAddCurve_clicked(); - void on_cmbUAVObjects_currentIndexChanged(QString val); + void on_cmbUAVObjects_currentIndexChanged(QString val); void on_btnColor_clicked(); void on_mathFunctionComboBox_currentIndexChanged(int currentIndex); void on_loggingEnable_clicked(); - }; #endif // SCOPEGADGETOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index e5da31784..7ae473fa1 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -176,38 +176,18 @@ - - + + - Color: + Math function: - - + + Qt::StrongFocus - - Choose - - - - - - - Y-axis scale factor: - - - - - - - Qt::StrongFocus - - - false - @@ -248,18 +228,51 @@ - - + + - Math function: + Color: - - + + Qt::StrongFocus + + Choose + + + + + + + Y-axis scale factor: + + + + + + + Qt::StrongFocus + + + false + + + + + + + Check this to have the curve drawn antialiased. + + + Draw Antialiased + + + true + @@ -277,7 +290,7 @@ 20 - 100 + 40 @@ -288,8 +301,7 @@ Add a new curve to the scope, or update it if the UAVObject and UAVField is the same. - Add -Update + Add / Update @@ -299,8 +311,7 @@ Update Remove the curve from the scope. - Remove - + Remove @@ -310,12 +321,12 @@ Update Qt::Vertical - QSizePolicy::Fixed + QSizePolicy::Expanding 20 - 15 + 40 @@ -331,8 +342,8 @@ Update - 0 - 200 + 20 + 40 @@ -347,6 +358,19 @@ Update + + + + Qt::Vertical + + + + 20 + 40 + + + + diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index e1775ace0..661ac3035 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -53,16 +53,16 @@ #include #include -//using namespace Core; +// using namespace Core; // ****************************************************************** ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent) { - setMouseTracking(true); -// canvas()->setMouseTracking(true); + setMouseTracking(true); +// canvas()->setMouseTracking(true); - //Setup the timer that replots data + // Setup the timer that replots data replotTimer = new QTimer(this); connect(replotTimer, SIGNAL(timeout()), this, SLOT(replotNewData())); @@ -71,179 +71,191 @@ ScopeGadgetWidget::ScopeGadgetWidget(QWidget *parent) : QwtPlot(parent) // Also listen to disconnect actions from the user Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); connect(cm, SIGNAL(deviceAboutToDisconnect()), this, SLOT(stopPlotting())); - connect(cm, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(startPlotting())); + connect(cm, SIGNAL(deviceConnected(QIODevice *)), this, SLOT(startPlotting())); - m_csvLoggingStarted=0; - m_csvLoggingEnabled=0; - m_csvLoggingHeaderSaved=0; - m_csvLoggingDataSaved=0; - m_csvLoggingDataUpdated=0; - m_csvLoggingNameSet=0; - m_csvLoggingConnected=0; - m_csvLoggingNewFileOnConnect=0; + m_csvLoggingStarted = 0; + m_csvLoggingEnabled = 0; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingDataSaved = 0; + m_csvLoggingDataUpdated = 0; + m_csvLoggingNameSet = 0; + m_csvLoggingConnected = 0; + m_csvLoggingNewFileOnConnect = 0; m_csvLoggingPath = QString("./csvlogging/"); - m_csvLoggingStartTime = QDateTime::currentDateTime(); + m_csvLoggingStartTime = QDateTime::currentDateTime(); - //Listen to autopilot connection events + // Listen to autopilot connection events connect(cm, SIGNAL(deviceAboutToDisconnect()), this, SLOT(csvLoggingDisconnect())); - connect(cm, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(csvLoggingConnect())); + connect(cm, SIGNAL(deviceConnected(QIODevice *)), this, SLOT(csvLoggingConnect())); } ScopeGadgetWidget::~ScopeGadgetWidget() { - if (replotTimer) - { - replotTimer->stop(); + if (replotTimer) { + replotTimer->stop(); - delete replotTimer; - replotTimer = NULL; - } + delete replotTimer; + replotTimer = NULL; + } - // Get the object to de-monitor - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - foreach (QString uavObjName, m_connectedUAVObjects) - { - UAVDataObject *obj = dynamic_cast(objManager->getObject(uavObjName)); - disconnect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(uavObjectReceived(UAVObject*))); - } + // Get the object to de-monitor + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + foreach(QString uavObjName, m_connectedUAVObjects) { + UAVDataObject *obj = dynamic_cast(objManager->getObject(uavObjName)); - clearCurvePlots(); + disconnect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *))); + } + + clearCurvePlots(); } // ****************************************************************** void ScopeGadgetWidget::mousePressEvent(QMouseEvent *e) { - QwtPlot::mousePressEvent(e); + QwtPlot::mousePressEvent(e); } void ScopeGadgetWidget::mouseReleaseEvent(QMouseEvent *e) { - QwtPlot::mouseReleaseEvent(e); + QwtPlot::mouseReleaseEvent(e); } void ScopeGadgetWidget::mouseDoubleClickEvent(QMouseEvent *e) { - //On double-click, toggle legend + // On double-click, toggle legend mutex.lock(); - if (legend()) + if (legend()) { deleteLegend(); - else + } else { addLegend(); + } mutex.unlock(); - //On double-click, reset plot zoom + // On double-click, reset plot zoom setAxisAutoScale(QwtPlot::yLeft, true); update(); - QwtPlot::mouseDoubleClickEvent(e); + QwtPlot::mouseDoubleClickEvent(e); } void ScopeGadgetWidget::mouseMoveEvent(QMouseEvent *e) { - QwtPlot::mouseMoveEvent(e); + QwtPlot::mouseMoveEvent(e); } void ScopeGadgetWidget::wheelEvent(QWheelEvent *e) { - //Change zoom on scroll wheel event - QwtInterval yInterval=axisInterval(QwtPlot::yLeft); - if (yInterval.minValue() != yInterval.maxValue()) //Make sure that the two values are never the same. Sometimes axisInterval returns (0,0) - { - //Determine what y value to zoom about. NOTE, this approach has a bug that the in that - //the value returned by Qt includes the legend, whereas the value transformed by Qwt - //does *not*. Thus, when zooming with a legend, there will always be a small bias error. - //In practice, this seems not to be a UI problem. - QPoint mouse_pos=e->pos(); //Get the mouse coordinate in the frame - double zoomLine=invTransform(QwtPlot::yLeft, mouse_pos.y()); //Transform the y mouse coordinate into a frame value. + // Change zoom on scroll wheel event + QwtInterval yInterval = axisInterval(QwtPlot::yLeft); - double zoomScale=1.1; //THIS IS AN ARBITRARY CONSTANT, AND PERHAPS SHOULD BE IN A DEFINE INSTEAD OF BURIED HERE + if (yInterval.minValue() != yInterval.maxValue()) { // Make sure that the two values are never the same. Sometimes axisInterval returns (0,0) + // Determine what y value to zoom about. NOTE, this approach has a bug that the in that + // the value returned by Qt includes the legend, whereas the value transformed by Qwt + // does *not*. Thus, when zooming with a legend, there will always be a small bias error. + // In practice, this seems not to be a UI problem. + QPoint mouse_pos = e->pos(); // Get the mouse coordinate in the frame + double zoomLine = invTransform(QwtPlot::yLeft, mouse_pos.y()); // Transform the y mouse coordinate into a frame value. - mutex.lock(); //DOES THIS mutex.lock NEED TO BE HERE? I DON'T KNOW, I JUST COPIED IT FROM THE ABOVE CODE + double zoomScale = 1.1; // THIS IS AN ARBITRARY CONSTANT, AND PERHAPS SHOULD BE IN A DEFINE INSTEAD OF BURIED HERE + + mutex.lock(); // DOES THIS mutex.lock NEED TO BE HERE? I DON'T KNOW, I JUST COPIED IT FROM THE ABOVE CODE // Set the scale - if (e->delta()<0){ + if (e->delta() < 0) { setAxisScale(QwtPlot::yLeft, - (yInterval.minValue()-zoomLine)*zoomScale+zoomLine, - (yInterval.maxValue()-zoomLine)*zoomScale+zoomLine ); - } - else{ + (yInterval.minValue() - zoomLine) * zoomScale + zoomLine, + (yInterval.maxValue() - zoomLine) * zoomScale + zoomLine); + } else { setAxisScale(QwtPlot::yLeft, - (yInterval.minValue()-zoomLine)/zoomScale+zoomLine, - (yInterval.maxValue()-zoomLine)/zoomScale+zoomLine ); + (yInterval.minValue() - zoomLine) / zoomScale + zoomLine, + (yInterval.maxValue() - zoomLine) / zoomScale + zoomLine); } mutex.unlock(); } QwtPlot::wheelEvent(e); } +void ScopeGadgetWidget::showEvent(QShowEvent *e) +{ + replotNewData(); + QwtPlot::showEvent(e); +} + /** * Starts/stops telemetry */ void ScopeGadgetWidget::startPlotting() { - if (!replotTimer) - return; + if (!replotTimer) { + return; + } - if (!replotTimer->isActive()) + if (!replotTimer->isActive()) { replotTimer->start(m_refreshInterval); + } } void ScopeGadgetWidget::stopPlotting() { - if (!replotTimer) - return; + if (!replotTimer) { + return; + } - replotTimer->stop(); + replotTimer->stop(); } void ScopeGadgetWidget::deleteLegend() { - if (!legend()) - return; + if (!legend()) { + return; + } - disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0); + disconnect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, 0); - insertLegend(NULL, QwtPlot::TopLegend); -// insertLegend(NULL, QwtPlot::ExternalLegend); + insertLegend(NULL, QwtPlot::TopLegend); +// insertLegend(NULL, QwtPlot::ExternalLegend); } void ScopeGadgetWidget::addLegend() { - if (legend()) - return; + if (legend()) { + return; + } - // Show a legend at the top - QwtLegend *legend = new QwtLegend(); - legend->setItemMode(QwtLegend::CheckableItem); - legend->setFrameStyle(QFrame::Box | QFrame::Sunken); - legend->setToolTip(tr("Click legend to show/hide scope trace")); + // Show a legend at the top + QwtLegend *legend = new QwtLegend(); + legend->setItemMode(QwtLegend::CheckableItem); + legend->setFrameStyle(QFrame::Box | QFrame::Sunken); + legend->setToolTip(tr("Click legend to show/hide scope trace")); - QPalette pal = legend->palette(); - pal.setColor(legend->backgroundRole(), QColor(100, 100, 100)); // background colour -// pal.setColor(legend->backgroundRole(), Qt::transparent); // background colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour - pal.setColor(QPalette::Text, QColor(0, 0, 0)); // text colour - legend->setPalette(pal); + QPalette pal = legend->palette(); + pal.setColor(legend->backgroundRole(), QColor(100, 100, 100)); // background colour +// pal.setColor(legend->backgroundRole(), Qt::transparent); // background colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour + pal.setColor(QPalette::Text, QColor(0, 0, 0)); // text colour + legend->setPalette(pal); - insertLegend(legend, QwtPlot::TopLegend); -// insertLegend(legend, QwtPlot::ExternalLegend); + insertLegend(legend, QwtPlot::TopLegend); +// insertLegend(legend, QwtPlot::ExternalLegend); -// // Show a legend at the bottom -// QwtLegend *legend = new QwtLegend(); -// legend->setItemMode(QwtLegend::CheckableItem); -// legend->setFrameStyle(QFrame::Box | QFrame::Sunken); -// insertLegend(legend, QwtPlot::BottomLegend); +//// Show a legend at the bottom +// QwtLegend *legend = new QwtLegend(); +// legend->setItemMode(QwtLegend::CheckableItem); +// legend->setFrameStyle(QFrame::Box | QFrame::Sunken); +// insertLegend(legend, QwtPlot::BottomLegend); // Update the checked/unchecked state of the legend items // -> this is necessary when hiding a legend where some plots are - // not visible, and the un-hiding it. - foreach (QwtPlotItem *item, this->itemList()) { - bool on = item->isVisible(); + // not visible, and the un-hiding it. + foreach(QwtPlotItem * item, this->itemList()) { + bool on = item->isVisible(); QWidget *w = legend->find(item); - if ( w && w->inherits("QwtLegendItem") ) + + if (w && w->inherits("QwtLegendItem")) { ((QwtLegendItem *)w)->setChecked(!on); + } } connect(this, SIGNAL(legendChecked(QwtPlotItem *, bool)), this, SLOT(showCurve(QwtPlotItem *, bool))); @@ -258,18 +270,18 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType) setMinimumSize(64, 64); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); -// setMargin(1); +// setMargin(1); -// QPalette pal = palette(); -// QPalette::ColorRole cr = backgroundRole(); -// pal.setColor(cr, QColor(128, 128, 128)); // background colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour -// setPalette(pal); +// QPalette pal = palette(); +// QPalette::ColorRole cr = backgroundRole(); +// pal.setColor(cr, QColor(128, 128, 128)); // background colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour +// setPalette(pal); -// setCanvasBackground(Utils::StyleHelper::baseColor()); +// setCanvasBackground(Utils::StyleHelper::baseColor()); setCanvasBackground(QColor(64, 64, 64)); - //Add grid lines + // Add grid lines QwtPlotGrid *grid = new QwtPlotGrid; grid->setMajPen(QPen(Qt::gray, 0, Qt::DashLine)); grid->setMinPen(QPen(Qt::lightGray, 0, Qt::DotLine)); @@ -281,12 +293,12 @@ void ScopeGadgetWidget::preparePlot(PlotType plotType) // Only start the timer if we are already connected Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); - if (cm->getCurrentConnection() && replotTimer) - { - if (!replotTimer->isActive()) + if (cm->getCurrentConnection() && replotTimer) { + if (!replotTimer->isActive()) { replotTimer->start(m_refreshInterval); - else + } else { replotTimer->setInterval(m_refreshInterval); + } } } @@ -294,22 +306,23 @@ void ScopeGadgetWidget::showCurve(QwtPlotItem *item, bool on) { item->setVisible(!on); QWidget *w = legend()->find(item); - if ( w && w->inherits("QwtLegendItem") ) + if (w && w->inherits("QwtLegendItem")) { ((QwtLegendItem *)w)->setChecked(on); + } - mutex.lock(); - replot(); - mutex.unlock(); + mutex.lock(); + replot(); + mutex.unlock(); } void ScopeGadgetWidget::setupSequentialPlot() { preparePlot(SequentialPlot); -// QwtText title("Index"); +// QwtText title("Index"); //// title.setFont(QFont("Helvetica", 20)); -// title.font().setPointSize(title.font().pointSize() / 2); -// setAxisTitle(QwtPlot::xBottom, title); +// title.font().setPointSize(title.font().pointSize() / 2); +// setAxisTitle(QwtPlot::xBottom, title); //// setAxisTitle(QwtPlot::xBottom, "Index"); setAxisScaleDraw(QwtPlot::xBottom, new QwtScaleDraw()); @@ -317,175 +330,187 @@ void ScopeGadgetWidget::setupSequentialPlot() setAxisLabelRotation(QwtPlot::xBottom, 0.0); setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); - QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); + QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); - // reduce the gap between the scope canvas and the axis scale - scaleWidget->setMargin(0); + // reduce the gap between the scope canvas and the axis scale + scaleWidget->setMargin(0); - // reduce the axis font size - QFont fnt(axisFont(QwtPlot::xBottom)); - fnt.setPointSize(7); - setAxisFont(QwtPlot::xBottom, fnt); // x-axis - setAxisFont(QwtPlot::yLeft, fnt); // y-axis + // reduce the axis font size + QFont fnt(axisFont(QwtPlot::xBottom)); + fnt.setPointSize(7); + setAxisFont(QwtPlot::xBottom, fnt); // x-axis + setAxisFont(QwtPlot::yLeft, fnt); // y-axis } void ScopeGadgetWidget::setupChronoPlot() { preparePlot(ChronoPlot); -// QwtText title("Time [h:m:s]"); +// QwtText title("Time [h:m:s]"); //// title.setFont(QFont("Helvetica", 20)); -// title.font().setPointSize(title.font().pointSize() / 2); -// setAxisTitle(QwtPlot::xBottom, title); +// title.font().setPointSize(title.font().pointSize() / 2); +// setAxisTitle(QwtPlot::xBottom, title); //// setAxisTitle(QwtPlot::xBottom, "Time [h:m:s]"); setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw()); uint NOW = QDateTime::currentDateTime().toTime_t(); setAxisScale(QwtPlot::xBottom, NOW - m_xWindowSize / 1000, NOW); -// setAxisLabelRotation(QwtPlot::xBottom, -15.0); - setAxisLabelRotation(QwtPlot::xBottom, 0.0); - setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); -// setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignCenter | Qt::AlignBottom); +// setAxisLabelRotation(QwtPlot::xBottom, -15.0); + setAxisLabelRotation(QwtPlot::xBottom, 0.0); + setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignLeft | Qt::AlignBottom); +// setAxisLabelAlignment(QwtPlot::xBottom, Qt::AlignCenter | Qt::AlignBottom); - QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); -// QwtScaleDraw *scaleDraw = axisScaleDraw(); + QwtScaleWidget *scaleWidget = axisWidget(QwtPlot::xBottom); +// QwtScaleDraw *scaleDraw = axisScaleDraw(); - // reduce the gap between the scope canvas and the axis scale - scaleWidget->setMargin(0); + // reduce the gap between the scope canvas and the axis scale + scaleWidget->setMargin(0); - // reduce the axis font size - QFont fnt(axisFont(QwtPlot::xBottom)); - fnt.setPointSize(7); - setAxisFont(QwtPlot::xBottom, fnt); // x-axis - setAxisFont(QwtPlot::yLeft, fnt); // y-axis + // reduce the axis font size + QFont fnt(axisFont(QwtPlot::xBottom)); + fnt.setPointSize(7); + setAxisFont(QwtPlot::xBottom, fnt); // x-axis + setAxisFont(QwtPlot::yLeft, fnt); // y-axis - // set the axis colours .. can't seem to change the background colour :( -// QPalette pal = scaleWidget->palette(); -// QPalette::ColorRole cr = scaleWidget->backgroundRole(); -// pal.setColor(cr, QColor(128, 128, 128)); // background colour -// cr = scaleWidget->foregroundRole(); -// pal.setColor(cr, QColor(255, 255, 255)); // tick colour -// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour -// scaleWidget->setPalette(pal); + // set the axis colours .. can't seem to change the background colour :( +// QPalette pal = scaleWidget->palette(); +// QPalette::ColorRole cr = scaleWidget->backgroundRole(); +// pal.setColor(cr, QColor(128, 128, 128)); // background colour +// cr = scaleWidget->foregroundRole(); +// pal.setColor(cr, QColor(255, 255, 255)); // tick colour +// pal.setColor(QPalette::Text, QColor(255, 255, 255)); // text colour +// scaleWidget->setPalette(pal); /* - In situations, when there is a label at the most right position of the - scale, additional space is needed to display the overlapping part - of the label would be taken by reducing the width of scale and canvas. - To avoid this "jumping canvas" effect, we add a permanent margin. - We don't need to do the same for the left border, because there - is enough space for the overlapping label below the left scale. + In situations, when there is a label at the most right position of the + scale, additional space is needed to display the overlapping part + of the label would be taken by reducing the width of scale and canvas. + To avoid this "jumping canvas" effect, we add a permanent margin. + We don't need to do the same for the left border, because there + is enough space for the overlapping label below the left scale. */ -// const int fmh = QFontMetrics(scaleWidget->font()).height(); -// scaleWidget->setMinBorderDist(0, fmh / 2); +// const int fmh = QFontMetrics(scaleWidget->font()).height(); +// scaleWidget->setMinBorderDist(0, fmh / 2); -// const int fmw = QFontMetrics(scaleWidget->font()).width(" 00:00:00 "); -// const int fmw = QFontMetrics(scaleWidget->font()).width(" "); -// scaleWidget->setMinBorderDist(0, fmw); +// const int fmw = QFontMetrics(scaleWidget->font()).width(" 00:00:00 "); +// const int fmw = QFontMetrics(scaleWidget->font()).width(" "); +// scaleWidget->setMinBorderDist(0, fmw); } -void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen) +void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int meanSamples, QString mathFunction, QPen pen, bool antialiased) { - PlotData* plotData; + PlotData *plotData; - if (m_plotType == SequentialPlot) + if (m_plotType == SequentialPlot) { plotData = new SequentialPlotData(uavObject, uavFieldSubField); - else if (m_plotType == ChronoPlot) + } else if (m_plotType == ChronoPlot) { plotData = new ChronoPlotData(uavObject, uavFieldSubField); - //else if (m_plotType == UAVObjectPlot) - // plotData = new UAVObjectPlotData(uavObject, uavField); + } + // else if (m_plotType == UAVObjectPlot) + // plotData = new UAVObjectPlotData(uavObject, uavField); plotData->m_xWindowSize = m_xWindowSize; - plotData->scalePower = scaleOrderFactor; - plotData->meanSamples = meanSamples; - plotData->mathFunction = mathFunction; + plotData->scalePower = scaleOrderFactor; + plotData->meanSamples = meanSamples; + plotData->mathFunction = mathFunction; - //If the y-bounds are supplied, set them - if (plotData->yMinimum != plotData->yMaximum) - { - setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum); - } + // If the y-bounds are supplied, set them + if (plotData->yMinimum != plotData->yMaximum) { + setAxisScale(QwtPlot::yLeft, plotData->yMinimum, plotData->yMaximum); + } - //Create the curve + // Create the curve QString curveName = (plotData->uavObject) + "." + (plotData->uavField); - if(plotData->haveSubField) + if (plotData->haveSubField) { curveName = curveName.append("." + plotData->uavSubField); + } - //Get the uav object + // Get the uav object ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast(objManager->getObject((plotData->uavObject))); - if(!obj) { + UAVDataObject *obj = dynamic_cast(objManager->getObject((plotData->uavObject))); + if (!obj) { qDebug() << "Object " << plotData->uavObject << " is missing"; return; } - UAVObjectField* field = obj->getField(plotData->uavField); - if(!field) { + UAVObjectField *field = obj->getField(plotData->uavField); + if (!field) { qDebug() << "In scope gadget, in fields loaded from GCS config file, field" << plotData->uavField << " of object " << plotData->uavObject << " is missing"; return; } QString units = field->getUnits(); - if(units == 0) + if (units == 0) { units = QString(); + } QString curveNameScaled; - if(scaleOrderFactor == 0) + if (scaleOrderFactor == 0) { curveNameScaled = curveName + " (" + units + ")"; - else + } else { curveNameScaled = curveName + " (x10^" + QString::number(scaleOrderFactor) + " " + units + ")"; + } + + QwtPlotCurve *plotCurve = new QwtPlotCurve(curveNameScaled); + + if (antialiased) { + plotCurve->setRenderHint(QwtPlotCurve::RenderAntialiased); + } - QwtPlotCurve* plotCurve = new QwtPlotCurve(curveNameScaled); plotCurve->setPen(pen); plotCurve->setSamples(*plotData->xData, *plotData->yData); plotCurve->attach(this); plotData->curve = plotCurve; - //Keep the curve details for later + // Keep the curve details for later m_curvesData.insert(curveNameScaled, plotData); - //Link to the new signal data only if this UAVObject has not been connected yet + // Link to the new signal data only if this UAVObject has not been connected yet if (!m_connectedUAVObjects.contains(obj->getName())) { m_connectedUAVObjects.append(obj->getName()); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(uavObjectReceived(UAVObject*))); + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(uavObjectReceived(UAVObject *))); } - mutex.lock(); - replot(); - mutex.unlock(); + mutex.lock(); + replot(); + mutex.unlock(); } -//void ScopeGadgetWidget::removeCurvePlot(QString uavObject, QString uavField) -//{ -// QString curveName = uavObject + "." + uavField; +// void ScopeGadgetWidget::removeCurvePlot(QString uavObject, QString uavField) +// { +// QString curveName = uavObject + "." + uavField; // -// PlotData* plotData = m_curvesData.take(curveName); -// m_curvesData.remove(curveName); -// plotData->curve->detach(); +// PlotData* plotData = m_curvesData.take(curveName); +// m_curvesData.remove(curveName); +// plotData->curve->detach(); // -// delete plotData->curve; -// delete plotData; +// delete plotData->curve; +// delete plotData; // -// mutex.lock(); -// replot(); -// mutex.unlock(); -//} +// mutex.lock(); +// replot(); +// mutex.unlock(); +// } -void ScopeGadgetWidget::uavObjectReceived(UAVObject* obj) +void ScopeGadgetWidget::uavObjectReceived(UAVObject *obj) { - foreach(PlotData* plotData, m_curvesData.values()) { - if (plotData->append(obj)) m_csvLoggingDataUpdated=1; + foreach(PlotData * plotData, m_curvesData.values()) { + if (plotData->append(obj)) { + m_csvLoggingDataUpdated = 1; + } } csvLoggingAddData(); } void ScopeGadgetWidget::replotNewData() { - QMutexLocker locker(&mutex); + if (!isVisible()) { + return; + } - foreach(PlotData* plotData, m_curvesData.values()) - { + QMutexLocker locker(&mutex); + foreach(PlotData * plotData, m_curvesData.values()) { plotData->removeStaleData(); plotData->curve->setSamples(*plotData->xData, *plotData->yData); } @@ -493,66 +518,20 @@ void ScopeGadgetWidget::replotNewData() QDateTime NOW = QDateTime::currentDateTime(); double toTime = NOW.toTime_t(); toTime += NOW.time().msec() / 1000.0; - if (m_plotType == ChronoPlot) + if (m_plotType == ChronoPlot) { setAxisScale(QwtPlot::xBottom, toTime - m_xWindowSize, toTime); + } -// qDebug() << "replotNewData from " << NOW.addSecs(- m_xWindowSize) << " to " << NOW; +// qDebug() << "replotNewData from " << NOW.addSecs(- m_xWindowSize) << " to " << NOW; csvLoggingInsertData(); - replot(); + replot(); } -/* -void ScopeGadgetWidget::setupExamplePlot() -{ - preparePlot(SequentialPlot); - - // Show the axes - - setAxisTitle(xBottom, "x"); - setAxisTitle(yLeft, "y"); - - // Calculate the data, 500 points each - const int points = 500; - double x[ points ]; - double sn[ points ]; - double cs[ points ]; - double sg[ points ]; - - for (int i = 0; i < points; i++) { - x[i] = (3.0 * 3.14 / double(points)) * double(i); - sn[i] = 2.0 * sin(x[i]); - cs[i] = 3.0 * cos(x[i]); - sg[i] = (sn[i] > 0) ? 1 : ((sn[i] < 0) ? -1 : 0); - } - - // add curves - QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1"); - curve1->setPen(QPen(Qt::blue)); - QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2"); - curve2->setPen(QPen(Qt::red)); - QwtPlotCurve *curve3 = new QwtPlotCurve("Curve 3"); - curve3->setPen(QPen(Qt::green)); - - // copy the data into the curves - curve1->setSamples(x, sn, points); - curve2->setSamples(x, cs, points); - curve3->setSamples(x, sg, points); - curve1->attach(this); - curve2->attach(this); - curve3->attach(this); - - // finally, refresh the plot - mutex.lock(); - replot(); - mutex.unlock(); -} -*/ - void ScopeGadgetWidget::clearCurvePlots() { - foreach(PlotData* plotData, m_curvesData.values()) { + foreach(PlotData * plotData, m_curvesData.values()) { plotData->curve->detach(); delete plotData->curve; @@ -564,49 +543,42 @@ void ScopeGadgetWidget::clearCurvePlots() /* -int csvLoggingEnable; -int csvLoggingHeaderSaved; -int csvLoggingDataSaved; -QString csvLoggingPath; -QFile csvLoggingFile; -*/ + int csvLoggingEnable; + int csvLoggingHeaderSaved; + int csvLoggingDataSaved; + QString csvLoggingPath; + QFile csvLoggingFile; + */ int ScopeGadgetWidget::csvLoggingStart() { - if (!m_csvLoggingStarted) - if (m_csvLoggingEnabled) - if ((!m_csvLoggingNewFileOnConnect)||(m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) - { - QDateTime NOW = QDateTime::currentDateTime(); - m_csvLoggingStartTime = NOW; - m_csvLoggingHeaderSaved=0; - m_csvLoggingDataSaved=0; - m_csvLoggingBuffer.clear(); - QDir PathCheck(m_csvLoggingPath); - if (!PathCheck.exists()) - { - PathCheck.mkpath("./"); - } + if (!m_csvLoggingStarted) { + if (m_csvLoggingEnabled) { + if ((!m_csvLoggingNewFileOnConnect) || (m_csvLoggingNewFileOnConnect && m_csvLoggingConnected)) { + QDateTime NOW = QDateTime::currentDateTime(); + m_csvLoggingStartTime = NOW; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingDataSaved = 0; + m_csvLoggingBuffer.clear(); + QDir PathCheck(m_csvLoggingPath); + if (!PathCheck.exists()) { + PathCheck.mkpath("./"); + } - if (m_csvLoggingNameSet) - { - m_csvLoggingFile.setFileName(QString("%1/%2_%3_%4.csv").arg(m_csvLoggingPath).arg(m_csvLoggingName).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + if (m_csvLoggingNameSet) { + m_csvLoggingFile.setFileName(QString("%1/%2_%3_%4.csv").arg(m_csvLoggingPath).arg(m_csvLoggingName).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + } else { + m_csvLoggingFile.setFileName(QString("%1/Log_%2_%3.csv").arg(m_csvLoggingPath).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); + } + QDir FileCheck(m_csvLoggingFile.fileName()); + if (FileCheck.exists()) { + m_csvLoggingFile.setFileName(""); + } else { + m_csvLoggingStarted = 1; + csvLoggingInsertHeader(); + } + } } - else - { - m_csvLoggingFile.setFileName(QString("%1/Log_%2_%3.csv").arg(m_csvLoggingPath).arg(NOW.toString("yyyy-MM-dd")).arg(NOW.toString("hh-mm-ss"))); - } - QDir FileCheck(m_csvLoggingFile.fileName()); - if (FileCheck.exists()) - { - m_csvLoggingFile.setFileName(""); - } - else - { - m_csvLoggingStarted=1; - csvLoggingInsertHeader(); - } - } return 0; @@ -614,33 +586,37 @@ int ScopeGadgetWidget::csvLoggingStart() int ScopeGadgetWidget::csvLoggingStop() { - m_csvLoggingStarted=0; + m_csvLoggingStarted = 0; return 0; } int ScopeGadgetWidget::csvLoggingInsertHeader() { - if (!m_csvLoggingStarted) return -1; - if (m_csvLoggingHeaderSaved) return -2; - if (m_csvLoggingDataSaved) return -3; - - m_csvLoggingHeaderSaved=1; - if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) - { - qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header"; + if (!m_csvLoggingStarted) { + return -1; + } + if (m_csvLoggingHeaderSaved) { + return -2; + } + if (m_csvLoggingDataSaved) { + return -3; } - else - { - QTextStream ts( &m_csvLoggingFile ); - ts << "date" << ", " << "Time"<< ", " << "Sec since start"<< ", " << "Connected" << ", " << "Data changed"; - foreach(PlotData* plotData2, m_curvesData.values()) - { - ts << ", "; - ts << plotData2->uavObject; - ts << "." << plotData2->uavField; - if (plotData2->haveSubField) ts << "." << plotData2->uavSubField; + m_csvLoggingHeaderSaved = 1; + if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) { + qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Header"; + } else { + QTextStream ts(&m_csvLoggingFile); + ts << "date" << ", " << "Time" << ", " << "Sec since start" << ", " << "Connected" << ", " << "Data changed"; + + foreach(PlotData * plotData2, m_curvesData.values()) { + ts << ", "; + ts << plotData2->uavObject; + ts << "." << plotData2->uavField; + if (plotData2->haveSubField) { + ts << "." << plotData2->uavSubField; + } } ts << endl; m_csvLoggingFile.close(); @@ -650,47 +626,40 @@ int ScopeGadgetWidget::csvLoggingInsertHeader() int ScopeGadgetWidget::csvLoggingAddData() { - if (!m_csvLoggingStarted) return -1; - m_csvLoggingDataValid=0; + if (!m_csvLoggingStarted) { + return -1; + } + m_csvLoggingDataValid = 0; QDateTime NOW = QDateTime::currentDateTime(); QString tempString; - QTextStream ss( &tempString ); - ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", " ; + QTextStream ss(&tempString); + ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", "; #if QT_VERSION >= 0x040700 - ss <<(NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch())/1000.00; + ss << (NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch()) / 1000.00; #else - ss <<(NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); + ss << (NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); #endif ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated; - m_csvLoggingDataUpdated=0; + m_csvLoggingDataUpdated = 0; - foreach(PlotData* plotData2, m_curvesData.values()) - { - ss << ", "; - if (plotData2->xData->isEmpty ()) - { - ss << ", "; - if (plotData2->xData->isEmpty ()) - { + foreach(PlotData * plotData2, m_curvesData.values()) { + ss << ", "; + if (plotData2->xData->isEmpty()) { + ss << ", "; + if (plotData2->xData->isEmpty()) {} else { + ss << QString().sprintf("%3.10g", plotData2->yData->last()); + m_csvLoggingDataValid = 1; } - else - { - ss << QString().sprintf("%3.10g",plotData2->yData->last()); - m_csvLoggingDataValid=1; - } - } - else - { - ss << QString().sprintf("%3.10g",plotData2->yData->last()); - m_csvLoggingDataValid=1; + } else { + ss << QString().sprintf("%3.10g", plotData2->yData->last()); + m_csvLoggingDataValid = 1; } } ss << endl; - if (m_csvLoggingDataValid) - { - QTextStream ts( &m_csvLoggingBuffer ); + if (m_csvLoggingDataValid) { + QTextStream ts(&m_csvLoggingBuffer); ts << tempString; } @@ -699,16 +668,15 @@ int ScopeGadgetWidget::csvLoggingAddData() int ScopeGadgetWidget::csvLoggingInsertData() { - if (!m_csvLoggingStarted) return -1; - m_csvLoggingDataSaved=1; - - if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) - { - qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data"; + if (!m_csvLoggingStarted) { + return -1; } - else - { - QTextStream ts( &m_csvLoggingFile ); + m_csvLoggingDataSaved = 1; + + if (m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append) == FALSE) { + qDebug() << "Unable to open " << m_csvLoggingFile.fileName() << " for csv logging Data"; + } else { + QTextStream ts(&m_csvLoggingFile); ts << m_csvLoggingBuffer; m_csvLoggingFile.close(); } @@ -719,20 +687,22 @@ int ScopeGadgetWidget::csvLoggingInsertData() void ScopeGadgetWidget::csvLoggingSetName(QString newName) { - m_csvLoggingName = newName; - m_csvLoggingNameSet=1; + m_csvLoggingName = newName; + m_csvLoggingNameSet = 1; } void ScopeGadgetWidget::csvLoggingConnect() { - m_csvLoggingConnected=1; - if (m_csvLoggingNewFileOnConnect)csvLoggingStart(); - return; + m_csvLoggingConnected = 1; + if (m_csvLoggingNewFileOnConnect) { + csvLoggingStart(); + } } void ScopeGadgetWidget::csvLoggingDisconnect() { - m_csvLoggingHeaderSaved=0; - m_csvLoggingConnected=0; - if (m_csvLoggingNewFileOnConnect)csvLoggingStop(); - return; + m_csvLoggingHeaderSaved = 0; + m_csvLoggingConnected = 0; + if (m_csvLoggingNewFileOnConnect) { + csvLoggingStop(); + } } diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h index f812e6fa6..da081c5c5 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h @@ -49,7 +49,6 @@ class TimeScaleDraw : public QwtScaleDraw { public: TimeScaleDraw() { - //baseTime = QDateTime::currentDateTime().toTime_t(); } virtual QwtText label(double v) const { uint seconds = (uint)(v); @@ -58,8 +57,6 @@ public: upTime.setTime(timePart); return upTime.toLocalTime().toString("hh:mm:ss"); } -private: -// double baseTime; }; class ScopeGadgetWidget : public QwtPlot @@ -81,15 +78,15 @@ public: int refreshInterval(){return m_refreshInterval;} - void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, QString mathFunction= "None", QPen pen = QPen(Qt::black)); - //void removeCurvePlot(QString uavObject, QString uavField); + void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int meanSamples = 1, + QString mathFunction= "None", QPen pen = QPen(Qt::black), bool antialiased = true); void clearCurvePlots(); int csvLoggingStart(); int csvLoggingStop(); void csvLoggingSetName(QString); - void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;}; - void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;}; - void setLoggingPath(QString value){m_csvLoggingPath=value;}; + void setLoggingEnabled(bool value){m_csvLoggingEnabled=value;} + void setLoggingNewFileOnConnect(bool value){m_csvLoggingNewFileOnConnect=value;} + void setLoggingPath(QString value){m_csvLoggingPath=value;} protected: void mousePressEvent(QMouseEvent *e); @@ -97,6 +94,7 @@ protected: void mouseDoubleClickEvent(QMouseEvent *e); void mouseMoveEvent(QMouseEvent *e); void wheelEvent(QWheelEvent *e); + void showEvent(QShowEvent *e); private slots: void uavObjectReceived(UAVObject*); From ed68fbe68d40f700f9d2d04a84494221d75970f8 Mon Sep 17 00:00:00 2001 From: "Richard Flay (Hyper)" Date: Tue, 14 May 2013 07:01:45 +0930 Subject: [PATCH 36/39] OP-951: Adds -Wshadow to flight CFLAGS and fixes resulting compilation breakage. +review OPReview --- flight/libraries/insgps13state.c | 270 +++++++++--------- flight/libraries/op_dfu.c | 4 +- flight/modules/FirmwareIAP/firmwareiap.c | 6 +- .../fixedwingpathfollower.c | 3 - flight/modules/ManualControl/manualcontrol.c | 26 +- flight/modules/Osd/osdgen/osdgen.c | 22 +- flight/modules/PathPlanner/pathplanner.c | 35 ++- flight/modules/Sensors/sensors.c | 8 +- .../VtolPathFollower/vtolpathfollower.c | 3 - flight/pios/common/pios_adxl345.c | 8 +- flight/pios/common/pios_bma180.c | 8 +- flight/pios/common/pios_l3gd20.c | 8 +- flight/pios/common/pios_mpu6000.c | 8 +- flight/pios/stm32f10x/pios_ppm.c | 11 +- .../STM32_USB_OTG_Driver/src/usb_core.c | 1 - flight/pios/stm32f4xx/pios_ppm.c | 12 +- .../targets/boards/oplinkmini/board_hw_defs.c | 2 - .../boards/oplinkmini/firmware/pios_board.c | 5 +- .../targets/boards/osd/firmware/pios_board.c | 30 +- .../boards/revolution/firmware/pios_board.c | 18 +- .../boards/revoproto/firmware/pios_board.c | 4 +- flight/uavobjects/eventdispatcher.c | 108 ++++--- make/common-defs.mk | 1 + 23 files changed, 289 insertions(+), 312 deletions(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index 7eca68a51..8bbfed86e 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -49,7 +49,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]); void SerialUpdate(float H[NUMV][NUMX], float R[NUMV], float Z[NUMV], - float Y[NUMV], float P[NUMX][NUMX], float X[NUMX], + float Y[NUMV], float P[NUMX][NUMX], float X[NUMX], float K[NUMX][NUMV], uint16_t SensorsUsed); void RungeKutta(float X[NUMX], float U[NUMU], float dT); void StateEq(float X[NUMX], float U[NUMU], float Xdot[NUMX]); @@ -59,12 +59,22 @@ void MeasurementEq(float X[NUMX], float Be[3], float Y[NUMV]); void LinearizeH(float X[NUMX], float Be[3], float H[NUMV][NUMX]); // Private variables -float F[NUMX][NUMX], G[NUMX][NUMW], H[NUMV][NUMX]; // linearized system matrices - // global to init to zero and maintain zero elements -float Be[3]; // local magnetic unit vector in NED frame -float P[NUMX][NUMX], X[NUMX]; // covariance matrix and state vector -float Q[NUMW], R[NUMV]; // input noise and measurement noise variances -float K[NUMX][NUMV]; // feedback gain matrix +struct EKFData { + // linearized system matrices + float F[NUMX][NUMX]; + float G[NUMX][NUMW]; + float H[NUMV][NUMX]; + // local magnetic unit vector in NED frame + float Be[3]; + // covariance matrix and state vector + float P[NUMX][NUMX]; + float X[NUMX]; + // input noise and measurement noise variances + float Q[NUMW]; + float R[NUMV]; + float K[NUMX][NUMV]; // feedback gain matrix +} ekf; + // Global variables struct NavStruct Nav; @@ -79,52 +89,52 @@ uint16_t ins_get_num_states() void INSGPSInit() //pretty much just a place holder for now { - Be[0] = 1.0f; - Be[1] = 0.0f; - Be[2] = 0.0f; // local magnetic unit vector + ekf.Be[0] = 1.0f; + ekf.Be[1] = 0.0f; + ekf.Be[2] = 0.0f; // local magnetic unit vector for (int i = 0; i < NUMX; i++) { for (int j = 0; j < NUMX; j++) { - P[i][j] = 0.0f; // zero all terms - F[i][j] = 0.0f; + ekf.P[i][j] = 0.0f; // zero all terms + ekf.F[i][j] = 0.0f; } for (int j = 0; j < NUMW; j++) - G[i][j] = 0.0f; + ekf.G[i][j] = 0.0f; for (int j = 0; j < NUMV; j++) { - H[j][i] = 0.0f; - K[i][j] = 0.0f; + ekf.H[j][i] = 0.0f; + ekf.K[i][j] = 0.0f; } - X[i] = 0.0f; + ekf.X[i] = 0.0f; } for (int i = 0; i < NUMW; i++) - Q[i] = 0.0f; + ekf.Q[i] = 0.0f; for (int i = 0; i < NUMV; i++) - R[i] = 0.0f; + ekf.R[i] = 0.0f; - P[0][0] = P[1][1] = P[2][2] = 25.0f; // initial position variance (m^2) - P[3][3] = P[4][4] = P[5][5] = 5.0f; // initial velocity variance (m/s)^2 - P[6][6] = P[7][7] = P[8][8] = P[9][9] = 1e-5f; // initial quaternion variance - P[10][10] = P[11][11] = P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 + ekf.P[0][0] = ekf.P[1][1] = ekf.P[2][2] = 25.0f; // initial position variance (m^2) + ekf.P[3][3] = ekf.P[4][4] = ekf.P[5][5] = 5.0f; // initial velocity variance (m/s)^2 + ekf.P[6][6] = ekf.P[7][7] = ekf.P[8][8] = ekf.P[9][9] = 1e-5f; // initial quaternion variance + ekf.P[10][10] = ekf.P[11][11] = ekf.P[12][12] = 1e-9f; // initial gyro bias variance (rad/s)^2 - X[0] = X[1] = X[2] = X[3] = X[4] = X[5] = 0.0f; // initial pos and vel (m) - X[6] = 1.0f; - X[7] = X[8] = X[9] = 0.0f; // initial quaternion (level and North) (m/s) - X[10] = X[11] = X[12] = 0.0f; // initial gyro bias (rad/s) + ekf.X[0] = ekf.X[1] = ekf.X[2] = ekf.X[3] = ekf.X[4] = ekf.X[5] = 0.0f; // initial pos and vel (m) + ekf.X[6] = 1.0f; + ekf.X[7] = ekf.X[8] = ekf.X[9] = 0.0f; // initial quaternion (level and North) (m/s) + ekf.X[10] = ekf.X[11] = ekf.X[12] = 0.0f; // initial gyro bias (rad/s) - Q[0] = Q[1] = Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 - Q[3] = Q[4] = Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 - Q[6] = Q[7] = Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 + ekf.Q[0] = ekf.Q[1] = ekf.Q[2] = 50e-4f; // gyro noise variance (rad/s)^2 + ekf.Q[3] = ekf.Q[4] = ekf.Q[5] = 0.00001f; // accelerometer noise variance (m/s^2)^2 + ekf.Q[6] = ekf.Q[7] = ekf.Q[8] = 2e-8f; // gyro bias random walk variance (rad/s^2)^2 - R[0] = R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) - R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) - R[3] = R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 - R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 - R[6] = R[7] = R[8] = 0.005f; // magnetometer unit vector noise variance - R[9] = .25f; // High freq altimeter noise variance (m^2) + ekf.R[0] = ekf.R[1] = 0.004f; // High freq GPS horizontal position noise variance (m^2) + ekf.R[2] = 0.036f; // High freq GPS vertical position noise variance (m^2) + ekf.R[3] = ekf.R[4] = 0.004f; // High freq GPS horizontal velocity noise variance (m/s)^2 + ekf.R[5] = 100.0f; // High freq GPS vertical velocity noise variance (m/s)^2 + ekf.R[6] = ekf.R[7] = ekf.R[8] = 0.005f; // magnetometer unit vector noise variance + ekf.R[9] = .25f; // High freq altimeter noise variance (m^2) } void INSResetP(float PDiag[NUMX]) @@ -135,8 +145,8 @@ void INSResetP(float PDiag[NUMX]) for (i=0;iRoll * stabSettings.RollMax; - altitudeHoldDesired.Pitch = cmd->Pitch * stabSettings.PitchMax; - altitudeHoldDesired.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; + altitudeHoldDesiredData.Roll = cmd->Roll * stabSettings.RollMax; + altitudeHoldDesiredData.Pitch = cmd->Pitch * stabSettings.PitchMax; + altitudeHoldDesiredData.Yaw = cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; float currentDown; PositionActualDownGet(¤tDown); if(changed) { // After not being in this mode for a while init at current height - altitudeHoldDesired.Altitude = 0; + altitudeHoldDesiredData.Altitude = 0; zeroed = false; } else if (cmd->Throttle > DEADBAND_HIGH && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT; + altitudeHoldDesiredData.Altitude += (cmd->Throttle - DEADBAND_HIGH) * dT; } else if (cmd->Throttle < DEADBAND_LOW && zeroed) { - altitudeHoldDesired.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT; + altitudeHoldDesiredData.Altitude += (cmd->Throttle - DEADBAND_LOW) * dT; } else if (cmd->Throttle >= DEADBAND_LOW && cmd->Throttle <= DEADBAND_HIGH) { // Require the stick to enter the dead band before they can move height zeroed = true; } - AltitudeHoldDesiredSet(&altitudeHoldDesired); + AltitudeHoldDesiredSet(&altitudeHoldDesiredData); } #else // TODO: These functions should never be accessible on CC. Any configuration that -// could allow them to be called sholud already throw an error to prevent this happening +// could allow them to be called should already throw an error to prevent this happening // in flight static void updatePathDesired(__attribute__((unused)) ManualControlCommandData * cmd, __attribute__((unused)) bool changed, diff --git a/flight/modules/Osd/osdgen/osdgen.c b/flight/modules/Osd/osdgen/osdgen.c index e67580bcd..9e9d94d8a 100644 --- a/flight/modules/Osd/osdgen/osdgen.c +++ b/flight/modules/Osd/osdgen/osdgen.c @@ -1063,7 +1063,7 @@ int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *loo void write_char16(char ch, unsigned int x, unsigned int y, int font) { unsigned int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; + uint16_t and_mask, or_mask, levels; struct FontEntry font_info; //char lookup = 0; fetch_font_info(0, font, &font_info, NULL); @@ -1103,17 +1103,17 @@ void write_char16(char ch, unsigned int x, unsigned int y, int font) addr = addr_temp; for (yy = y; yy < y + font_info.height; yy++) { if (font == 3) { - level_bits = font_frame12x18[row]; + levels = font_frame12x18[row]; //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; or_mask = font_mask12x18[row] << xshift; - and_mask = (font_mask12x18[row] & level_bits) << xshift; + and_mask = (font_mask12x18[row] & levels) << xshift; } else { - level_bits = font_frame8x10[row]; + levels = font_frame8x10[row]; //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; or_mask = font_mask8x10[row] << xshift; - and_mask = (font_mask8x10[row] & level_bits) << xshift; + and_mask = (font_mask8x10[row] & levels) << xshift; } write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); // If we're not bold write the AND mask. @@ -1139,7 +1139,7 @@ void write_char16(char ch, unsigned int x, unsigned int y, int font) void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) { unsigned int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; + uint16_t and_mask, or_mask, levels; struct FontEntry font_info; char lookup = 0; fetch_font_info(ch, font, &font_info, &lookup); @@ -1178,13 +1178,13 @@ void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) row = row_temp; addr = addr_temp; for (yy = y; yy < y + font_info.height; yy++) { - level_bits = font_info.data[row + font_info.height]; + levels = font_info.data[row + font_info.height]; if (!(flags & FONT_INVERT)) { // data is normally inverted - level_bits = ~level_bits; + levels = ~levels; } or_mask = font_info.data[row] << xshift; - and_mask = (font_info.data[row] & level_bits) << xshift; + and_mask = (font_info.data[row] & levels) << xshift; write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); // If we're not bold write the AND mask. //if(!(flags & FONT_BOLD)) diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index 530cc6ca8..d9bd44724 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -215,29 +215,29 @@ void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) { // use local variables, dont use stack since this is huge and a callback, // dont use the globals because we cant use mutexes here - static WaypointActiveData waypointActive; - static PathActionData pathAction; - static WaypointData waypoint; + static WaypointActiveData waypointActiveData; + static PathActionData pathActionData; + static WaypointData waypointData; static PathDesiredData pathDesired; // find out current waypoint - WaypointActiveGet(&waypointActive); + WaypointActiveGet(&waypointActiveData); - WaypointInstGet(waypointActive.Index,&waypoint); - PathActionInstGet(waypoint.Action, &pathAction); + WaypointInstGet(waypointActiveData.Index,&waypointData); + PathActionInstGet(waypointData.Action, &pathActionData); - pathDesired.End[PATHDESIRED_END_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; - pathDesired.End[PATHDESIRED_END_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; - pathDesired.End[PATHDESIRED_END_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN]; - pathDesired.EndingVelocity = waypoint.Velocity; - pathDesired.Mode = pathAction.Mode; - pathDesired.ModeParameters[0] = pathAction.ModeParameters[0]; - pathDesired.ModeParameters[1] = pathAction.ModeParameters[1]; - pathDesired.ModeParameters[2] = pathAction.ModeParameters[2]; - pathDesired.ModeParameters[3] = pathAction.ModeParameters[3]; - pathDesired.UID = waypointActive.Index; + pathDesired.End[PATHDESIRED_END_NORTH] = waypointData.Position[WAYPOINT_POSITION_NORTH]; + pathDesired.End[PATHDESIRED_END_EAST] = waypointData.Position[WAYPOINT_POSITION_EAST]; + pathDesired.End[PATHDESIRED_END_DOWN] = waypointData.Position[WAYPOINT_POSITION_DOWN]; + pathDesired.EndingVelocity = waypointData.Velocity; + pathDesired.Mode = pathActionData.Mode; + pathDesired.ModeParameters[0] = pathActionData.ModeParameters[0]; + pathDesired.ModeParameters[1] = pathActionData.ModeParameters[1]; + pathDesired.ModeParameters[2] = pathActionData.ModeParameters[2]; + pathDesired.ModeParameters[3] = pathActionData.ModeParameters[3]; + pathDesired.UID = waypointActiveData.Index; - if(waypointActive.Index == 0) { + if(waypointActiveData.Index == 0) { PositionActualData positionActual; PositionActualGet(&positionActual); // First waypoint has itself as start point (used to be home position but that proved dangerous when looping) @@ -260,7 +260,6 @@ void updatePathDesired(__attribute__((unused)) UAVObjEvent * ev) { pathDesired.StartingVelocity = waypointPrev.Velocity; } PathDesiredSet(&pathDesired); - } // helper function to go to a specific waypoint diff --git a/flight/modules/Sensors/sensors.c b/flight/modules/Sensors/sensors.c index 86829956e..feefbe1e2 100644 --- a/flight/modules/Sensors/sensors.c +++ b/flight/modules/Sensors/sensors.c @@ -487,7 +487,7 @@ static void magOffsetEstimation(MagnetometerData *mag) const float Rz = homeLocation.Be[2]; const float rate = cal.MagBiasNullingRate; - float R[3][3]; + float Rot[3][3]; float B_e[3]; float xy[2]; float delta[3]; @@ -496,9 +496,9 @@ static void magOffsetEstimation(MagnetometerData *mag) Quaternion2R(&attitude.q1, R); // Rotate the mag into the NED frame - B_e[0] = R[0][0] * mag->x + R[1][0] * mag->y + R[2][0] * mag->z; - B_e[1] = R[0][1] * mag->x + R[1][1] * mag->y + R[2][1] * mag->z; - B_e[2] = R[0][2] * mag->x + R[1][2] * mag->y + R[2][2] * mag->z; + B_e[0] = Rot[0][0] * mag->x + Rot[1][0] * mag->y + Rot[2][0] * mag->z; + B_e[1] = Rot[0][1] * mag->x + Rot[1][1] * mag->y + Rot[2][1] * mag->z; + B_e[2] = Rot[0][2] * mag->x + Rot[1][2] * mag->y + Rot[2][2] * mag->z; float cy = cosf(DEG2RAD(attitude.Yaw)); float sy = sinf(DEG2RAD(attitude.Yaw)); diff --git a/flight/modules/VtolPathFollower/vtolpathfollower.c b/flight/modules/VtolPathFollower/vtolpathfollower.c index 8d1d21484..f18be2605 100644 --- a/flight/modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/modules/VtolPathFollower/vtolpathfollower.c @@ -566,7 +566,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude) StabilizationDesiredData stabDesired; AttitudeActualData attitudeActual; NedAccelData nedAccel; - VtolPathFollowerSettingsData vtolpathfollowerSettings; StabilizationSettingsData stabSettings; SystemSettingsData systemSettings; @@ -580,8 +579,6 @@ static void updateVtolDesiredAttitude(bool yaw_attitude) float downCommand; SystemSettingsGet(&systemSettings); - VtolPathFollowerSettingsGet(&vtolpathfollowerSettings); - VelocityActualGet(&velocityActual); VelocityDesiredGet(&velocityDesired); StabilizationDesiredGet(&stabDesired); diff --git a/flight/pios/common/pios_adxl345.c b/flight/pios/common/pios_adxl345.c index f8e23e8d3..0b2b08a97 100644 --- a/flight/pios/common/pios_adxl345.c +++ b/flight/pios/common/pios_adxl345.c @@ -70,13 +70,13 @@ static struct adxl345_dev * PIOS_ADXL345_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_ADXL345_Validate(struct adxl345_dev * dev) +static int32_t PIOS_ADXL345_Validate(struct adxl345_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_ADXL345_DEV_MAGIC) + if (vdev->magic != PIOS_ADXL345_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } diff --git a/flight/pios/common/pios_bma180.c b/flight/pios/common/pios_bma180.c index 35fd09d2f..96e94256e 100644 --- a/flight/pios/common/pios_bma180.c +++ b/flight/pios/common/pios_bma180.c @@ -86,13 +86,13 @@ static struct bma180_dev * PIOS_BMA180_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_BMA180_Validate(struct bma180_dev * dev) +static int32_t PIOS_BMA180_Validate(struct bma180_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_BMA180_DEV_MAGIC) + if (vdev->magic != PIOS_BMA180_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } diff --git a/flight/pios/common/pios_l3gd20.c b/flight/pios/common/pios_l3gd20.c index 6ca37a2d1..c67f97a00 100644 --- a/flight/pios/common/pios_l3gd20.c +++ b/flight/pios/common/pios_l3gd20.c @@ -93,13 +93,13 @@ static struct l3gd20_dev * PIOS_L3GD20_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev * dev) +static int32_t PIOS_L3GD20_Validate(struct l3gd20_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_L3GD20_DEV_MAGIC) + if (vdev->magic != PIOS_L3GD20_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } diff --git a/flight/pios/common/pios_mpu6000.c b/flight/pios/common/pios_mpu6000.c index 2b2d06b0b..6183225ad 100644 --- a/flight/pios/common/pios_mpu6000.c +++ b/flight/pios/common/pios_mpu6000.c @@ -91,13 +91,13 @@ static struct mpu6000_dev * PIOS_MPU6000_alloc(void) * @brief Validate the handle to the spi device * @returns 0 for valid device or -1 otherwise */ -static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev * dev) +static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *vdev) { - if (dev == NULL) + if (vdev == NULL) return -1; - if (dev->magic != PIOS_MPU6000_DEV_MAGIC) + if (vdev->magic != PIOS_MPU6000_DEV_MAGIC) return -2; - if (dev->spi_id == 0) + if (vdev->spi_id == 0) return -3; return 0; } diff --git a/flight/pios/stm32f10x/pios_ppm.c b/flight/pios/stm32f10x/pios_ppm.c index 2088e426e..8933d9a46 100644 --- a/flight/pios/stm32f10x/pios_ppm.c +++ b/flight/pios/stm32f10x/pios_ppm.c @@ -50,7 +50,7 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds /* Local Variables */ -static TIM_ICInitTypeDef TIM_ICInitStructure; +//static TIM_ICInitTypeDef TIM_ICInitStructure; static void PIOS_PPM_Supervisor(uint32_t ppm_id); @@ -156,12 +156,13 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) return -1; } + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + /* Configure the channels to be in capture/compare mode */ for (uint8_t i = 0; i < cfg->num_channels; i++) { const struct pios_tim_channel * chan = &cfg->channels[i]; /* Configure timer for input capture */ - TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInit(chan->timer, &TIM_ICInitStructure); @@ -182,12 +183,6 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) } } - /* Setup local variable which stays in this scope */ - /* Doing this here and using a local variable saves doing it in the ISR */ - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - ppm_dev->supv_timer = 0; if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); diff --git a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c index 1b6cb84b4..3ba8b0486 100644 --- a/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c +++ b/flight/pios/stm32f4xx/libraries/STM32_USB_OTG_Driver/src/usb_core.c @@ -1355,7 +1355,6 @@ USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev) } for (i = 0; i < pdev->cfg.dev_endpoints; i++) { - USB_OTG_DEPCTL_TypeDef depctl; depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPCTL); if (depctl.b.epena) { diff --git a/flight/pios/stm32f4xx/pios_ppm.c b/flight/pios/stm32f4xx/pios_ppm.c index fad9a22e3..9d976320b 100644 --- a/flight/pios/stm32f4xx/pios_ppm.c +++ b/flight/pios/stm32f4xx/pios_ppm.c @@ -48,9 +48,6 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds -/* Local Variables */ -static TIM_ICInitTypeDef TIM_ICInitStructure; - static void PIOS_PPM_Supervisor(uint32_t ppm_id); enum pios_ppm_dev_magic { @@ -155,12 +152,13 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) return -1; } + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + /* Configure the channels to be in capture/compare mode */ for (uint8_t i = 0; i < cfg->num_channels; i++) { const struct pios_tim_channel * chan = &cfg->channels[i]; /* Configure timer for input capture */ - TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; TIM_ICInitStructure.TIM_Channel = chan->timer_chan; TIM_ICInit(chan->timer, &TIM_ICInitStructure); @@ -181,12 +179,6 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) } } - /* Setup local variable which stays in this scope */ - /* Doing this here and using a local variable saves doing it in the ISR */ - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); } diff --git a/flight/targets/boards/oplinkmini/board_hw_defs.c b/flight/targets/boards/oplinkmini/board_hw_defs.c index ad8b4eacc..3487f33c1 100644 --- a/flight/targets/boards/oplinkmini/board_hw_defs.c +++ b/flight/targets/boards/oplinkmini/board_hw_defs.c @@ -582,8 +582,6 @@ const struct pios_ppm_cfg pios_ppm_main_cfg = { #if defined(PIOS_INCLUDE_PPM_OUT) #include -uint32_t pios_ppm_id; - static const struct pios_tim_channel pios_tim_ppmout[] = { { .timer = TIM2, diff --git a/flight/targets/boards/oplinkmini/firmware/pios_board.c b/flight/targets/boards/oplinkmini/firmware/pios_board.c index c3bd75b71..92569c0b9 100644 --- a/flight/targets/boards/oplinkmini/firmware/pios_board.c +++ b/flight/targets/boards/oplinkmini/firmware/pios_board.c @@ -218,10 +218,9 @@ void PIOS_Board_Init(void) { /* Initalize the RFM22B radio COM device. */ #if defined(PIOS_INCLUDE_RFM22B) { - extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); const struct pios_board_info * bdinfo = &pios_board_info_blob; - const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { PIOS_Assert(0); } diff --git a/flight/targets/boards/osd/firmware/pios_board.c b/flight/targets/boards/osd/firmware/pios_board.c index 5aba31dc1..a241c27e9 100644 --- a/flight/targets/boards/osd/firmware/pios_board.c +++ b/flight/targets/boards/osd/firmware/pios_board.c @@ -343,10 +343,10 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - PIOS_Assert(rx_buffer); + uint8_t *gps_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); + PIOS_Assert(gps_rx_buffer); if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, + gps_rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, NULL, 0)) { PIOS_Assert(0); } @@ -361,14 +361,14 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_DEBUG_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); + uint8_t *aux_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_RX_BUF_LEN); + uint8_t *aux_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_AUX_TX_BUF_LEN); + PIOS_Assert(aux_rx_buffer); + PIOS_Assert(aux_tx_buffer); if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id, - rx_buffer, PIOS_COM_AUX_RX_BUF_LEN, - tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) { + aux_rx_buffer, PIOS_COM_AUX_RX_BUF_LEN, + aux_tx_buffer, PIOS_COM_AUX_TX_BUF_LEN)) { PIOS_DEBUG_Assert(0); } } @@ -383,13 +383,13 @@ PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driv PIOS_Assert(0); } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); + uint8_t *telem_rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t *telem_tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(telem_rx_buffer); + PIOS_Assert(telem_tx_buffer); if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + telem_rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + telem_tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { PIOS_Assert(0); } } diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index d7611a634..febdf32d2 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -269,7 +269,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg } static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + const struct pios_com_driver *usart_com_driver,enum pios_dsm_proto *proto, ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) { uint32_t pios_usart_dsm_id; @@ -278,7 +278,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm } uint32_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver, pios_usart_dsm_id, *proto, *bind)) { PIOS_Assert(0); } @@ -290,11 +290,11 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; } -static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pios_pwm_cfg) +static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) { /* Set up the receiver port. Later this should be optional */ uint32_t pios_pwm_id; - PIOS_PWM_Init(&pios_pwm_id, pios_pwm_cfg); + PIOS_PWM_Init(&pios_pwm_id, pwm_cfg); uint32_t pios_pwm_rcvr_id; if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { @@ -303,10 +303,10 @@ static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pios_pwm_cfg) pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } -static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *pios_ppm_cfg) +static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg) { uint32_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, pios_ppm_cfg); + PIOS_PPM_Init(&pios_ppm_id, ppm_cfg); uint32_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { @@ -667,10 +667,8 @@ void PIOS_Board_Init(void) { break; case HWSETTINGS_RADIOPORT_TELEMETRY: { - extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision); - const struct pios_board_info * bdinfo = &pios_board_info_blob; - const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) { + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { PIOS_Assert(0); } diff --git a/flight/targets/boards/revoproto/firmware/pios_board.c b/flight/targets/boards/revoproto/firmware/pios_board.c index 03f532b65..5c5a5e3b6 100644 --- a/flight/targets/boards/revoproto/firmware/pios_board.c +++ b/flight/targets/boards/revoproto/firmware/pios_board.c @@ -339,7 +339,7 @@ static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg } static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_dsm_proto *proto, + const struct pios_com_driver *usart_com_driver,enum pios_dsm_proto *proto, ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) { uint32_t pios_usart_dsm_id; @@ -348,7 +348,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm } uint32_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver, pios_usart_dsm_id, *proto, *bind)) { PIOS_Assert(0); } diff --git a/flight/uavobjects/eventdispatcher.c b/flight/uavobjects/eventdispatcher.c index e56e916b3..962298980 100644 --- a/flight/uavobjects/eventdispatcher.c +++ b/flight/uavobjects/eventdispatcher.c @@ -68,11 +68,11 @@ struct PeriodicObjectListStruct { typedef struct PeriodicObjectListStruct PeriodicObjectList; // Private variables -static PeriodicObjectList* objList; -static xQueueHandle queue; -static xTaskHandle eventTaskHandle; -static xSemaphoreHandle mutex; -static EventStats stats; +static PeriodicObjectList* mObjList; +static xQueueHandle mQueue; +static xTaskHandle mEventTaskHandle; +static xSemaphoreHandle mMutex; +static EventStats mStats; // Private functions static int32_t processPeriodicUpdates(); @@ -89,19 +89,19 @@ static uint16_t randomizePeriod(uint16_t periodMs); int32_t EventDispatcherInitialize() { // Initialize variables - objList = NULL; - memset(&stats, 0, sizeof(EventStats)); + mObjList = NULL; + memset(&mStats, 0, sizeof(EventStats)); - // Create mutex - mutex = xSemaphoreCreateRecursiveMutex(); - if (mutex == NULL) + // Create mMutex + mMutex = xSemaphoreCreateRecursiveMutex(); + if (mMutex == NULL) return -1; // Create event queue - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo)); + mQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(EventCallbackInfo)); // Create task - xTaskCreate( eventTask, (signed char*)"Event", STACK_SIZE, NULL, TASK_PRIORITY, &eventTaskHandle ); + xTaskCreate(eventTask, (signed char*)"Event", STACK_SIZE, NULL, TASK_PRIORITY, &mEventTaskHandle); // Done return 0; @@ -113,9 +113,9 @@ int32_t EventDispatcherInitialize() */ void EventGetStats(EventStats* statsOut) { - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memcpy(statsOut, &stats, sizeof(EventStats)); - xSemaphoreGiveRecursive(mutex); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); + memcpy(statsOut, &mStats, sizeof(EventStats)); + xSemaphoreGiveRecursive(mMutex); } /** @@ -123,9 +123,9 @@ void EventGetStats(EventStats* statsOut) */ void EventClearStats() { - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memset(&stats, 0, sizeof(EventStats)); - xSemaphoreGiveRecursive(mutex); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); + memset(&mStats, 0, sizeof(EventStats)); + xSemaphoreGiveRecursive(mMutex); } /** @@ -143,7 +143,7 @@ int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb) evInfo.cb = cb; evInfo.queue = 0; // Push to queue - return xQueueSend(queue, &evInfo, 0); // will not block if queue is full + return xQueueSend(mQueue, &evInfo, 0); // will not block if queue is full } /** @@ -204,26 +204,26 @@ int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t p */ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQueueHandle queue, uint16_t periodMs) { - PeriodicObjectList* objEntry; + PeriodicObjectList *objEntry; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Check that the object is not already connected - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { if (objEntry->evInfo.cb == cb && objEntry->evInfo.queue == queue && objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.instId == ev->instId && - objEntry->evInfo.ev.event == ev->event) - { + objEntry->evInfo.ev.event == ev->event) { // Already registered, do nothing - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return -1; } } // Create handle objEntry = (PeriodicObjectList*)pvPortMalloc(sizeof(PeriodicObjectList)); - if (objEntry == NULL) return -1; + if (objEntry == NULL) { + return -1; + } objEntry->evInfo.ev.obj = ev->obj; objEntry->evInfo.ev.instId = ev->instId; objEntry->evInfo.ev.event = ev->event; @@ -232,9 +232,9 @@ static int32_t eventPeriodicCreate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue objEntry->updatePeriodMs = periodMs; objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates // Add to list - LL_APPEND(objList, objEntry); + LL_APPEND(mObjList, objEntry); // Release lock - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return 0; } @@ -250,26 +250,24 @@ static int32_t eventPeriodicUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, xQue { PeriodicObjectList* objEntry; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Find object - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { if (objEntry->evInfo.cb == cb && objEntry->evInfo.queue == queue && objEntry->evInfo.ev.obj == ev->obj && objEntry->evInfo.ev.instId == ev->instId && - objEntry->evInfo.ev.event == ev->event) - { + objEntry->evInfo.ev.event == ev->event) { // Object found, update period objEntry->updatePeriodMs = periodMs; objEntry->timeToNextUpdateMs = randomizePeriod(periodMs); // avoid bunching of updates // Release lock - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return 0; } } // If this point is reached the object was not found - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return -1; } @@ -283,7 +281,7 @@ static void eventTask() EventCallbackInfo evInfo; /* Must do this in task context to ensure that TaskMonitor has already finished its init */ - PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_EVENTDISPATCHER, eventTaskHandle); + PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_EVENTDISPATCHER, mEventTaskHandle); // Initialize time timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS; @@ -295,7 +293,7 @@ static void eventTask() delayMs = timeToNextUpdateMs - (xTaskGetTickCount() * portTICK_RATE_MS); // Wait for queue message - if ( xQueueReceive(queue, &evInfo, delayMs/portTICK_RATE_MS) == pdTRUE ) + if ( xQueueReceive(mQueue, &evInfo, delayMs/portTICK_RATE_MS) == pdTRUE ) { // Invoke callback, if one if ( evInfo.cb != 0) @@ -324,49 +322,43 @@ static int32_t processPeriodicUpdates() int32_t offset; // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + xSemaphoreTakeRecursive(mMutex, portMAX_DELAY); // Iterate through each object and update its timer, if zero then transmit object. // Also calculate smallest delay to next update. timeToNextUpdate = xTaskGetTickCount()*portTICK_RATE_MS + MAX_UPDATE_PERIOD_MS; - LL_FOREACH(objList, objEntry) - { + LL_FOREACH(mObjList, objEntry) { // If object is configured for periodic updates - if (objEntry->updatePeriodMs > 0) - { + if (objEntry->updatePeriodMs > 0) { // Check if time for the next update timeNow = xTaskGetTickCount()*portTICK_RATE_MS; - if (objEntry->timeToNextUpdateMs <= timeNow) - { + if (objEntry->timeToNextUpdateMs <= timeNow) { // Reset timer - offset = ( timeNow - objEntry->timeToNextUpdateMs ) % objEntry->updatePeriodMs; + offset = (timeNow - objEntry->timeToNextUpdateMs) % objEntry->updatePeriodMs; objEntry->timeToNextUpdateMs = timeNow + objEntry->updatePeriodMs - offset; // Invoke callback, if one - if ( objEntry->evInfo.cb != 0) - { + if (objEntry->evInfo.cb != 0) { objEntry->evInfo.cb(&objEntry->evInfo.ev); // the function is expected to copy the event information } // Push event to queue, if one - if ( objEntry->evInfo.queue != 0) - { - if ( xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) // do not block if queue is full - { - if (objEntry->evInfo.ev.obj != NULL) - stats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); - ++stats.eventErrors; + if (objEntry->evInfo.queue != 0) { + if (xQueueSend(objEntry->evInfo.queue, &objEntry->evInfo.ev, 0) != pdTRUE ) { // do not block if queue is full + if (objEntry->evInfo.ev.obj != NULL) { + mStats.lastErrorID = UAVObjGetID(objEntry->evInfo.ev.obj); + } + ++mStats.eventErrors; } } } // Update minimum delay - if (objEntry->timeToNextUpdateMs < timeToNextUpdate) - { + if (objEntry->timeToNextUpdateMs < timeToNextUpdate) { timeToNextUpdate = objEntry->timeToNextUpdateMs; } } } // Done - xSemaphoreGiveRecursive(mutex); + xSemaphoreGiveRecursive(mMutex); return timeToNextUpdate; } diff --git a/make/common-defs.mk b/make/common-defs.mk index 76cb43746..a06625f2d 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -120,6 +120,7 @@ CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer CFLAGS += -Wall -Wextra CFLAGS += -Wfloat-equal -Wunsuffixed-float-constants -Wdouble-promotion +CFLAGS += -Wshadow CFLAGS += -Werror CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) From 1608d114164f4bd4710ee1b8080d8d0c1b4134cf Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 14 May 2013 20:20:52 -0700 Subject: [PATCH 37/39] Cleans up some compiler warnings/erros and adds missing ifdefs around some e.g. WDG calls. --- flight/modules/Actuator/actuator.c | 4 ++++ flight/modules/Fault/Fault.c | 2 +- flight/modules/ManualControl/manualcontrol.c | 4 ++++ flight/modules/Stabilization/stabilization.c | 4 ++++ flight/pios/inc/pios_rcvr_priv.h | 2 -- flight/pios/stm32f10x/pios_i2c.c | 11 ++--------- 6 files changed, 15 insertions(+), 12 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index f8212caa0..9b5dcbf91 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -103,7 +103,9 @@ int32_t ActuatorStart() // Start main task xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ACTUATOR, taskHandle); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR); +#endif return 0; } @@ -185,7 +187,9 @@ static void actuatorTask(__attribute__((unused)) void* parameters) lastSysTime = xTaskGetTickCount(); while (1) { +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR); +#endif // Wait until the ActuatorDesired object is updated uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS); diff --git a/flight/modules/Fault/Fault.c b/flight/modules/Fault/Fault.c index b707ed5a5..33b15f7cb 100644 --- a/flight/modules/Fault/Fault.c +++ b/flight/modules/Fault/Fault.c @@ -112,7 +112,7 @@ static int32_t fault_start(void) } MODULE_INITCALL(fault_initialize, fault_start) -static void fault_task(void *parameters) +static void fault_task(__attribute__((unused))void *parameters) { switch (active_fault) { case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK: diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index 1107a601d..7c28ade1d 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -138,7 +138,9 @@ int32_t ManualControlStart() // Start main task xTaskCreate(manualControlTask, (signed char *) "ManualControl", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_MANUALCONTROL, taskHandle); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL); +#endif return 0; } @@ -208,7 +210,9 @@ static void manualControlTask(__attribute__((unused)) void *parameters) // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_MANUAL); +#endif // Read settings ManualControlSettingsGet(&settings); diff --git a/flight/modules/Stabilization/stabilization.c b/flight/modules/Stabilization/stabilization.c index b417864e6..d9b17f1c2 100644 --- a/flight/modules/Stabilization/stabilization.c +++ b/flight/modules/Stabilization/stabilization.c @@ -113,7 +113,9 @@ int32_t StabilizationStart() // Start main task xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_STABILIZATION, taskHandle); +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION); +#endif return 0; } @@ -161,7 +163,9 @@ static void stabilizationTask(__attribute__((unused)) void* parameters) while(1) { float dT; +#ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); +#endif // 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 ) diff --git a/flight/pios/inc/pios_rcvr_priv.h b/flight/pios/inc/pios_rcvr_priv.h index 7b41d2764..46ced2e24 100644 --- a/flight/pios/inc/pios_rcvr_priv.h +++ b/flight/pios/inc/pios_rcvr_priv.h @@ -33,8 +33,6 @@ #include -extern uint32_t pios_rcvr_max_channel; - extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id); extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id); diff --git a/flight/pios/stm32f10x/pios_i2c.c b/flight/pios/stm32f10x/pios_i2c.c index f61d00c14..054cc1454 100644 --- a/flight/pios/stm32f10x/pios_i2c.c +++ b/flight/pios/stm32f10x/pios_i2c.c @@ -126,7 +126,7 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter); static void i2c_adapter_log_fault(enum pios_i2c_error_type type); -const static struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { +static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = { [I2C_STATE_FSM_FAULT] = { .entry_fn = go_fsm_fault, .next_state = { @@ -607,9 +607,6 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum * guarantee that the entry function never depends on the previous * state. This way, it cannot ever know what the previous state was. */ - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event]; /* Call the entry function (if any) for the next state. */ @@ -626,10 +623,6 @@ static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter) { PIOS_IRQ_Disable(); - - enum i2c_adapter_state prev_state = i2c_adapter->curr_state; - if (prev_state) ; - while (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]) { i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]; @@ -659,7 +652,7 @@ static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter) * in spinning on this bit in the ISR forever. */ #define I2C_CR1_STOP_REQUESTED 0x0200 - for (guard = 1e6; /* FIXME: should use the configured bus timeout */ + for (guard = 1000000; /* FIXME: should use the configured bus timeout */ guard && (i2c_adapter->cfg->regs->CR1 & I2C_CR1_STOP_REQUESTED); guard--) continue; if (!guard) { From 156109bb8895b5ac885bd8f9bdf6578d217daf7d Mon Sep 17 00:00:00 2001 From: Brian Webb Date: Tue, 14 May 2013 20:37:13 -0700 Subject: [PATCH 38/39] Added support for an active low USB vsense line. --- flight/pios/inc/pios_usb_priv.h | 1 + flight/pios/stm32f10x/pios_usb.c | 2 +- flight/pios/stm32f4xx/pios_usb.c | 2 +- flight/targets/boards/coptercontrol/board_hw_defs.c | 6 ++++-- flight/targets/boards/oplinkmini/board_hw_defs.c | 3 ++- flight/targets/boards/osd/board_hw_defs.c | 3 ++- flight/targets/boards/revolution/board_hw_defs.c | 6 ++++-- flight/targets/boards/revoproto/board_hw_defs.c | 3 ++- 8 files changed, 17 insertions(+), 9 deletions(-) diff --git a/flight/pios/inc/pios_usb_priv.h b/flight/pios/inc/pios_usb_priv.h index 76b430a99..ee3c26bd9 100644 --- a/flight/pios/inc/pios_usb_priv.h +++ b/flight/pios/inc/pios_usb_priv.h @@ -37,6 +37,7 @@ struct pios_usb_cfg { struct stm32_irq irq; struct stm32_gpio vsense; + bool vsense_active_low; }; extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg); diff --git a/flight/pios/stm32f10x/pios_usb.c b/flight/pios/stm32f10x/pios_usb.c index 13fb8c3c5..bfecbe3ff 100644 --- a/flight/pios/stm32f10x/pios_usb.c +++ b/flight/pios/stm32f10x/pios_usb.c @@ -215,7 +215,7 @@ bool PIOS_USB_CableConnected(__attribute__((unused)) uint8_t id) if (PIOS_USB_validate(usb_dev) != 0) return false; - return usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin; + return ((usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin) != 0) ^ usb_dev->cfg->vsense_active_low; } /** diff --git a/flight/pios/stm32f4xx/pios_usb.c b/flight/pios/stm32f4xx/pios_usb.c index d0592a815..6666e120d 100644 --- a/flight/pios/stm32f4xx/pios_usb.c +++ b/flight/pios/stm32f4xx/pios_usb.c @@ -162,7 +162,7 @@ bool PIOS_USB_CheckAvailable(__attribute__((unused)) uint32_t id) if(!PIOS_USB_validate(usb_dev)) return false; - usb_found = (usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin); + usb_found = ((usb_dev->cfg->vsense.gpio->IDR & usb_dev->cfg->vsense.init.GPIO_Pin) != 0) ^ usb_dev->cfg->vsense_active_low; return usb_found; return usb_found != 0 && transfer_possible ? 1 : 0; } diff --git a/flight/targets/boards/coptercontrol/board_hw_defs.c b/flight/targets/boards/coptercontrol/board_hw_defs.c index b4f83f541..ad042fada 100644 --- a/flight/targets/boards/coptercontrol/board_hw_defs.c +++ b/flight/targets/boards/coptercontrol/board_hw_defs.c @@ -1431,7 +1431,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { @@ -1450,7 +1451,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/oplinkmini/board_hw_defs.c b/flight/targets/boards/oplinkmini/board_hw_defs.c index ad8b4eacc..24464595b 100644 --- a/flight/targets/boards/oplinkmini/board_hw_defs.c +++ b/flight/targets/boards/oplinkmini/board_hw_defs.c @@ -640,7 +640,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Speed = GPIO_Speed_10MHz, .GPIO_Mode = GPIO_Mode_AF_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/osd/board_hw_defs.c b/flight/targets/boards/osd/board_hw_defs.c index 7b433a030..95f142788 100644 --- a/flight/targets/boards/osd/board_hw_defs.c +++ b/flight/targets/boards/osd/board_hw_defs.c @@ -502,7 +502,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index 4ea6bbae8..3f2778838 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -1837,7 +1837,8 @@ static const struct pios_usb_cfg pios_usb_main_rm1_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { @@ -1857,7 +1858,8 @@ static const struct pios_usb_cfg pios_usb_main_rm2_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) diff --git a/flight/targets/boards/revoproto/board_hw_defs.c b/flight/targets/boards/revoproto/board_hw_defs.c index 0934a5a26..b10ffec6f 100644 --- a/flight/targets/boards/revoproto/board_hw_defs.c +++ b/flight/targets/boards/revoproto/board_hw_defs.c @@ -2003,7 +2003,8 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, }, - } + }, + .vsense_active_low = false }; #include "pios_usb_board_data_priv.h" From 667f46ceb1af3da7d3820c4add2846d6c743b932 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 16 May 2013 23:21:32 +0200 Subject: [PATCH 39/39] removed non ASCII characters in comment line --- flight/libraries/insgps13state.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/libraries/insgps13state.c b/flight/libraries/insgps13state.c index a3216e131..3ad148c95 100644 --- a/flight/libraries/insgps13state.c +++ b/flight/libraries/insgps13state.c @@ -427,7 +427,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], float Q[NUMW], float dT, float P[NUMX][NUMX]) { - // Pnew = (I+F*T)*P*(I+F*T)' + T²*G*Q*G' = T²[(P/T + F*P)*(I/T + F') + G*Q*G')] + // Pnew = (I+F*T)*P*(I+F*T)' + (T^2)*G*Q*G' = (T^2)[(P/T + F*P)*(I/T + F') + G*Q*G')] float dT1 = 1.0f / dT; // multiplication is faster than division on fpu. float dTsq = dT * dT; @@ -451,7 +451,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], } } } - for (i = 0; i < NUMX; i++) { // Calculate Pnew = T² [Dummy/T + Dummy*F' + G*Qw*G'] + for (i = 0; i < NUMX; i++) { // Calculate Pnew = (T^2) [Dummy/T + Dummy*F' + G*Qw*G'] float *Dirow = Dummy[i]; float *Girow = G[i]; @@ -483,7 +483,7 @@ void CovariancePrediction(float F[NUMX][NUMX], float G[NUMX][NUMW], } } - P[j][i] = Pirow[j] = Ptmp * dTsq; // [] * T² + P[j][i] = Pirow[j] = Ptmp * dTsq; // [] * (T^2) } } }