From 35fb0b3c6a9b7def8b0371f8bed710fb667762b8 Mon Sep 17 00:00:00 2001 From: zedamota Date: Sun, 12 Feb 2012 16:26:31 +0000 Subject: [PATCH 001/165] Fixes BT telemetry not working on non Windows OSs Signed-off-by: James Cotton --- .../plugins/serialconnection/serialplugin.cpp | 22 +++++-- .../serialconnection/serialpluginoptions.ui | 58 +------------------ .../serialpluginoptionspage.cpp | 32 ++++++++++ 3 files changed, 50 insertions(+), 62 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp index 23bb8f9f9..f83efe968 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp @@ -205,31 +205,43 @@ void SerialConnection::resumePolling() } BaudRateType SerialConnection::stringToBaud(QString str) -{ +{ if(str=="1200") return BAUD1200; + if(str=="1800") + return BAUD1800; else if(str=="2400") - return BAUD1200; - else if(str== "4800") return BAUD2400; + else if(str== "4800") + return BAUD4800; else if(str== "9600") return BAUD9600; + else if(str== "14400") + return BAUD14400; else if(str== "19200") return BAUD19200; else if(str== "38400") return BAUD38400; - else if(str== "57600") + else if(str== "56000") return BAUD56000; + else if(str== "57600") + return BAUD57600; + else if(str== "76800") + return BAUD76800; else if(str== "115200") return BAUD115200; + else if(str== "128000") + return BAUD128000; else if(str== "230400") return BAUD230400; + else if(str== "256000") + return BAUD256000; else if(str== "460800") return BAUD460800; else if(str== "921600") return BAUD921600; else - return BAUD56000; + return BAUD57600; } SerialPlugin::SerialPlugin() diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui index 04f9faf06..1aedd7e2c 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui @@ -22,63 +22,7 @@ - - - - 1200 - - - - - 2400 - - - - - 4800 - - - - - 9600 - - - - - 19200 - - - - - 38400 - - - - - 57600 - - - - - 115200 - - - - - 230400 - - - - - 460800 - - - - - 921600 - - - + diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp index 29d8b3784..bd46dbb47 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp @@ -47,6 +47,38 @@ QWidget *SerialPluginOptionsPage::createPage(QWidget *parent) QWidget *optionsPageWidget = new QWidget; //main layout options_page->setupUi(optionsPageWidget); + QStringList allowedSpeeds; + allowedSpeeds<<"1200" +#ifdef Q_OS_UNIX + <<"1800" //POSIX ONLY +#endif + <<"2400" + <<"4800" + <<"9600" +#ifdef Q_OS_WIN + <<"14400" //WINDOWS ONLY +#endif + <<"19200" + <<"38400" +#ifdef Q_OS_WIN + <<"56000" //WINDOWS ONLY +#endif + <<"57600" +#ifdef Q_OS_UNIX + <<"76800" //POSIX ONLY +#endif + <<"115200" +#ifdef Q_OS_WIN + <<"128000" //WINDOWS ONLY + <<"230400" //WINDOWS ONLY + <<"256000" //WINDOWS ONLY + <<"460800" //WINDOWS ONLY + <<"921600" //WINDOWS ONLY +#endif + ; + + + options_page->cb_speed->addItems(allowedSpeeds); options_page->cb_speed->setCurrentIndex(options_page->cb_speed->findText(m_config->speed())); return optionsPageWidget; } From 319e834d32293e1a5fb05a0fe791839da6095194 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sat, 18 Feb 2012 08:38:01 +1100 Subject: [PATCH 002/165] Update Plist info for Mac --- ground/openpilotgcs/src/app/Info.plist | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/app/Info.plist b/ground/openpilotgcs/src/app/Info.plist index 23e542b6d..297c81b5c 100644 --- a/ground/openpilotgcs/src/app/Info.plist +++ b/ground/openpilotgcs/src/app/Info.plist @@ -172,7 +172,7 @@ CFBundleGetInfoString - Qt Creator; Copyright Nokia Corporation + OpenPilot GCS; Copyright OpenPilot CFBundleIconFile @ICON@ CFBundlePackageType @@ -182,7 +182,7 @@ CFBundleExecutable @EXECUTABLE@ CFBundleIdentifier - com.nokia.qtcreator + org.openpilot.openpilotgcs CFBundleVersion 1.3.1 CFBundleShortVersionString From 1d1915d2be8a84551ed0b673bb198ae80dca2622 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 12 Jul 2012 01:41:24 +0300 Subject: [PATCH 003/165] GCS Input widget: make RC inputs the default tab --- ground/openpilotgcs/src/plugins/config/input.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index e00f4baf3..199f52620 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -17,7 +17,7 @@ - 1 + 0 From 43bd9a88190102f78fb099c0f5510d69b3723da1 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 Jul 2012 00:14:50 +0300 Subject: [PATCH 004/165] nsis: add some translations for DE (thanks, D-Lite) --- package/winx86/translations/strings_de.nsh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/package/winx86/translations/strings_de.nsh b/package/winx86/translations/strings_de.nsh index 2eea9dd8d..234a1fe3a 100644 --- a/package/winx86/translations/strings_de.nsh +++ b/package/winx86/translations/strings_de.nsh @@ -31,9 +31,9 @@ LangString DESC_InSecSounds ${LANG_GERMAN} "GCS Sounddateien (benötigt für akustische Ereignisbenachrichtigungen)." LangString DESC_InSecLocalization ${LANG_GERMAN} "GCS Lokalisierung (für unterstützte Sprachen)." LangString DESC_InSecFirmware ${LANG_GERMAN} "OpenPilot firmware binaries." - LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot utilities (Matlab log parser)." - LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot Dienstprogramme (Matlab Log Parser)." + LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot Hardware Treiberdateien (optionaler OpenPilot CDC Treiber)." + LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Installiere OpenPilot CDC Treiber (optional)." LangString DESC_InSecShortcuts ${LANG_GERMAN} "Installiere Verknüpfungen unter Startmenü->Anwendungen." ;-------------------------------- From 9507a79c6ddf119b5db951fa696e27a421316e11 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 16 Jul 2012 13:08:12 -0700 Subject: [PATCH 005/165] MultiRotor Config, Bugfix: include TriYaw channel in getChannelDescriptions --- .../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index d27f4c530..bfa4fe7a2 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -274,6 +274,8 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions() channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW"); if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE"); + if (multi.TRIYaw > 0 && multi.TRIYaw <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.TRIYaw-1] = QString("Tri-Yaw"); return channelDesc; } From 86d672473911c9c84769d98d1973ff76723e3aa6 Mon Sep 17 00:00:00 2001 From: David Date: Thu, 19 Jul 2012 07:02:49 +1000 Subject: [PATCH 006/165] Change the wording to be less harsh --- ground/openpilotgcs/src/plugins/config/airframe.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 47006a789..ba3396ac7 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -2788,7 +2788,7 @@ p, li { white-space: pre-wrap; } <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD NEEDS CAUTION</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> From dc1a8205cadbb6579d881d6ce1cbaa41457fd464 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 00:31:59 -0500 Subject: [PATCH 007/165] Allow building an unsigned linux package until we have official OP signing keys --- package/Makefile.linux | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package/Makefile.linux b/package/Makefile.linux index 78e902d71..086079905 100644 --- a/package/Makefile.linux +++ b/package/Makefile.linux @@ -42,7 +42,7 @@ DEB_PACKAGE_NAME := openpilot_$(VERSION_FULL)_$(DEB_PLATFORM) linux_deb_package: deb_build gcs @echo $@ starting - cd .. && dpkg-buildpackage -b + cd .. && dpkg-buildpackage -b -us -uc $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR) $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) $(V1)rm -rf $(DEB_BUILD_DIR) From 9e33751df345e32b9a0c5a00d7a4420a51b73c68 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 19 Jul 2012 12:40:28 +0300 Subject: [PATCH 008/165] AeroSimRC: add copyright and license comments to HITLv2 plugin --- .../src/plugins/hitlv2/aerosimrc.cpp | 27 +++++++++++++++++++ .../src/plugins/hitlv2/aerosimrc.h | 27 +++++++++++++++++++ .../plugins/hitlv2/hitlv2configuration.cpp | 8 +++--- .../src/plugins/hitlv2/hitlv2configuration.h | 8 +++--- .../src/plugins/hitlv2/hitlv2factory.cpp | 9 ++++--- .../src/plugins/hitlv2/hitlv2factory.h | 8 +++--- .../src/plugins/hitlv2/hitlv2gadget.cpp | 9 ++++--- .../src/plugins/hitlv2/hitlv2gadget.h | 8 +++--- .../src/plugins/hitlv2/hitlv2optionspage.cpp | 8 +++--- .../src/plugins/hitlv2/hitlv2optionspage.h | 8 +++--- .../src/plugins/hitlv2/hitlv2plugin.cpp | 9 ++++--- .../src/plugins/hitlv2/hitlv2plugin.h | 8 +++--- .../src/plugins/hitlv2/hitlv2widget.cpp | 9 ++++--- .../src/plugins/hitlv2/hitlv2widget.h | 8 +++--- .../src/plugins/hitlv2/simulatorv2.cpp | 8 +++--- .../src/plugins/hitlv2/simulatorv2.h | 8 +++--- 16 files changed, 114 insertions(+), 56 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp index 51daf2460..f8306e30d 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp @@ -1,3 +1,30 @@ +/** + ****************************************************************************** + * + * @file aerosimrc.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITLv2 Plugin + * @{ + * @brief The Hardware In The Loop plugin version 2 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #include "aerosimrc.h" #include #include diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h index 19dae3bce..42b7d4aa5 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h @@ -1,3 +1,30 @@ +/** + ****************************************************************************** + * + * @file aerosimrc.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITLv2 Plugin + * @{ + * @brief The Hardware In The Loop plugin version 2 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #ifndef AEROSIMRC_H #define AEROSIMRC_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp index 890742e41..5977e5220 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2configuration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h index dfac80ddf..3e6a96df6 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlconfiguration.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2configuration.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp index 6e6f1a42e..c9e52ebb4 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlfactory.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2factory.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + #include "hitlv2factory.h" #include "hitlv2widget.h" #include "hitlv2gadget.h" diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h index b4142eeed..cfa91750d 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlfactory.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2factory.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp index de22d121b..b114cbde5 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitl.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2gadget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + #include "hitlv2gadget.h" #include "hitlv2widget.h" #include "hitlv2configuration.h" diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h index 0e4fd1a80..45302abb8 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitl.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2gadget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp index 5b88785ad..280ccf030 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitloptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2optionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h index 5c8d33f59..dbfe028bc 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitloptionspage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2optionspage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp index f0ee2d07a..c63ba5c86 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file mapplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2plugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + #include "hitlv2plugin.h" #include "hitlv2factory.h" #include diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h index e68129bd4..3e83915b3 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file browserplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2plugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp index 55d14f735..8933d7748 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2widget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + #include "hitlv2widget.h" #include "ui_hitlv2widget.h" #include diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h index 78f3e9405..6cf1c66c7 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file hitlv2widget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp index c4c698689..bc5e0b0b1 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file simulator.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file simulatorv2.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h index 6a0a9f008..445358a22 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file simulator.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file simulatorv2.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITL Plugin + * @addtogroup HITLPlugin HITLv2 Plugin * @{ - * @brief The Hardware In The Loop plugin + * @brief The Hardware In The Loop plugin version 2 *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify From 58de9dbd476c0c021b3efc92e39385bc1988ff06 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 19 Jul 2012 12:47:03 +0300 Subject: [PATCH 009/165] AeroSimRC: import the simulator plugin (proxy) source into the GCS tree Original location is: git@github.com:hhrhhr/Aerosim-plugin-for-CopterControl.git --- .../plugins/hitlv2/aerosimrc/aerosimrc.pro | 10 + .../plugins/hitlv2/aerosimrc/res/cc_off.tga | Bin 0 -> 128570 bytes .../hitlv2/aerosimrc/res/cc_off_hover.tga | Bin 0 -> 128400 bytes .../plugins/hitlv2/aerosimrc/res/cc_on.tga | Bin 0 -> 134221 bytes .../hitlv2/aerosimrc/res/cc_on_hover.tga | Bin 0 -> 134442 bytes .../hitlv2/aerosimrc/res/cc_plugin.ini | 55 + .../plugins/hitlv2/aerosimrc/res/plugin.txt | 86 ++ .../aerosimrc/src/aerosimrcdatastruct.h | 215 ++++ .../src/plugins/hitlv2/aerosimrc/src/enums.h | 102 ++ .../plugins/hitlv2/aerosimrc/src/plugin.cpp | 394 ++++++++ .../src/plugins/hitlv2/aerosimrc/src/plugin.h | 53 + .../plugins/hitlv2/aerosimrc/src/plugin.pro | 28 + .../hitlv2/aerosimrc/src/qdebughandler.cpp | 64 ++ .../hitlv2/aerosimrc/src/qdebughandler.h | 37 + .../plugins/hitlv2/aerosimrc/src/settings.cpp | 98 ++ .../plugins/hitlv2/aerosimrc/src/settings.h | 67 ++ .../hitlv2/aerosimrc/src/udpconnect.cpp | 228 +++++ .../plugins/hitlv2/aerosimrc/src/udpconnect.h | 90 ++ .../plugins/hitlv2/aerosimrc/src/udptest.pro | 14 + .../hitlv2/aerosimrc/src/udptestmain.cpp | 38 + .../hitlv2/aerosimrc/src/udptestwidget.cpp | 537 ++++++++++ .../hitlv2/aerosimrc/src/udptestwidget.h | 94 ++ .../hitlv2/aerosimrc/src/udptestwidget.ui | 940 ++++++++++++++++++ .../src/plugins/hitlv2/hitlv2.pro | 32 +- .../src/plugins/hitlv2/plugin.pro | 32 + 25 files changed, 3187 insertions(+), 27 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off.tga create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off_hover.tga create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on.tga create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on_hover.tga create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui create mode 100644 ground/openpilotgcs/src/plugins/hitlv2/plugin.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro new file mode 100644 index 000000000..74df87185 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro @@ -0,0 +1,10 @@ +TEMPLATE = subdirs + +win32 { + SUBDIRS += plugin +} + +SUBDIRS += udptest + +plugin.file = src/plugin.pro +udptest.file = src/udptest.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off.tga new file mode 100644 index 0000000000000000000000000000000000000000..d8f4e0297073e2d74e5246aa594ce213a939e748 GIT binary patch literal 128570 zcmagH2bdK__WnOJ1OZ7ZNzxESMZrYQIp>^n&N+uWGvqV`$&wKz2#6wxq7oHz0CQZ| z@O90*rrq`Y-_PmW_s)R(`|~_Q*R8Iut~&MBdrqASosf_#A^i7z!t)8GaxAW1y?R2< zYSpSGRIOSyp+=1wIqTJ{SG`fAMqQgWZ92Y1%a$u!wrqKStClU->AEgLAkwN;%XJBa zQi#hM-sGykwTfKh3A2z;fA=dU9-EhkxYM9PgSB_vb=R7^@4kE8op;``Rxe-Eu3fuz z-MV#K+pTNYHC?-QU8ldbUAlBx)3r;Nb-J!gVXcI~pJLx=Wj z>({ThrcN&T+_}^0MhzRTu2QAS>V^#)rZ;QaY;{VrX3bV-ZPu*mY6a4pH*dbCxgxkmTC`}f zI*a~GZ>fO9$6tDcKthI4i)dVGEG|1ClIhtM%5}QhwReO1^&8i!RqN&mjqc6A7)WH* zUzHp=axA&=#v9%)T&U2WMG6Z;Z z`!h;aSbv0z7A>m3o9*VCi&(pMZ7mW>u{m?*SY-P2>9%3Uj2V`H#*FDUbLLE2uwa4p z?c3LQNw#d+EcEVz zE#Zb6Zm@`Ilp&Nz+>QE6AwEJVNO9whH(IKvCFF70$s|`U-jvJkz4soQI%SH@n>WuW z>qg3Y9U%f~X=yfo{CF#0uAHaNr!sinyeqfC+MLi$F$;l-> zUmj>szpkaPSY}I>EU``rvkZ2>j#N@bzA z{K{O_FxD%0eON87B}$Y~(eAJvo7UOJb?LTr*)kh2pufsh-KyMouT`#er`=DH3zR8S z)+=yF#oMjYop;#1ci(LzM~<+iOPAQ-zTK@}t!gTDK}Tm;@}d$P01rxCEGV_!NTCs2 z3PsHlmNmS3P5hRJynVb8J(QI;Ev>dKrK>W3J!j6Gt-bXZ0D&yIbLSqST74ZP3EPtw zCGdhYLW!AP<=NgGM$s8Z3>{=c2lWp+DIK$IYdd}F3EQ%9z16K#%hFQjnM;4(9D8v0 zHY-=QjPP67I(2Ag5ANM#9oo0^bUfF#bt`MxqM0>r)X-|zu5BrG>eR8MI(2Fr0j{Y8 z5@MlD_afX&<{r;-ZPc)V)u>+8s#mLKiv_gw#dB@(tkKr6PIaSm(T57@kKO`skw4%p zUR(So$R&k95}`0Al|U|H=nU1XRYJp*3wn`kHoEa6}~_3eUnrS7EkL!GZ+@lQ-EuUuwl zpMBc)KeXGPzi`fODPPWBfAwWsm=^I)Ljy|hsgo_Wh7IbuhUnR|r}gR6N2;Ko^^>sI z_wV1|ZY0#ZcW;wUHJK7Ne!@gsu{dJWNA0Sw^q2t zazNb`ZYgiK-de$kxJ}nv^c(O1B06vyl1qdeOR7sdC~^R{8r7=Wm!G|3+qP{rXAWWI0HfHQNTe&pNW{>M{wX5HARWoCH6tMy- z1tJ4Xus}KW_*=@CcLt#6!06PRdmy`9xw78aRFilYca$}V1Np>Ny!|#815Fb22HnWc z9r)>szrAalH*d7o;y>B34$du<|3&}|D0=qlr4F#vS~snmp}DaDGP4)jgXS)&G61u% zxe@q61fE2xGD$vxd)@|7Oz5YpkgQ=+DjIF-0x2}L|Cc1|rXzJBnLm&~z7D7B06zD^ z-VY=~Bg4}NN%f?sFThU_uxtBfJNWP(TeL9MUR0-_HDjuM@a|=M{`_;+y=!NC{goH( z^Upps{vF)E&+CfaBjZ=5#A02Ws9Se-1h@pt(fTrAZS1)5wo0u(XTkuhQ~h4cpZ^B$ z;P5|Egm!9GuOb~W-zJV8=G_*qr;~$*uASQ3TQ8lnjcZoArl%uQYNXw@QwKY9>T%n0 zf4aK;ErH(9JzAUY{raV|wtdt6cK2PC{ays|cGeDU}9ZOfKT)}~Dx)4(C#`h|L_ z)myb{rIW%H4JCSGy zC9Rb$Y_>9G0=t1qk|J(pB+`;|Z=FK}< zu<4?|&I(VG@E?}~`js?c0sTD%c_U93RQ1wVEV2Ll@^ky(y(^Z!YI)F9HL9uO-RjJL zN5$K$mW;4HJGWV%-aW0b#tu#ke*uaVy46BxVL>dEMko_d(w8l;`I81&of-m4OyGrF z*rg@Nb;}}l{^S8W`@})3Q>%t|HK?M5y4;hG9yI&!k7ob=!KO|a>y3jBz=$~e9A(NR3%s}6z4uhIYSr$sTD7XmP^w||>em*Pm5G8=Vs}39uIZtK z7yxp3GpUiqT^~#3Z_JY?&v2R)TT-K+bP4_q$9Mce54j2fTN;A(bjBm(?Dq&t2VoRaI9zfkD+F8+W;G2Vx~NCCZPU_~aZy=46)Kds z`!ovU2{@ZxNQ|ly?lYCOc`u-YuuMXrvzZR zMeo|aZi$^bvP*zDWX&2ka3KR0YW?DwC+*LFeP#ds`AdOijE@Q^4a1;sKDlCl{`7bI z?{D8YIAAJNIM2Ot>5SQ*KiZ%F{g=&{I+5NeCe6$$A4kE`HpVJTDElI6;i2Sfz|y>d z*8u6jiBrc9w6)7-+XEXG*?|W)*kea`+fyeG+siMWvxoNW^qQ#qIz1r$SnEm3v9PyF z@SEnBR{CCDf3yfApIeF9G&a3XqvWolkB_KZn3K0`7M_u|{acnSS&BN-@SotI_m=#H z=5*j>jlE9E75iVoa^w<{7R#SM|J>41u!LE2W#Bbz$Uxh*ZIddU->o|gjd5c}+H=o5 zWtU}qOjeUT@z_z@vT3~?J$%6S?%HP4rcRdf$nQo6qgPZ<2pHt+C`kY>5sb_AFvLsn_Cf#Kv@LUs#LL$FTZ4$o;xlIdc?*I?e97b3xVg(pFVC^UVhGAK6k>p zb!zLD5MV;QJkQ|#%P&5=hI|&s>YEztA0AgAGqRRjyB2X|71OA3&g9|x8)XY-PqH;j zBDP~=y6xJ$#)c0bU>Bw9%d19^CM5_P&F#)C)VFjgEUluK#RZk!1(hT~l#t1L(V2uK z4jwmB1-7XGA&LJ4i_xV8h5%b6=})7zxezUdqe$Uz3hUt)cK-sa|j)Mcx zp;X(wIo&z^kL-h2I`z5e{u)~Z=UVd!S%n*l@e-h3q`zIn@*ObTof7;-@* zhJr}FwvL|a#!RS62UQJYd{tCfPnkYib(?RyHZHSA_ieFrV%!T)9kr1|2iY@EKN&|A zElcwzfPiZWMAq{^G(?Imu#`q%XK@UC_E=_f0KN8Iq5*wcoELeKYnj7Jb%Fk_U~g)Kly|`a$ujm|Lzrg z<;9D(clQokw`P?iYtF1`cKFbKTe)JX`zsmnf~*!Tn)`4T5yk|XB}5fh29CItEkRCc z!}V;5gb1V%NFqdllulT2nz|NZYgaC^#WP1bO_h+T*}Jnwu8nKEoAOqTeAh0WZ%fi< z+v1cNR{4(G-Atxa0kb3fciWMJdu+$%)mFcDbsxsvEV$qrdHsdw?9jtIZSS`A*12tS zD}*U4_(4-oJi6abK7P;+J+$4LHmd8w3&ym`4#nEFYT6Iq{X@p|)=Usv7?Vg)BVd%^ zor$iMg|0jA)YtvU)hgOY!;6O)mz)c%v>z2$BAuq8bdpFs0#~-%yr;gaT zQN!)I)2E!6p|QBPBMuCx$bpe4-+3c};?K;aB#8V+1XnFdNGzw(#y2pPw_^~6_rd4y> zAW!C;S<~If-ub{Ln<3K^-&iC0;1(`iXqscOwr$(GHyt^`IAKRcazlm;v56BW`W2aW z?AXyF3}O=)%S1YK=wMk15ycPCHDJI1i;NpLE`XVL{>%s?!^x8-Sj{Sx)%r!Pd;6yL z%E|5a#NKo(TRPb)%D*yo{7Ac{;vH7$?z`+3*{%!&OKMQ&UYR*FtkQk=+1+x>-h0;_ zRzS{k1cGV!z{b^f+g*3rJqkCeU&}`r4E<3#X_47>x15Fd;xw#sj}s>57{h%ARJT^B zU=zlVu~jQq`mme|0UJk4o=`NP2GM{nIut2JjT+@);t&&Q5F^j{(=nAv3@+}9x84$S z`r~7qbJUk@@GlUTF*}$`V)$IPTVBtkaMmnYiis_M;0`GfWY2D0?Cm#S z)!!?&cGXhby?u+dYS~N;P{12A@NgH8dcO$%Gsfo5ooo0K zHLdCQNRv?po=c4K=YwK+6`U8a;Zn_x(`de?fR4ZrHG4QZD)2yF*_|R%eFn z%9kr`WmJKMb0^#0?Hg>@*0pxmofXw0H;MFuNz^%0#@fTXx7dT**IQ!^=JVyt@8nTd zLRh(AwmqbK5AWJ+-8;6nd>Xt!h9E04bD|xVx;?aSyR~c8R2EwaS8U7_fHb^Yx2r`L zEn4KBsF3j7W#aY73xuc{%!Z6Y7gkt%ss`jVAMR;@C(j^Dhg{6fh191`o$7@{06?y! zAU9%2cX>!|7Bp@YlNYd?6rUq!PFt~Tv3>gShj#mI6}&Y=5=zd{+O9AKtkS0G-hqyw z>-4V{D1hGl3QGKUDc-p!LGu=~9JRq5p^}k-ylwke34IBPA$2-xv*U9>PV~^Y-xcO$ zLRAk(C|C|~$XggtL33cPZr!@x6*HM_*+PlZf$6;H4v>}t^b(M(<0}Xe=SX8ZnKt05 zP{whj<>MB9P?}@-@F>#6J0Ky~^|`Ho_jZ;tW3-PM@03IBZp|s(Rp}1RW0p3IET28i zQt|d%J@&3j6@4Zz!Yy|cjW~RSF>n3gP)llO}mLLvNe|f#1|Bx3o1j)iOa<%VRV^ss79rT|C{45>cdwSJ`!Dil z!dA#)k}N(Xm}v5-ewMy)y1O}%0jK~TNKy0qrOiFc+;P+-P+gBtz|)*U(gcQE9+#J) zfaenJP~<`;a27@&v(jMeHno*ws!beI?!EI~;T5Mkh=i(PFle=p11aJaM+7X;AVp}p zX5w(q?XNKvr7tw*H)E15O`D^?d79bkX6MeF4wTk4n9A7P)KDt1 zPk<@WR}IzwPiLqkBtetQ@;aX+JUIwJgxh|?htK@KExRwfn`~KSyxkzG`kFhT{tVz5 z#)Pl-8B0Maz#cjl5r^EB5l(JCT?eBBF5rY@ffC&mg9{KXbgm*aVZsELIg-sJQO8rR zOn8cN6cG?Ti9F-sDoPGG_^EP43C_DRHW(2vyi$eqGU{VE| zPea5(#Dwi0yQ*yg5QOAdi06_hH2g=9s~Ze5wTP-ci0}k)cfE)wo>vg|8E$8z>;ZJ* zYVR88#Cs%YK!edE5gH4l;@ClS+zG`P+7T|stO0DAyNVk&Y$)}%2$+$%nOEI#fUR3P z$8EzEtkp@Vr2iHZ%EbZ-puq42$`2q=&=KSiXd9oJbBJbwK*%CAKP-a2rp#&J{W`!v zulQez$@9CGL{y4UF`*z=FOm`Wz-oJJ|2BCT9F_ zIY*tPr5HH8m>}0?(1ucM4}pTXbuH+7+j~r)(?Sw}U*Kbj6nvVKkz6EIKE*v>i$ zyf_GPPi-ICKAxFS69D0_ImG3VJ?vVvY$#VGN83gaWvY`1+J3}{5r0j~o>OjyI-NBQ z)TmKCN5lvX)-ag?1QVs#=gw`@Ck(RLS` zxFIW}jKE-tBg0wHp&T>eC^r2b4+_xsDmX4&tzwLUnvAwFSn*5>P=nsRL3}%38W7S0 z2n8D$FAO)C5;(A9ot=1Or(JyNh`smfS;xkx;X?v?kpB&mqs?6_Bm^y^Hj1f_Tv{3C z-l(i{H{C9i<)5TMQPY$Ti9{M*J>*=1SYp0U@Hz`5(d^=c|4K#ma2I-(yz*^@dL#CH z93zg5=wmUm(2O{*{9hJ}H|n)Kf#eYG@ZrPbHnR6Qj2J|JwQNC{^F@B-+d<3FYG~qa z(xiz#g2Pkfy+3OB&73sSwys|mMMx#@XBdGDb6MKA8k}4o!-;cCk19)?C}*9Hm`tmEDIOA{m;m4FtTH*aLknm37Awt}fvFfl&F206HUgS~d) zNqbiw`p@2b!~XI25AC}zKh=cR4twd+^KRFoB!LJG79(?oGyV=baItq~MBL=w@u=rJ z?n-h*xS!?8Z0l2YS(qYL%HKi=d3Fgg(E2NUiAgC<1Tlo5 zOUhz)Z!uxyt{0ZFZ2t>RnH70B;=&%GKcZtoBiL=hZ16dD40q|&nXDGi%v%CDRjYoV zd!$B+pIik|q8w7amNI*??R;RJuY>_NEE5AvSgI8@0$S?ygIZchC{Rlw^$1c>5Z*H& zwP-PxN!+siYZHtLL7$9_z>!<@72r|a6rqtuWinbNA*Px(ZEQ_7y~%F|=6DQ1)Q##S zl;z-_O`>~6S7scYJ!*83dVDH5&c{UW0<;N{&d^3V`CBSX#|pRF<@~#nq29<*R?|{+r4Rp9nwror*^Gu>&7+qswT)@*R;lhl(|05 z!3xo5HS@B4>n69}7&|71uv0t70g?o+KsNOzOD$yJn*edrmZGhzh< zG}qIbG;OHA#!xnhQ_EEGK;wCKJS1dBMk2_dog=8woI=@?OaKad^@NDZxFoetqpx7TUy%J* zh>B=dAua-cBsm2*JfB4yRvd4!>|HR*28QELgyBvG;7|eG@Ayfk*WWb6s3cCX~KnGUA zCV0g+K-DsmUcY{Uk>6AxtXZ>~jEk|KN!*E@N6(h>ohH z098(fXYd)s(UZWfs|e8_%;H(;bzyP^^ET2u8H_JYK`z1TBaqqEx zTkWJ=AWI^0CCan_do*{`rcM4DcMhSPv|cFn9s(cyhw`M=t^u6S#a(^G384|jWyqU{{DGUo$GI}c$8^lRIkU8u?=?Gh z>V%!vy1omVq+AtUMU1h-7#9Tje2kb2ctAK{!0E?PltR-bA!#?3dq&sv#h1wV3Z-0~ zJ9o5tS~bORa)dC3!+`+`TAEcA_pe>;yPkmUsu(vd3gCn4$ONB|mDN5#X|!!rN5_J< zO{{6Xwd3uc7&d4;siTR!Woezy&ft;u1OT2kL)df9fCTO*kkB)WhvMlxRE+$Byh^!e zgnc{7s(z}p*ZA}QwL5nFYWMB=)$Tp;yH%a@sNH;1K35YMT1}fY@g)ivH4Pfnx0bD1 zXu&}X^|zWw5$A z=-$OTv}@DjQ61HYv~1Gp)2Ekp zRTpW~s-@S2jd^wI)Yg<-OKYwTaMTJTbN1|6ZoMOKwn(g7y~3tXnc#!vK?5{zoI20u z&YEF0YgDu5vfS8A=zFlF{I~)ErjBBu)F3);+(f}4`NZSmAo9CeLbRa>GYm2Hj1yj< z%|b-#x(GNWhEHY0n;vmM(;kegB7iL~ve%w!tFqx^E3wP0)DHbUq`yf=tndxFeW(p< zgD{qRph<4keuq2Nf+>|MRk9KlwH1{d1`O!0O;Md)4wWibw!5^+q)QiVfx&awp^fBU zOH=s4_E}eXO53(|3vZK(!f+eurvClO72Bl1!!C+m)7i?_h4fou0x93HxU~=Nt zWNKMNuhuAO=wehR$a-+^UYA$gDYguZiMaxd#hB~nz@HzY3=TpPcZD@7c(+O)qO4>4 z*5cd%QLtA(M}B*2)S#Xto~P0By?S=H4ni4>L@z-iLD~-1Qf^k3MY_DM17;us%!UY~ zjVov)80!Unn@IwANdZhA^0=e`L)s|{E6~IVATC0*CM#p(NZp9DlZV{gc2GDx0@Epq zsq;x%-{T;n5LYFS^HLIbc_)x`XgS;xLxj5XA%WhavR1JC6e^f_FX@A(Qgei_y~3Ax zE5O$QE0q6w_q<}8H)zn{ukn=?c{KrF1Nu2;TD53u5dc;k)&gB!J9n^pb?d6v$I;bO z`jI89a7ciz)S}Z$NzjFUq>ob*%FmjjP1>67=n~oj(+dsh=2%YT9w4h= zY^Lb{2U#jLXra^%Rco*fvihq}bnnv1Ih8tttlmOaZ+Q?qOJCKLQYCGZ#*JkwD6RTh z>z2*`pU5if>=EL|Q53+%f#$#gV;+}-5JoU9O|#P4h$VRZ7Nu za*D$347Pl#1IW|Iaiuiz99%tKN0$feP!=VFc=;WM9cnjFJ~|ZTW+25H_ZnNjv_jj> zifz-MU{`9=F)LOepU-VT*`ZMeozY#vQ_4N+qlwT!(xi@FSu$yBRWO|N527CL06Q;=gWI#gx~E33hE&}qUg?ICIw z5lEuNKtYUSvSdb9nc(n<1n$RmTO4g364|(opJ6=c8jXxI=v2YZlRE$%tM1$P7e+aj zLZ(nKQEUY(93sd|sCT#nYtC%jceaOf^U6BMNQS+)h=+)~8Dkb{qBihYby8%zc5U2v35c(;PfB+d zSu~dM=Cq~UD@mz=rv?q`xku^r$z%4#2QS;_?_TotLh=*ZIv+bqDT=n-fuCUkLvX4_ z)RdQlf(e1pl*e$QU+{k3=W0u(*XnA@oZl6>s1{Ntf-x**BmI3^Ku`HOqNS7SQ>|K6 zuOIXrq?J0<@Wk`XN$&Kcj0P98ipUnepx?(;BB3-$Dyj%&y6e7khR+0p9a=CmvSOo4 z-3d{Y0f$ad9`C+V@`$4Bs>Lmth|1~7!RoKi5+6GR=Q*UJ%ze(E0N|%k6wdLO4<|jI z;ZNSYXctc$uuG>7*&An%+x^-njK*OWlC}AO2}_tJ;b|-{1eOM7BG|({-bWzT+{tz5n&7#s>i zaXyMG!C;t3Za#F(i8+Zn#PNk%$1y}@aN1(v5$2r{UYKsIt&a9T*Gu zIswl@wqOj^MLcQoD;D9eNN{EJ=lePQnPlG&K0{;RUw``2e)#e|`{C;kv~BF~c1k;< zAZuJqlz=8-tTsWXnlNhAB$MB#K6FH1Vws3ANgbg$sXQO8x_(|2%1zxUN$JvMY=A8K zJzLhilA_TzJ}XiTp^%cnqHkTMg&w&@%ZO`&m{t=Z+XMz&Gg*k6u$oXx~THAp`qcUrl5T z8Z_7j$TN+#}9F z6&d(Re0YcDgdZ@M81_|0gDDI@ag(dxQ@k^mm{PHD3%3$8-OHNs30QziMj*AD!Y)X6 zW$>4lmgaLiu+G@AW8|M7ZDZx5A3b`M*l3u#*ATC2A4!F-hVPy_QpNuLwYLpFd}4n& zkVzTgR-O?`!x>;hWhoAnm=M)K4SjJnlgE@PQ&fBHY1JGOV0XO-*I@?gWER?H^2Lg z;6KGfyLRuk2E!Ix!{JNqo*uKUM3WI#rqx)hJ9weumRQX}i)_}ijrP#ibelPLplwNC zAiqu>=RWcWmzBs3hcJzp0)TH|>`2@3qlm&H$JJ4J%NnR6DJiugtB~0xD@9e_vJv8$Tl9=StKX#dyLp2Z&1L)< zwobsG%v+#4U_|sp{kpYnzb4-I?|neqgVx(f)dR4lj2bo4iUZH-QzqF0?QUGYIMt3l z@{lcFnC4OddQ6*d-L%1WZr`c{cpgxAy*#Y*{XX+dNUM)#4kk~WV5_v}X6d3dOJBLn zpP4;trq4-X*-#o(F(^r)Pi051l$W0%XofbKR+gaUcYY0{DC zAqRV6$fG{@NXh`q;cGm3-tdKf6|u3Ec-NNo0`1R!K+89uUAB$e_gaY_E38EK6;`U( zDl6M(jg{%MT56`pO3PKC^KzTCa<3hc1vPeH7fVl@VfE|OlB$-2O>afz-YuKAW%Fhh zY1yo)CAF3lyS@|-CGj%l0@`zCOwn6^)8D`Ck6*sBW7>OLuJ39q(ruL$@0o7JdgxEr zNU@%)t^ZA3(ydoymz_Pn&*qHlYui^xtVidzzHbY)X+0 zO&nrZE}gQ`!w327Kf4rJTk`ei@7llr_|bm-=U0B3#e`9V?Vh{j$ky|e1-(rf)+|f0 zhqtY@RcX`g@9({=O|-*3ALhSY>DSeuJ{xBqRIggq&u~I}AbBL=_(}?lhG2l;U``CJ zO}`&^(m45WtKZf$E6d|g^;jmuhT_KBi1pur;9RQASgiw}m{{FUY+OfyV^jvPG zdn~t90=dfcT46=IEVGHrciG`x_uGWQU2RqBv;em1lF7<7fNpV}(OS5O>EzYGtOri9 zE+bLFwZX!pU)3nT*w5d8Zby$iVigChwq$jcGQC%6Lr!m@mJZXZX!ljtC$htyIrgBR zu(oC8JeePz)Y?Li^b)o?!*qN=P#P_Zp7R2!P}uSqeWan4k_*eU0k!+0PR8A4W!8Lc z1xu8*!ZLdh21Tq>tESH7IAdFPY_|2A);b!QX{9GXMvoraXS*KUVGjtojWjbW%S+D| z^frA%=Xq`4z16nu+Tx4LnACv8DBt5p_S^1#dTz%iYZ!eF%Ec(9eDtvUfz1-NRqnXWs@+>zhaFTC(mUxqm1-6tgPUt;0_^*5K9+!gx8HyJ zR_FRWE4G-dJ<+M6>p8Z3Nt(hDnbwPJ?aIY=^5}y$f66e&EQ0~q1!I@9joy9rqJ8)I zd-jjd-m!mt`i}kdf1l`?C9WV`smBoO%!}#jh{ZSHh)tmR9hq^vA&IyUwQ@a?(MQeyaRShV{} zL3g{Iesr&_lYX{&#a!#%t)tEn1G-vC5QQ#eMW+Y4ke3s&puj+t83zcL8kQ?j*zOp* z)=J7&D7jsKnuAGR`>ho#dz%#!X)-^3I#}#3Tedh&MPFtq^JeNmg*moez4GxxyDTzwgnjn*i#Bc2 zIQPhbTh6%xv-a!P_QU6I+dn>e(|-QyeOtR?k@s-K88$Mbb$mwQ;4JWb`{W5p62r8P zWk+5d#tEeG8!^myia72) z=h}Sv(OdS)xf6Ey!7cWPmd!t|v;%r|^^Ophlq;&o=LxSucUDiN1Q`>%0TJLa3J}Mm z6Yf=^Ye0=3%P09_JtN*n;_GAlg#oB{hNknMKiM~byJ8y!>QX(HS#tMfR$6q8fkIL5LI+}mq+o>Pr3J(4Q7V+%OdW1#f68G0 z^GEyn+fVF~LkH~EzA~G;$zT_aV|$bq(j#zs!@@Gyd(Pcvr*uBb#G&16(~5aItfEU4 zdMwdHkrZkLeVmgYvgD^y3v^YOq?pS`}@` zd{GBrUC_$d$7OQf>Ca;@kpHtMj@n0;FUcf5spA=RsFq_~hib{V{N&2Z+R&+0>=&Q1 z?pona{{zRA@9e2#I=JmcdrkM6HmvLZL1+*|DJ(Z-MOr0_mvDS@pe)FC62FCYJ{+E2 zPo~EJZSkKvcCek25rH2ES(i`=+28QbZ$1^y|Ii5Kd;8mauW2WNjv^T`Om2_SHb^T> zYSyUkE13@Lc|bURQU@CDQL}vI<`3sFxU@9s@#)*I*mF-Fv6IL4+tbG%u`@bGtarB# zzMrSKvS%y~kHGmhu7_m6u^?nE&Kz?-PCHwT5vy>iJu)sk=a ztuuZ`LY$`w;6D;DKYZ&2Kk=vrN+=PLwkQ{Q0Mk>wPcTJKEaXMT?ghJp_OcMg_bY8Q&pp}ZGG^t9Xfv69)9#mJAL|T z@zT@w_ABRo=)u}6Oh(=TBh1l!m@~@n|FECbiN5{xEon#&4GoS;3C011Z0yKkv3Gxb z`DMHE>hpH)+*y0!(k0upb-NWwE^kd*wzKEXowu{+FW8xL=d@+ktYt~Ui zgTuh7=l_O$FrgiCJTh<-R4YmtGTDE$vF5k`b5qppC%H22muo@?GbtTS&f(3UzWu7| z^ppMi?PtE$47CNINOR`NV}8$m|IWsUIhk}Oe?ATIw|8Hc%jpLl^ZJ$hIo!LlZMkcXxgOluJx#c+c7@SETKcft6A#YnU*S(db|djRdnzt(|Qvtb`n18&0lj@a6Lt*4RXP`M0<@Hvt4Z99CAPhl}p8FhU zJy9KDs*aZH)S<2Xo(nXhQ{L*_NFfe*XLp~JPjDNZyFRNQx5^X2O8luSvVpsEjM6hT90EK zvO@x#amCwy{PKeUpa1?&-I95qU!~~QJH}nU<-o?!f&J{PNO<#FjT&T$fNpX@nQ`y@ zGbe1l26yx#h}cI9B7EpHcup3e-b@McFwjH#X(`Rc=T6#_#}4{xDDs1XDLI%Tp8ntHRFUYPt~J zG+)r~GNYUKk~>?cmoG}O2iB+CW;w1mq%ZTM_y_mzL)vi^; z#_D9qwd$*b2ljJ=u%yxi^D}`gD5b+WJ2}&7=p;x##3fh9v7^x;9tsknx~C#3mRK>K z&WEMW%?YIPP>i>u>nDN|cyiChQ+g;Tf~0Y1@<1h_x`Jhh08tj~{->B99)} zZHb+k%b|ErdA_;p+O_}eyo@lH*g>zD`ND*y)R zqg_b2k09GbdH{F4`blA$m_VZC4ds(Fz%1_VfRRIlB#W_WX{1Y*p51lymXKb;IXujN zx1SiJ_Y!EM9IStP#oOF4$DY7IM~Kv${OM!x34;V0BSNMD zr%<$lti2~acxCiVm~==X@O$27Z)tCBqsH}pPi^{&#d0X7+T7XGh2es+IY!|xg89u?K+NuqsYdL6& zXmiBz?2YXzfC90i5Z7&_LA|Q%L_lU_mLA@nXX!dmS3!V1ZXEY6?iNlHwAPL5{I4vivQZx8z|jTDkd*kGJfG!CAkrJt0wA8vU23cJXSEd$cP2+uz@R z!yeIu8cjgqxWX!kKA77V6NwEvYgO3fk^OD+>cw{X<#TrVl@~NUaF4SLnHMXpBTgqC zx3Zd!F8hF4IbD;dK4k@O%pV7?%1c@=6~GnT058BLF3?S+aJcx-gxJq~gs4m$#c={e zrijDUu(A!aBt2PEEupxAJFRHB@dvE)@+UN7f4?o7H^n9l@1ryGSL#H<&aRet zDZ|!J-hR~%_>z+QZJ*{r5A4~h??bfqHR?1uZ*y&}D^*4bfHMYzAiD$#020bpq)70c zDt=&s`c>wq-%Vl_K^T)lAP+InJ!eASq(4ra3Cz`C$smR#=;m$63l0()pH0l4?|*Mb z&xvxIt|7M87|D70h5btdw^z0F?Xkm}>)pP^=X2@3KCCWuhe9>w%b7lQkPYk8(H762 zD(A>W`|6W-H9V;i0A5lk$*^(C6As{VF(9A13djKmAu-D8Hbxw&iNsTnKw}Vc*n?mF zIW$RG4+z6)DjN z9rigvGASu?M!TKg6wYBn|0H7$&h-;~BWzSn*(RNbK5lR~KN+vT+;HTNHNnD-uf$j1eEyDo z@zI<1<;QQ?w_m<*3+2@Yu#_0+aI|r~I<>4x!v@CEofgd+>)>r|2D!76l`SW0uB?WX zrORqRRvG;lgi4o-hH?|)Cf71bT_(ft(Eqr*i5ZI!3pIWkYcX z5SFPc!9?NfP7S9SZ2hMz&eXg=&LY!5{!c9i=1i~i&pl-?T|A>{VjM$J z1mDQOsJ;02E;7_MW6tF3mvuh&?7t!((!%NE+AlsP)1 zX`Js2_r<-=vp3-uyW{p-ty#m`*0x0>8`8g*rk`eOpq%11Gj)R|CXE|ogC76cif{ST z%0Hk#p|t$0XMHtLFqUKN7q#9TLeLa2a@5jLK>;bR!}%(Z=FbFD21*$i7U^a*J;;RW zhNKtc*qAgt_iJ343n@po&`<&+Ad{Tk;vf(^d?zz5!wwY1B~L|73bKq3>;fx*xQO?t zSnb`YARhe=n!f$weWCI<`}&Lb?77Duwzhk|v?4-cq?|-sqPVtp*4g=k@bkF7(KOe_ z>TK+z`l`+l?Iwe0$%QXVegAjmBImaKE~jGDvB=^c+RQO2&SEVH|NiyQukD$WN9`F+ z3!Xl4#Jcw#Y9O(0vrbk|e_SJVn|8E>y3O<*5kdv)=s$k(qfXNf`qLR3o;HZ9-k_}w z9Wl;v{@jy~+KHnN+f(ix;uZv`;8bh*ZShhm2b1`x)l%0TMbAwpZ^aY0I zH*1W*Z}Ra>cIk^m-VZfP_gHb~KE@4j-z z=AZq=YVG-_l}dXE)x&DC)@E84miNe*8)kg-0CtPd{Ys0o4A9jXn4cgeSQRD60Q^)LCb*K|M-Dk?E{<4U=>w8SC z1=m1vgust}u`0g%Bot1(`L6dU$qc14bWneLOP@A-Rjce@y?9!mIXk0|w5{`eac1C> zaOmF*^!d~Tr}Tw37~l$XqXmN5k}3ME;am2`g_HKy^QY{+SDv%ITi1B&F!Ka``!h-p zFySv+G(?I+I)OWZDkfjjyG?u5s+GThz1ti*EM6t$d!ekqV;43vEzB;ku@Wrd)deqH zQB175XOVMN%@lH&VmRpVw|YSW-w7p24gnf6djNO=Gz7fdd)~iPEzZQZcOHs7Cao9jN9tI+VkOI=IVl1kix~8PVGTHv+*Ro;+fw z1@?>#UjwEdJ=rci|AL*raMAh<(!QEW(-pp8#~wRwEj#qG8FSO@(u*(Isi&T{&b7`2|%nA2YdDy*tM}Q0DCZDz)PI@e4IH$6QuSZX+?eA)3oLvtL^z`o^Ub( zK(W+`v?_@3F`?TnA*_>?W8ih*TOzS1oMRn)xkK6m6(RD-{a)=Ue*5JM+9>#;eWi*0 zCl2qk{=K{T6w@kcqNVkmlELXob4_YYqN28`ehmpi=0 z(-eK1brPa(P|3`nC zO@8J4(+-(X-*{)Z1IH?hs#s}8=Y%+Dmy*TRZPW%_i|cnWX)Cs{U|3;n@$phOGD0Bg z8d?I>%ne@Ej67NXj(^hr{K5W^X21CC69V!u+q`~_pWHiUzX|TJe@ACXPhw-yz3$QTy!$196bSqDN$&DfEC&$Xd~r9LjU*y zPhs+h-IOPJDndYCWe&DP&{hl_U4D8Q+7Kf;*4ct`@N*gMoD>$B;>A^vW0+glU|2gy z`S;@w>>55K1N^W(6}3m)){xE7s8v^c?X_3+d9oQcbykYK^Y&#MHGZ1oblc9o_S&nj z+7-<)cIiFD?%%l8j-NQ`xCj4kk3=c@tOlK@9y?&u#|*UPktsHB+PIi`Nxj1Ig@$;F z`gW8)Ghx{2MXd}afSi84dZ>RK)7rwr{;5)Sz1_chrS`W?47P@bG<_|G^)%89D4MtF z-PW(S^3!1pryqaBp4K0$csA(hYRX4D1{kJAn8W21XjUrp*NTRgTJOXeRK=6^>5yWY z&nu?k&MmiERh`sUqgoaJI4|E2tgq-Ug1pkbfQ5&M)8p zO*K90Ykn5$bmQq#D5&WXLkG!uQ`MK%AKCYS@27nKwX?BrjXMLVc8=Wg86gse!5gW- z8ZIKopMc142D62dVc&seN(gF+Ck{vxrUcZ2-_(v?gKY$$!5w+=9Pc52_=k8_>Fe$3 zXP%KUqI0i=^y;#_hmIKUJag>eZrivr&6duaWC!&XhSf__yazkhs7)fJ6V}cb(8$oc zDY4X=3V1kr4aaGLkXX7?)W5%nx0EGyj407x&?JkQplP>BvV=B?`^%MDc3Ppp-I^SN zI2!;9MtQ*qHuRypXYq!D^7Hw+R~B3AjA;f+=bzYb<9D35Vhi85(hJ|QQu@1P#Ya|W z^XGQp$Whz9LAw~Fpw=y(>l@5)`Z#qK$wbrwI4URvIQ9rC=yz=>JA3L;A3AN6eL8>6 zbX%CJ>5bHRKD^qrc7>M9Z?#$D2HHn&T(BwHAdKP;rRM+-a70vDl*S6}Jz+6pX^H&M zgF7|vHq@nb>aj<3I8!}qB`5DmS#>~{uLAGgzS(JMjg$lHaZx5m9^PZ^TDSCV?x&wP z>Py9zEljb8c0S-8^}wF(z9}Dzko$wQ%!GsUcn4k;sP zU4G8&Avzr5-VtKGnI7e%;OIzm{%kaRupb+S|K(r*v~$m#)JSu%)zE0Nj+nh+%P#iv z%P-r=@zZVkoHV=q)*Ci!-U1omGwrR*Z@HCn<*nDPYoDQ7cez6r%yFwBoWtzk9cSU= z2Y1;l?cbg{qPMMHFx^k(-LiIhFpC~@b-@{$;e6b#z!Z?zSBMVTX6aW!{0@?nhEP+r8 z-Re$Ai51y%Snx{=$rM8>hsq5oUJ!|_PSZ!kl zbkZK+=~@L`)0I)in#AZ_e#02rHQo8~l~?SKAHJ}kWQo77?JRR-I873gr%axxMU)e@ zxL#*RcWiHmAKGcpNg+S>@HYGYZ|~X^EwW^E;b>P~GZ-Q+JmOiAeLy>Qzxd!SUsU+! zr8Bvjd}me_EmnN%#k2Ojw(xMY-@m@mci`8p^34G1!ohe!y)usJs4bG{C08jO(eb6s zs!Mn$)=Lt2+DB=g_!e3UJ_qA8Bo^m{x?4856S2TYj+x}& zbDlJ`hs_)_z#IFRT%H@X{|FnvEdolP7;t)FcOnM1%MD?z{Q4IdXVlD|O-}E(U;fYj ztx@JDS6;N^haYyOjyokb%FJ=6*oE&Yj_BXj#t-SC@8`|54_-fSpTGCIZ^l4*FF;0# zAP)n=*IeY_SF)J?LA4+I7Z`*7EPTIk>Y$B(_-!k?#Vo>nd+AbIEmC>=A9n1dh9(cB z+vxrsEnS`3cesnmGoqXPL*tb&4MYi8^xeKqD@Pi89-3(lW!*ZptY04)N&R|j!|BHl1U#-Kqz~M`(kJ*XX-R1d zZIA4z^QkVLJ}&d4g0JX5s-DD%9z%cS;uLSRlSdww>DbNJ@PGKm^V(ci-Sa&w1B-0~ z&&oZwePg;CU@SkKI)0SviVx)m?Af)G_cSmXOwJKX00E9x=VxCI;4t=%nw2COD}um$ zaq6wi6LB{)rdj{}hyKhy`S2abG`x+c5AR>^funp>dGL`(t!)<_hTn6bMw5qSfj{8* z9W+wh{KS*m==`v?>C#VL#P;qYXGA(;v`%dhX-$@*o-(43rA{AZyVft&De5!b9KfLs zV3JEh&0_Ath0kQYA%A}V`kz-JS`}BdHxm;uH#|$%3{fp#hmP#{^}EmPHSGp{?&%Zu z+KU(DGz(@Vk#e{%8l$se-I|uF&!-RW(Z&|co}iCboe__{;j?87?R>vP{IE=4is1;q zIY9U3z+0pFhJSwhsSe$G*oNpU)L$$wqX_o8n=tL#IhomXu$m3zVUR7Xp4)*d^_ z9+Ve3GC@3ElNPUXu(?!4ThxH{1~5+Y6uQ4W`2SuOdFAk;@l;^NlRi zqOK0SdB1*RUw`_xU6M;2e=2ShI6K_!kBx#Gg@NBRDUgM;#@Z2W`TX`%Ek@9DY~+9d zbf8>$OW;lJ_3O`1euY;C4-fAWOWQ9R$7sG+^JZUv_?kU*@e{jc+?yYiunpCSxpGXCE?HD zI*NPn!uaqC)X@VtHbT@~eZ>w2>r6v1YS|>rA3Lzi55PI7ZG!r-1gHp;f*2p#%2$ z=bzcr+D-NT2k+ZujYu!*!2O|PCd>M6OW){dd1DUn=xh&b>gG%wW)p_?w5cQe+R(mT zqkgquVh(z6tQUz|D6XRdoU3)cYhMq(F|cSyaKMVx@mewt-;CBCLN>glEsL=H^?DBvfC{(loJw4OiZx645%9c?=U5#%Wx_a{ zsI5(vD`0JjTCsI&ti1pM)E&($UK@&XUqzl+e-5yuE7V=$06~ zmip~&N?{TZjC!5=pNDAvn7Yo0YnPH!LPaVB6szgDj($1`Y2w6*eqh&{^i?{vYnj56 zbzN$U7B0~DHm2HYeH&!<>{&Kz<_t?;wZf)No$4$2Rw^yeE?%_2(@vZ?!JnHqcdnMI z&$qR!wUtyKi&?6VyRBNW%%)D6qU&;{U+8(PQNEG+^OWyQPs`~`e8PznoH&0Pg$%TP zRdWKR4y+O4Lv{|Y!3J|gwGcBh3D!nFE)>9=1MZ$5ox_a#4C52`SSF6ilKP~8td?bLw&_?OlFn;qXT@FSA_Az`IAW|{zkYt)HV3GY2Um_x;{yexTNspTdhCq36Tha8}R|w0H`gKM9}{;JSdoofsyig%+0) zvQ^p;Ic}WHg|4-!QH8x1+7a}mn=%PH{N{7h7KMWAXxaTrE$(8Ef?mv zw}o0y#nNGXRlJeGY)pm{WXa4E3ckQD{@w%xxPbTi_WYP%Uetkzx$Dh9K@<5ED{;0s zl%s3^1VuNnN#2jfKvf-Cm{YeHyyf)-lKJ{OIFmO&jZb1}$}< zZAELRAueAHs8yr7&aCg`#~?RqP|u&^VCdE|E!wqdDTv;sv)$YJQOfx8yLZ)+C2bkM z?Y7(XcbgyAOIP7rL+~sV5jK1PWd!V;?Q@zgN5x!y^|Vvy6uaOEo27Ujf1{j~rs zewB#@s9AXuW9=MxviZfX>d!y_o4kbWyQ58&)eu=3$QBz3j=ZEVPhu|6-s z?B{V!D>DgyHJEYdIcKYcj3=XqjYJ!gGK-~xe&~443Ur8O$psIxwKzgSvVQaB=Ncv5 z?hTATT;EN!6x`fd5guvbFs^WdE55|!D6(CUK2phy$T+I?b^8p`rATU(kXi$iLgRJ> z?K^-{c*l)o&vPNJ!9UcB8YN7}@&b`gkJ350k~iiN>0)_P>sz?%xkX8uNaDzaRZ|NW zF7$&zL3OQKwS?0;zI21{4R8p2y?S;1J17ksHt;aVck^YT`t|BX@7MD$$&j{g-Mapr z0=}D4SNJE6v<>yg5#T&SK7{KjZKRPB6ygnh1EXPsAXo146ghBgJ||jp4i-e+v1126 z91wMfEW+A^P0nu!8V*1vZg|JrBpz}=`%3oAO#QV*Ky|5rr-!+V8xt9huGc)cR+sBz z=;%rIjkx;4#pgA>^NLOe{LMCQ*=AMhwse=cuO<|~SmCQcT?EO~m0gsa30{f6It7p84`qLm{xK zz6#Z>nU2pSkhNLUWK~S9(xi#^C{AL>5W+fV)kA>Yz{sHdNS3-FJ*tf2rC-OHI3v1);g&Dj(KDXL^;~8c z%ixIGz5zD}21go5&Ve_i&ydlUwq&Klm^t`f14lYvV}`)U5zOp7RqF}3!^gObh(+A& zik&jDpD)+#)1|Eg%$L7LIhk4rxMz}LK0cu{LTiiSU{Hl}_$pU58O?^R5M24LK(MF= zyLAzfS?Ci4fG}6zL@vje_NkFmVu;wk7F67tc7;IMJgOj}j99|R!D!yQZIivJV;f(8 z;W>MB|8AQwdZ?%4?7Z9M01h|e4I9|oRxFrfV}|s$9qU*4>;VeH`-E#wa?HfSxr25N z=BP=Fv5EQ5agr>Q!w}^_dq#n9Ve{ttghC7bmqdsF*E9lIGsc8>))KfLERq}N++(rK znl;Op3?ow3zA!jp=^YXPZNWG#W-rCRCnZEuVwY4DopAyP)GGJE97jp=@84RY9l7w_ z2`hC@Oa8m}g*w~I%iLMC*~PDQnsySlI?B}TC~sVAyStXo9+bxouN>YvX3p_l08*}C zv1-&R;H)Q>{5>is&vZGz7SA4UvnGvl+5{S*qNc=-K$*DSQ=pbqSR;E#Fr}jvN)|T3 zBIcbAjW1#ejN2CQGl?eR7gyi?t#4Nsvm|;hEEP19lw_H$xrvCV$Wh#_`Ka-B0_h#w>Q!1~pyViDst z{z8qzf*tL6T&Sg&<$8Jt#M`l5TN|J`6Xrj=$rmr=5UHD!(- zU?TA^=v~`~2H8Rqr0ewU+1;Lf>Ipk3Qi^QTA&@!wV0YjCgREuSF4m?) zcdJ#unYC=!#d`J~WIg-n1I@kqTeqJ5Ez-4TUn|hHhdw~2m=6CRVQ&F%b&>!7-+M`s zwo$pDC0TE>%-qxsTnEI15i3R13ItN)G8Qk*`su+!{l;&eyctf7)Ef3!72wj96<`Ulmt56z}1K3DSbIm1y>zQ7{ zSHhfF&)|Np1Zkqu@S)nIS91^rlp3zDZP0W#WtWMg5d7SUqZt z6w$XX<>)E>h!XR>{I$lYd?@d}x?L=JiBn0Pt)*e)IlfXmS)Z-+@-t-ne^OHTNwSiV ztdx{4Oj%=8caJQbk%k;GQaR?R{c2*K07jjj=54?bTWBJ7vKeWwUfK;T2fz*GOT_?? zQ^sjACC(VSH7P+dQNP&ui9LB&t~}Y{tbQN83xc6(ywJfc;tgPJaVQ%$GaLPYc?M@-=+P10dhKOxVZ0;Ua?|w|Oc?|%B&{D5Dp{Zl=mb~rM;#$U1ObQ8 z!2NX2N1;8TjdqAi4nVEW`ys4zhMr?4fJ0MIwN9-VNm`1!KZO~#j6m@f&d~V}DOW#R z!TR+VC0qW-58;RJzYX90?dy>FR{!kx>R8GyL+?Kf=#HDp9+R zPj9(RdlFm_e*EWm;a|V}7=F_ocF37^@y1o*zWc5SYu7D}G*yxej0G^zT}Vkesw(l5 z*G;cVS4w@9fR2>z)vEjwL1j*Jnt$l{x>V)MII}~3J?CGPuMcnZg=e2`EAcd?%N(m5 z_0zQl3Oi@5T7IIF-(7Rj8R2u~N4!eQVt6%+6LlDKZVkmr7)7GscjrzW!s)A5g$-*n ziXszr)}7XAvxTy<)nR}Z5V37*zkU&CCX>JC;wG2o|K{R(ET0Bk*MicT2n=ZQ9Xqzy zCg<{?iad`VK1fcT0?Z?gh8!cssy|-KW*)6y``cQ(FL9Q2<@T3_5uki3mwz|G#jS z{tYEhZMikve)E~(*MI*QtxT16$ZvY?IZMNJ*PjzkEjz(E2T%hu4C=0ABS83skLUCq ziJ80rFArU}w=_$S9H)?vT_}P^S&ZK+QLBUy?!f0a~1ZYotQumFfss52`w~Qe9Y0r{KY&1UCKAGE>sJB zyPKGJkM3Q)118?AWsBy7%Ql^@ELW#^ZQKJ&w~xh?(N0r_nM((GQst6)FvhUm$CQir z>@!cd2>#c-+6OK z`01ZNgc(yOhwfcF6V9<;sAUZ48BA703g!V=WSB_YKS4<{CMZ0SyaA96Qys`G)CaUv z(0Y^oMG*GLqwtg!glPUJkHTuNzVvu_@ZQV98}GajK9bM=qtD)!DfYo|%gq;ud+xqE zoSIoAaS~B7i^HlWd|**HG~v_7@HD!E2?56|<9#KuXsaM5ZHAwFCUC+Y6ZAOpt>j;0 zW;4h5PN*Z%+lR^M3Nrvl)MX@K3LF_FTRU|>Q`usAhw;kLygJMf#zr4%Ff@b(VR zdB%Vz8aR6~_=x^&)+Iql@kzgm3n8vv);Q=Ch~>sRhQHwDuCQ&`Y4ZLrnmZ$GJm>VVTwx0tqRWd9 zmng`LFUc@Am8o>lF?eet0T3u9u)vT8H34J5)bIXqvvjXiqIZPu-fmHA8GEKn9xAI&E zB7lxNlB$-WiFZ8GQL`*z;a=vG#Xuagw;HT^Pg@F{aj4I(0JWza9+z)AUlQKNu<5)r z!ur*kX4;Jf7v2!8Hu7Zm@88c5ik27v5z~{yH!!wr ztoA(sS@i@mGEXDOt(6D&mxgw0T>L9fv7 z@R4h;z9PK&+K%wZgNl6Jd_m}}4M574FEl_H`nHN-V`DN#-v*3Yj3B?#5!tFnjT+h) zs!Z`$Hw%dMLLC`Hr~_35W;~4%rmQ}fct;7O(z;IFx<016YBxTtC3;Rt61B7?PsAK! z0iIZ4@sEG}Ba69>8#j6DNgH7xz6aN~@nv^YTNZtSZ^jvTo3-o68}Tx{!=ib!!w;Gy zUw`_x{@w~-=}3w*R*C?B+CYFFl7RA^;_^v>_T|TKy3PH!-{^@%pGVfJda{Llt9oC2 zq_jg?>GIuQK2VI)bU!Pij;E8FpbWxaoH&5<$LODi+QTW!uy}N2?^0?7YBt(kvvy55 zT)s9GS!~dTTp4&O0ZV|*SY!9gqMmXCmQh;EIU}(wSIS~i7otlAa00tJ)_JoU2z-`( ziQ%&+pDayRW86ru#~gxO^NQwQ=Cd&S=;P%mQ9#Ksz#Ik6&??JothdjbqXY``X1VX^ z2X^K{rL0w}mUo?DK#9Q2pdFO3_J;zwHGHNj*CIEK=>@pD*WOV+O6Ch&jVqY3X*2;C z=y&@fT;*jnD&|hUFBOZaC4*l~lmK`D$~1+fuz6gla@Xy*gl_Fyg}&O1tXEe_FJ0P( zKC+@TJLF(LK$9)2n3VG6k>bUiK-``cAmmH=k9H*bm$tO{Re%4~HX{hE@NTZby zZy{M7N=hU?2_D{k<+<>x)}}na^?~q+RxxEVncvy+ES-U~3gC=Q>j4%B%izb$bno6h z6j3VU+-jo^H?-WxJwpY4(gu9yxM*$bxw>0-(b(Qc^#~IuPPB#Z3^{J@R;qY*X=6u# zryhI2+D}prm>|ZLu;n?GbK}!@m{wM3LDZ6kbG=b2Nuzsp>ku+W%i>j=EJH*3_Y8xy zg~wo}+8v;i17#{3q%yw;_Ejn{og1t=)Z;hXeH^X3^ply4av2wQNeUy(wkJeg< zqiJ^# z`;8cUvOQA`}V!!Le-Vb*(*ZD64&0O`X?;6`fs)lv*V&M-O0`fAMx zL<#hnMOKD>8GWh&+`7uh0Ws{-rAx@5WoB@$6;UeVdJ(`Z^Hoaq2$^u;f@*OV_Xij9 z=!}kGm@h8qu3fu$H}}z_M@fjx$o}0~(es0yD{;ZxnPHaR9Q!W37YVP>rsrssN(re@ zq~XH{YtiXzj>FG%(XK^nx^!wEs&v*r6gr6scWB>6A`6=iwpJG%Ax3;eSj&$}9dwo} z9on^#|NMyT)x*P@BQ=Z}>Q+mqJG5)<8*rtg%HxLhlUS|fd!ln-PVw(gRUil+G5|@Q zmhe_(tHyTLq(RCeGb+r{g11G-j}5C&oF0x6r9+sD{25dsXfdERwC~0*^Y4?FdQXT) z?zuTUs$F1M;(6(L>%3SGmO)FTPZpH1++oXucgXZ{r-;vk;p8P+i?3HiHx{(6fem&;vQ3bBTrN?;hd*|OtuLaIdWt;MZv)+^)akm`91T*iuXhgMo~Njl!Kwp+(!%-Pw~O7hXKBwaY(Ha$4Gc{iH?j}|B6%(LCtwr1Su+&Ss*POO?x71QSo@HBA5dbt}%9kvG@6Id1mq``%r*~iV%FPe8aTIRI zCpGclywmjYE0!(IdC_vH6jGs!36;Z!4GT+`E)AJgin%H}^;FrADIEqtL2oAoigggm zsmFb(v3&V*h{L5=JgfP~;@F*|1(I{WfH@mip#!)g|YK zw|8t0ugELNIvCp{v$%xL<3N7s!MhdkUS>-RUN_X#;lqc7XP@2XphL3*j8!|AQzD8?cl;+~Zg$sOVW)HIp$U{sA z$zeZNy!5Q~r#ZT8=8UN#)-j2AmZ! zIRa29VZvM)ASwl>2Mey8B@PmTNi9qoDK7@kHzd^G(5Z%k2cj(JO?E|o-QM?z8(o@Y zsvh-uZ(uc`9Qn*5H8Jz3s$|J$-HR@|C{(Rl)s%L3*^yzc)R48$WDUeJ{E$F+2S_#f zR5t+$>Jm53R&dH&z9j5*oSZ*xTetKKHm+3*jSANR(%S_}_<7Z37mF61td|zG(>0I^ zN?93q*`=2#EP6yZV_jKTq@;PoV>5Tq+jyb_g4R${RH2ke?0u#50zG$ls}_z)VXH0D zP_h@&%H=1SbP?@0MnW3o3S5GUUcGvm6n5|4-N<1%0{8<}kWSb&_GhpNDNMM9<;thhw0cuY9kwF?X8i>Iho25`3Fo-BpvgjSx=2}=i^Ss}80`*vZ>7-jO7 z5ILaVQQ{sGr1VHFPzMav5@x2d(Wy^|lgyUk`HtIe3Y98W(tGv`@4fS;X%(FfJI|3$ zkzBwDHaQ-q@PsBB&I9+`*XROeWd5T!jWqQo1JW3_E~F-uHW9K85Lqb|G?|CIjUM?>!bIFnG**qaB)C=< z6kG?kO!uu?xgv}oHzv%|+B0nW$ne;T5MSvUx(ZHq(~Z}MV<%5=+MTnMRRq`_*7RWC z!;D^EAE`VYYukr@m+Fr@xRZ4^>I@$;IDGgzd+NO+UcXIFxcik|?sl7{kCO!v{~l2@ zy+m4j3or?|$c%uOwK;$jps^;VwMb+;!4LupNj&ky6Afyv!=G7{Fldls=xI~|;I=*T zNIT!Ckpce$5?M{aB_JGG6pJIkWfEC4mq%pc#0lp4rvtO8s~=76@Pe4DLLUKI{M zZ3IMlE&MduX#8`(JIRWTHjT4DUivMm=b4z1Ro5e{3rBJ3})V~3<&eZen* zz8q{tmYay}wU{;A?V6vG3H3D*NI-@n?Pmhrast7gQ6Mmx6~QbI-ECWxZ*0o2uvog% z3EFpb*_?@C-SU}AX)HBgfCI9K%qjCO9{I3wG0wsyk6l0-WO%X(om}T2E~9%V(Nj+u2^=Gb7I|kiJ)o% zE(#H4qyf+d>`-{xv}qH{Ai0&03!tD}nXct#q>6y%8nUec{2=`Tq+po)6oR}Ev`8Qc zv{3ynUAn}TIN9(V00Dpql%s#pPdr((Ux~;zWBL>+NZRdi{v6TvIS$jHKN-1lvOof@ zq<~f(W&iujx8Z0R1-rfZp%ZG7$&TJTP;HS3%+HYp1lA0~z`jm?@W%UY)$8kjg#88Q zdV6c57macruG!__dgCNXG!aSZx^;UPpr`fuHG~G5{`K~d0W?h!jnBZ|T?-VeoMaHG zZ8;<6p`^rGGINa5`AiNdRhX4Fte748%09*{h87k=7NTA%0g+h_M1V32tH}B>Q9AWJ zvEuPkidYleK-<|RO_Yvaq974i9I;IE6@fT$!dUVAMg}AIg2$uPjvg+HPw%6`jA_T& z?}{%LL5&H*b1lVIp;W57nwg1d(i;7jp@rruQtzO!2jW7CwIQ?9`J(ezD8t8PnhZDt zM~)b-L7!%$I+Si_s{8*5-ad2Z&izC10@Wm309Sqk@UdgZdM#uEJn+S8wKL64-kz>q zJ9{|-lWflM$A&XbTcxYiyi;4o#5O1v#$-P?ytWWN(C^KApi$bp{;=RP(htVa6WQQ<)c&|Aol+9`_Mq= z8j4=h_rM*2q71y(N_RL!W6^EPwlGjF`u_BvaDe82sU`|knbCs;4er~m9CWohVQU3q z%m7e1YFq8rn{NoMTO1NPw^cx2yTe0=HZ3hAu%Qlg5a^p zklktH*{3Uvbb}&M&IubbOGD#>Vj^t7j`?Z3==znHoFCRGoc8q9E1gbe`Z41q7Vn;; z$|PcYSWcg-FTF6Ff7ZHi;W_J_dZvexQsGtru7KRMz7iz^xIVIcTxo+QT1H=#LTfQp zk-BV~#351x-A0VgwO49rS8IZ4t643N9iSK;w6H=M7f}H{tWZ<{W>8!RE}}vwL2mKl z#W`3`)^gicSy2I~TAHm3fB`BXM{K~LRSvkK_!tCp{cGP+ElwsVgV}#(9L9E^RFuY zB}kJ_qRp||&R4zBe({N+sa(v2Zkmc$f?N%eyC84IGPQlOf^fTb( ze&*4;oc{tU4PX)SpH+t8FFtxbWZqMNZH-Ugd07$O8#E#I7F=Wa4y=6Z!}oai=C@zo zrX;Y>NHUFCj(8H_G@Z4Lz{U^ziYyN3yLh`6lK9vlj_m(ruo*mfki&V{n+zB_!WL|L zsZ}x%Ag99Up@%>WbsvKPzyzQyzXF6wF2yjwvO*NF960x)B{iVg7z(hYCUCOC9B~A2 z?rb3FBB6i?;1MzqoT8_&-Ks6Af<~J*%GzfMR(?Aa)#~sQ@=5X4^d2OI9*n(Es#wqw zrm3wI++mt3V0#fmxo_x|GQFY}R``0&$ zrPTh(yZ-N=f3;^3d7l>anSGS(4e`@o^`~suN*TQU@dqN>s3Z@bYRM(w2yyMr6n<1q zc|T7)VXkKY&$MlzLVS8QBuL}r;Gbw2w6Opos<#mE@mo8zQS)EIXYanEJF^Z&o=tIn zA~p(FDF9T^1UUmah^`n0lIRKI5I;d0LMvEI809y(Zr4tWW`tL+nTR$9gf6 zWNI?-m6Xlo6Ea1~PQlMkvOq1Ez(4MzHsBs2J)1QzmJEct7nO?2n}7fGmC`NgPiwtk z{M=6-y!~VJ_=|cYGBIU>s#OaA{vnr-l$qcj*R##!OBjRXhFt@{bJ}QP^2xw>fmFM* zl&j%1Ey}}Qi`^XxI%(nr(?dsd910r22Z)4rjT$w|)_ZUTj`n zHFzt^QNt3bA*Y~wkryLyT1x_XSxSg)*Uc+YcV|v5rG9Zy5Y9RA5d6o$v{+Lmmhl35ds+p%MN`5@7R@QC6Kji&WP8w=6czkh${bD1wQ zXa?w2!K6g_<*GPRLN<;G@+Je<)G{h$G(%NQ90;EfHYh+&mMiXy22L zUAuNMw;wfflo8#s#i2s7gjzYr`{|uo^8)VpMl?T;P)5eryjUIeAWOHgPs5O>SUUsl7Cnc0P1NbsrE~doU4A(Ol z0E)5fHxe9{x zX9+-B8m&{r9-6qN!;(bxIO8>HicHpq3Tl^Vp)I7YT+Au#+YSqN{B%+27v4gN1z0O1aJ;ED&Y*!H79^Vxu$8Sg%mfbxsv=&#hO5AOH5}@PLfD zEn7CXpV(G4eIrABzySiGx*W-bt>^(ET{d{|fbge3eWav4Wnuoz!e;bFq) z!C~^)VPV3k!C~Bpfr`c*5XOxh7{+TQ|EQt;b#8#R2bM8m@<{#e7e)^|I*iu&QA7I4 zr+u{Bj2Rx!jnP(}oExcY++*sbkzu5^b{jFMuj_N3b|VJ$@x8g<@ImsTWZO_4H{xh* zMmI)o95%CJHwXuhMAe)RgKy{1S$x@LmnjCc7Qx8%!mj)6tMFvu3vLbF#DWjagcD%b zNj9Z~I)kMWV8Mg~4*@3prbY(H<>(x;4joO0`YP3Y19PF`gwOn`e5r_w{^_K>jkLUz zhhb1+ynNJyAsmon5_}&!X@VDLFPNvC3?i1j#Fh#FWu**Qi3?vS#Z(or?+moiL6|W_ z4t&LPTwTXihht`-cwXw7PzU*qi@H;*1<@RE40V_NqhV5rIY=JBkdoKD>qgRKN8REkkh|mD;FK zMwP1VM6f9wp*pmkAbb&+gkzHEB5~#?BWKQ1zPx|vqKhvMl`2&VMEDYCOmrw^lpO5# zrJ{Psfyu~jbm^S&kXt?kOc-Q{5Q7e##NX+5OxrEGbi*n~;iDo8qx$_ku zcsvC-nG-WUyK-L)^z&yO?>&de^F95zNixtcup|g7MhqX816Dr3*T6ar=xl&O6=8bG z#*_=M3NgdC^1 zjzeIq3NljH!8Z*hY(W}WeE^suH?=usIg<|8(A z2jEwgx6ZW?=2BD;^a0Nl!oq1Iq%lmeBXGsMN#Tr>=O}7eQSIWA zX-Pw(Pu2v)35|yG%q`)lNx~7BFzZVKtqF@}Cl}VxoxXuVWbU>Tk*b}*lZa6Q55ECV z1XTmk0>nVU%jkf<@-98G|fntkLm3S2%$@jA2i|pH#DpmH1{I}nD)#gxZcUqon z(xN(GqR_U5efAKI)MH0$ zo|d>&Y-s7z^B~zHf+P=$9C<0nt75hbHqzRBq4uJbCw9}hXUeykQ556`JGh3*E-~e} zV{gq8mt1(RgDDC6MnYgX>5UdG z4h#2a>z}pjR)xFdamt)}vPlkX-9}QGrCQ2F2RQ*Sc%}$TX*GLpXpaA9^0D5-4iS@{ z#@)gkKoUXvkO81csBR0Wq@w0ir-#E9Ee_3Q93O*H^b~f$Gh~2^TgJ8SZdrrHc8AG; z(p-@b%@mqas@^A>V88S{^>}#_aP&b9RBwl0&;&Cko4Q4Dr!-<_JARR(x&@3n$5fu_*xB_DGw<$5O z)R1E#U^ML#N#ZGtR9;xl3pem$@CnmoY9o#E!uZ|Lr{GOQj&zU%iO9Rnz$BkfNK59T zBm)zQzRGA+f{S(Ol3zrAvRq1Zpw&{16Q&ViR>Cgc zi|?R5D2hxek{z4Vg(l)ej{5Yg&|l{0uCKmplM5kf+&hsCWLPsMksDZ;nUiqTg71?kCvA`7`y80AD^ zDDxHxNqmiwRGAXAhbssKzk`o&wpWfRi6gj*Nmg8Gz;Bu|WXKbIay`inDA8LUyeGW< z@^dmXJ?woq?$lCo%uN#{<}5s6LDsR}y8uR(Xsl*60z=>l3PfPsQ9ZjmN%iSUO11XX zrQ!A)uMB6eKUK@s?zdqdt_auWTM~}%m7VBRE$kmXR_UZWwzs{=6i5!ma)xnHpcc}e zz)tVK{LR4@#2D4r$3Wx33$(^Q!I~J$(Z!mnh5dj!_Ed}!AsWOOmCAhCK&Vc%imoxG z(jCfxTMa@qx^H7ZE{!h_?JAoywe1{5?~vLvSNPfj|VJZ8V$r z376&ARxLooWt(&ao+J&ka-D!Unhza(bU0?>IE8nN^zGT>01jFz@YtZU8+|os(137; zR-UgZJ4G<;ZD}Y+cCyS1X~$&8%&T?id}>+fcK!vSUD9dwS?wn^cVWjN=*x zy&BiR3tbAQDy&N_Bv`aoFyOX^Nu4~6DNlx|28oK$D+Ehk@`j(1@gElARqYiMvmz-u z-eMMSUkXf|RL5#mjY4%BUmd0uQiPsz%1SGrtc_;&q%DrY2OngNc#k`0BB??r@nOiX zk+_Tu&u6tIk3JBogtFaS-_cw&l4u2lpO#{!)}@L7NQTN4Y{Zd?w5dpQQ+1<#zC|D+ zmU4dJDvULdunq>163Jy&Yx$894l?H3P-g%h0d@ZQJ+Jn<;;GypH;4+WwR9; zA{~kKugm973}q)yGbtf}2B`q22QCV@cM@eh%IX9lU^Y}tiEc3qDe`$L`88lR4L8{3UoZr{vT51((RkZ8i5GH<#rDCh(OwJNpeV|3QB4k~I%x)ie z0vyCy!75QQ8A9n28A|pX!zjb&Rs~r=E+Q-*vGAmjEf6N}TeDCFEb$8`Zz^*Hh^9Ee zt_Yl&x|D!4ejzS7;2`Jj-DjV)+STaFGAeyXIfq4!tFO8;G}wP15iI2o)*s8cnl=$n zQ3xx(j&kTi64%5=`p>f?my9NbDrPyB?Zi7(DJjH_uX%A=!WM{fXXn>P34T~$J zGuf2sPFPGkCJjFSbxIR|6|y z8Hno`kf}_JDw*j3Oz&R3;yMK#`8_CmR|3KbN<;+bNL%j5ng&4Gy?b1M1M=~?5~+29 z1R+zyn=#j`|{bUvQNLQ@fd zb7V_}6jG3m4jd?Ist^Llu@-|a{{m`WHA~vOow=Ig38aj9W3io-v0589ZgluxjT$w* z0Zk1lWi@Il08my%2s&akTrHUfZSxV~OxWYGzF#$aQf*hBawOAKB4@Zcu>Tz(0pXy7Meq)mQD<#qsbLkG9MUxK>mYSU zBUQ;9DB+@vip2*uQZ^XwOAz9y~E+5Ur!}+?ICrcYde<@Rs13*Yoq}fBj1h0UiWqvAa(;gLF^bQWxK581qRQ0EuyQb8jy0-kUY^d2NUqs}E=M+FIsRE^o#n+% zM<@@ViN1!Dz^LKFhB|bHSO6@DSZ4^|2M&aQjuvzX6zwXJX@r�E2#7bUc9FTcjBc z6GRAOLf;xccC@oyvr*~jQ6p?S7$R@#;6ciDF5)p-YsA^xg8PmiH`;b@2p0MtzFwlR z33@@6L_qX3tU`Cty=ZxW32BmZ0!d+N9_OR)o7qXFkLv!{#;#bn9%eP$mwHdLCUdTcuzef~<} zWuJeY^15E$fA;iNbUkIHk|7&i?_|a5ow;(ZFc`D>7<-~oEYW91fp=sBWgKK_&M|W#6Gn;-Q7II;tOPA$QVKW!wVE7_=b4 zL?aV7$CfKzid5qGPpz9@xl*y6ETG?w5)q*%uZRnjT|PNRg)UpZ%r%!UU*UK?*Ht4T zMlmwQx-o`%*|LJWR;T82opDWN6;3rdVnpA(`4X=ou__~y!(00+Eiw2T^ksmoP|70eN%28O`SJ8ySv}fd-UX3$#^4M_P#8Dx0%(xL@|B0iAhKXZ_D&T|wltB(C8K>Zr zu?i*`JA9ynO-2t@fJrv+gfamm1f6iC9@jXI8K$zX6J#=Su!2=oCfH=S{v5QTz!ic} z2ujItqAIOo?HHnR?3lq3hKg3Q`>l@2V4;OP>r>hNnI|6B9=D^yGU*3PW{sC`Wm4F1 za$L|vC{uk&ZJ4T%;2`iEfj}Z>29IEg#0O8_Th@;Zg7=G|+<8C7Uh`x7>K0 zS3TdNrK%U6e~!GW_I%9m`qKndY5G;O`@ z=IgyyaCK%?*rpzwD&za+i#IBs={DIj$Ar6XzbRay#N6Ct%Om&8_^>L>6e}jN|M4@X z*GE$*DD8!dv1V@^z81@^*MD7?C?8iI-C_>OCflXWg zCXebLrj8#H+9{w0MYmqPxL7GC`T(k?8|ltpY+14!bhXZRyvUw1nB} zt5zR56xB$MaW8gE@7pQ+Nl|5==at;~JHrCgoRwCNEKeaV3|^t{(XlD^#ec zjC-|}aZmA7wK>+#t^keeULZY2r;rE{1)U5y(7+u-9I;${C4nm0 z>07TnXEW#uEh~6ZYxBUzwO3pcu2f=BveaUyB9Xv}3+IRLzx-HH6kWsRa&dw~oYl`M z6zBdsZ?YTW^H1K^3hqg@PnCiCSnnLN@4gB((tYFHirY+>lIqL(p5%RFHgcYG zh*L-R?;9ph8XqpY@Vs!^nvCU6`T{;jycTvDRO6iSuL$Fx73FFu$4JR|kN_zPk2Mh; z?abCWN7?9l2B$$q5KDn4P!lQFF7&z%n$R!KI&eZY3O!q(6{MP;imD(pLwk145|Pz* z>UjBCIeNO=jn`ir4sCLv*DM{;LTi?qHw|rC9xC8B$Qo==r?cijA(rmpF)&hOJYKeQ z#}47EPu>h)ez+rKUfOzZsPO934~CT|ogf(_W+5?ItU~uf3OGWFMhqLGOpKp~kKfoH zo_qYRka_O0yF!)mQW>z!7S>L!IOeHxO{!QRQ@`YJt8p}Lv(&ZlHjFVZouj%?Ba z>|mBsWGv8J{oX-1*IsdP_*Rizq*#4TX(68zqH$CFs6|wpm1cIJj6mUkKe`Q+5o!-H z@Jtj%<0~4X+wuvu!K%4_me#tqc*Y~j=60Uw`;$*T9`J@Ctbz%!3fGT@>PT0O(CQA~ z&|R9z2(7IWJ=39%co2!)phrQR(W-hN*(RQfhp5)UB3TEBW<#!Q$1K$?l-gH(4Wz1u zV+jk8$_hJLHB{&Z3!6cxzNvnU!1_bpk28ZoDrdUh`}u8;hL!VWu3kLVE1581uUj@V z^z72ktC*PT$#l)<^NMr_9cc%LY2Sx@C_yQza>1N6=M(Ir8L;LUage@Z9M$0nX`g`OpB&ftfV5E>B&}N3joO* zc{oe{7>b(}@bmD!cbW}7p``m4o_m&5=OYB4XB^wbs{dD>f7(N~Y{{bV=>2!=UG@mK z-FR)dM8t~O$#quz&zpUG`02YZLRY!vH*Y#WJil#=A^e!-F7k@Qd_TiVu%5_%_xVVF0P_^9PVbS^onq zsVPZzW=t4p-`cEWV#bowmL6|NBC!F!?An)fZgstyg@NNtnOPI0yFue&z#Mz0gKrk)ejiDE?ah?2P z1TWDC(89J7e0Ya(+8BmxW-LLvbylQFv2ElL_<3607!af&P@^|NB5wPZ3RBePX1kr<|aT2A9tYy}K#h zLKeV$4D2TD%|hqV$#f)xj-opKxXI4(Jw?%_3PMuT>xOJt7DTUhy_u}N78`JB6OjyiT_sT~xMC(^eJH}~Z__oNQcq{ryN zIPIe_%@lB!Hl3#p(p&{39h|9|1KK>^ML`!`@!x}qM~;udYcP+t=}hQLUq z$_fcd1%p0ka0k_BroQRE?K!vV`&)3Pk`xA$)UUz)3d3NszH2E?&ZTPsAVo9OV8gC9 zEt-T*ZCiy7M{0$PmK1bqd$@+^08_g-Bv^LDzBH5^0jfJOIs)~JtOqE?&2<(FLOUw|*{NnO^K<0Nb?A=mJT_QjL5nzQmn~q5?MK%Qx2}A(Z?RN(*P(oVq44ws?68sai zfGKsjt0A799(@1r;mO5ZFR4blOQA@RTB1Hc77+KLv4sFFluj*|A`*xXbUlA#=y}Vn zq4S2b6ao>Q*FX>;C--9+gC zg_q;2MkfWU_0V&=UUo%js(`jbM5~zq=w#F#(mw`P6s)n2q5z!@ICHvxF}iA9rPk0vI;3!pAN=dBsxiiFU475DM*-V<*~eg%OlGu3bGr zlOr=gIL8AHrp2l>Q12a6Kf>s zCa?o*zL5tRblD@5gJ%LbCXc64+|w{i>(k^&%F^!?`zpDp9<|6v^~Br`0M>aQb}?<$ zuLR9zN}be9Pj99^N%0oA(aQMYFra)uQ1xcI^&xtF!stn%LhhV|Kk7RJiG=b33@Wx1 z$GFHF+ z(1Ynac(-*M>La8Q9Rf~3B2hcTu^f%`-S!7Wzz)bkiE=PhInq12b!4&)=GV`kYzALHk%|0>nfw5Ai0yr>;ji7eN#m(3}>Yak%7;D)ZEHE)pU zWqOMQ#OGyULe7L%WkWIa%L#B|AP`6^;;QMIAyo{y12AQrFHTr=g%a4Y!&=RoWuJ=K z9E>k$TsFLiHKVn03hAF*@L0|_x$84eJfyW)d8ZI-vXB-DCuEdy2r*#b3rZKio{z1X zCOr~A8o>GIY|vJMOPn1UEeYP81w#&4hNn0Nv!a{S*pafdpL^En3Tjv&wfJz^w*PNn zmD9`(E0aK{4Ch_SVN4?vF}5?wi+JJ#N;TAs7{E zCCWLc8(L2pYezmhuTK!CJu|u4J?D49o%?~86@C0=0vcr zY8cr#!%L@O2Znq=4vwk_jD9B;>h6ASg#^MJU}&DRwdP=$NS)wHO%u-j()*fITAWNo zF8TD~4{?KuCm*>l{Nwx2!{0vtK-))LAC_;rF&wh+`mpaY7li$ey&yE4aY^X6;i0hc z(#ygoZTWq|tYgAOI?`KgSeVFN^qgA=)R2rDJ4%_qp0ogqix4?MsXa8Oa6zud7g>=A zq2!dr*~pc$7zm`^DZx)^f25l#NJu$CqIa?kmt+YP9mR~>D~o+2ZDOs{rpc8KQuVZU z196Vw)+Ukg*Sxt0$E+6`?hORz9j8q^W{eFnTZr;I_(9o#Ap@6MCy?<}zi34U zjGA0Y?_ywjjT7KB6@)(um%!ZZimA)gh`$m5m0st7;3c8ye&}9YeN7fJnbyN^KYtxw z(YBt;@B1+9b3@QL-V(wQ2k4)JZw%p{Z7+s~h$mV!%g2R^FIv82 zz9`6S1$|6Ws`eSmbvs?*cvF?{mfXWLq%C5Eof78i`W#}8bbW!YFFs+GG6fvt>$4Ph z#I<>SSi(zD4mlMH(Fsws zqTrxkZKaU6+#etph=-4vFF3(`O&ulG13n-H00A|(G@!h=o7zC1vuOsJomS*m4w?W_ zf1W(WKr;7=#ePNI!LV$VL_e-4s<>l2J6!*)jkmuFFFkc%SbmobfLDjm=$a4?)L%pW zHNEb?;f^iOgu8CMOo3wK!zO^acwVH6dVA|91;F%V(AQ0yc1&2gYH3)yd{I~|u+0<5 zW(q9RbdO_?8?EFy!<9*Vco;uns1{BQ)q39{{ylTrq%iHcamoNS#OJAZ%;XVaGJlgs zgbXLDO`NE-IO7$Wq*miqbK0@vG#wO`q^OE<`WriDkP_?<(yE#PAv0$5z>wig6-u0* zpl0oron$Y$_`oNoCn>vI*(X}A5$!%Hsy$etHQ#^#eZ*$dP0HF?wQ5yW%kG*WVKW7V z1Iuz$Q|RO_Y1}xPh0B5V{pat?arSp5I{Gg9y4C+zZ;m^Lr~2l)8q4&XXs6N2+-v{1 z@*w6i*vZR&qVg#-lTuxd78Z>YV?e|cBtbe%+=_B_tc`<76IIng0Wl_Reat)4X`jgH zPTYJKTUNnuRdj|6p$d`}L>cKZAM|Fi zMNeVf<-VdyEIiq5x4L098#VNt7D{MOfy!$rRK|kBFQ0Xpd)BpsUjb!%X@5bzV%@rRpEUGHU$b1XDL?=GQ()&_ zlf`P6TzrW)Q#Ft06|9mHDijx4MuHfFF-$FTjZ(qvdPl! zm^KjQkQ;60(8$vsz;GS{XgMc4QYMrdpD0E~!f8IPdhl`xte;oJ)3YVrFTMi=jyoiC zcLq!sgCq*ZUlTuFzY_L%dZ8SU`1YGGJtOS>TmOF_K6&%mu=&|9!l9Rc7aE-TemLN) z55hs`eHI2k5W@D?-;#WDZ+P&|>%upGc{gl2|12|{ggyEqY011_$Bym7MHijtygS_` zzjyD_A#~HRN7oK6ckiqW8=S06=4h^@8eKcJ3tc;EqlXShhD;X~YIV~Y?!hs&cUjH5 zs1`N5DsvM%2(bMdjXKE<%z4Tgew4(TvR!h99~Iff5*7(2A#@^*@b21cfZ?iBmaAj< z?|d#rv+u)u@4Xhj)D^bVsad1CWJJ=2N%7UR!=3}s z;6`+c2NQf$#x?{v_`xv3V*n4eGoZdQriOj>$3W4J0nOcm9~IM(LfN=N?YJE~&$ax( zX(Lo*Fl#GOWiY{b72c8;fnCEyL1nI`w*>~1v^ubW*;AX@urr1&wQ4sTv3hP|n&>T; zc^t6i5tazDM+c)7^Fq9YA>N4Q)HB&+(x}Wi?!lKaK~|i!I9z<;IZC~8mP7A0ZM-n_ zA22A?+fNdH1LYTP(K4)Cuhcyo&kq~VKU;NUKKx^q;0#$SCv;|^iy5A-A0wsv)mL7$ zM+Q|n`ogoe#Hu!f<64v&&Q)|~JSuos@U)O2(J2lbJ+zCR;kulT_z7{8rwmT?BCZ|h zORPZ&N*?`@M9pPWa&S)9pd~|P4`TC<0(;}OiV7hTYWLLkKuZKnt!NJa&7yYO6SszY z?z|xU_U~V^sD1gRC*?#vF>HP6_HgCZ7YO#XJOz>seE6-ui z_#QlgPt3tpwW|zM&oImatl+*ibhHS0%>gmwl`OJ5F<<@TamMB8bky5BhNv=!5V$W z*m0y!8kB;R_?rm@v4?=uZy=ic$N9qhui+8-WgyN0kPuA^-U|{44tWB<-6>hzMa*&5 zH{zBRC{cjOa>ZX`KDwum7J0!_f{ zAayX5%~Y+3GbV|OW{(c+7_XLaxKJuH6|M@Ze@8ACn|M}Ms5vyO-mo zAxPK>0SW!i8!!-nmw_vTmMX(^!%!5*QKee^-TimiJ2rDwyPx8EqY@3EeJAdJ~b2+MYmD=!Vmwf(#*8AlF- z1`1_RG}AjMzIq-^LhT&M9uW+9o&JICv>NG?lSj#73ld$m6dA;wz%9t<9ca;5cWk7$ z$IccbGldpg;ZoMU#L+=;EfLMN>;b=O`AI^kIQsv7&`~HR?p(@Z2*2nLPA}nI|6PC0 z<)Lbos`de5YIoOFBA_!G)gsYopeuA*R2k?(OPmzc%~*A!D+J^gEJ)*e5kug+8kNRk zZfHRMA3!%>JqK_3>_^neU)BHuVvkCc}cB2l&g`k*%HF6aA-!7l}4xQLQ#)MZATaKaop0S^gXJ9i2XJ$#oas;H?t2--W6JrIrH z7%L3dwXIIa}ZcE1XHre*D=)D|Huwvb<&Yua?&YL{ENw+yYAG7qszdwG^@Uf%QQ!P6 zba?d1Tplpc#%C1L$RvdtosuKEJpNQT>TlnME-$|x_SbAe-yt&`Z=KpYZj*@$1()(g z9DB#x@AmV$zyE1ys5qq*c}Yit>hiKecC8Sy0$s>Q@j=$Vy$lkoC!#idktj5JL3 z(g1>22vZKPdQ9OEB6#xt*d@3(p=fO4#VR`@4oKsU=tejdtdWITWbKL9ztmSjOXa(Mg0iee?>uFmHZ~`OV-{eZ)%Wt?3 z-)=R-{QzNwJ7o!L7R2t(68DSmo9$pf+!ipNO+%RI*-iHq|Ioma*ww@bUwPHl#Q&u z>Jgj+MYaB<4?_C~x7mDVYH^5yal38J?|0a+ZM(3a$Uy2Aq^5y8WwAp}DA7M_BNnpy zcUh@$tp2SZN+>0{G(RFPRis-|_oSntSlMIc-p-R**GRB6fFpM4`;r{oatNn-q|ByT zk;Fp3a%i@OBR6>TI|2X(8*Srvca!E)-y_Co5o?kmPBsHri&}{Puc1`Tx#s$nVS`rJ zDC2yUc>XY(bb$dDZe&;pA&)KNxh1e!3LIBcu==0AIuh4-mHC#4ErUWi&c7IAM;lZZ z3jlhCXLbg*8Z|H#B4D#%-5mqp$`wnMY)1JVMPKi_^H$sKbF!i{wSN&$}vV2yWe(a==;vQp~vI$=j%o&&jz5w zJ*v_!Spg2whjqF9Dp&8d{e{q2&mvshS)(gK1PBYpuwN*%mPlqbIrQ)|j)t24X%In@ z`cpKaf$~qOD~cgc{4(?^(4mR5(@WX*Dj9S3Y8KJXN>dS!aQ{~Dh%kQoqimoVnCY2u z9B5H7qAu@y&&g?~C($IOnFFl;OMAi|IK@~H4^NqQVB3MIHR9lQJ5^)5Of=h}vGAGflGYW9a1u0bqb;&-8DjE~0Wz$^2mnsf1+VU}$ zP`)Dlv)bQiSQsisgiDh5vh+<~OYbBcWb5fntVeHfJ;z(JBTybe)N(K8v~SKdR6E2G zL?er4l_{k&;3tkz#H2}Hd_x+W&Qf4(%SoLYPd{CggLl)DU7s*^7At-wCieHgeiXWE zEe2lP9KkC|Xv~4M0@o4+q-@kyr5=%C949O1#BuU3BirC8Lso!i_-jqFAW(6klnj>j z_Nf=DqM`9#5w%$pl-@NNi%j%+=iIsva82JNRSEoZhg`3xZ`SNi(gD{~4|oK1L*B5B zVj$YKZ4;@u=19V9+PJu-7AAp3W7gXc7Pk;Q0c?tvYZ*%T2`L4!j?b)^qTy0-FR*mR ztX!Tp?wZJC0xTkHhG=%@&7y5tgsjZ;q_2$xGK!kTiCMdIi|HW`FJD=lKG(2x1@}dq z#niAQmDOXSrXERU6zJn5;FfNig)hK{w1`Zsg$vtoPXTbcP7$|WN4s(n9}p&AH=lQ@ zGNuCNCtJB~SbM5{uH-iWM&`IX!3}2Yao~Ecv=1e)$gxX@Hd-Qbgz<&^7$xkyYZoL! zLpq8EcT`{{JAtvdj5W<*2k{7+N11N`XZ+^#B4>c5FbnBkW~TMMU7}i)?Htw5sYSX+ z8i;&fa;AizOjR58c+M_#KO)vh5l>5ySxbC!7+Dh%#EiNU)}uw|keK~wqix>PLiE#=vRDcj+n)ywyjW~y+MU8l`~~TA1EZ_vv*zy&pdKlc;wD&!reDtZp*!m-6lZ1 zssWe%?DXpKe4=|$2IiMrS(e2sr~$BqO}V_FQiL~!x1>ZW(no8#IVmO(_xuW3{4Ix*i191HQ- z^G3%q-nlAQZ86f3i25-@``QQr%T4hd=p?r8ct}A^PJ-iyf)(O*u zShJmM*{YMnUqlD*ykT>=<*EzAtygafm!7{)0RxR37X)k)WDHUDUydo4K&lf>bpL4m zNo3D)gz3Gg2&GxgJ=_JA=`w1kjw%FboU>4JQoentWw+Cg86Som-8&2&&^ruPZlkgR zeY%I@qxH|xy}O4@e_301r8J;#k1%9FuP}6=c6pacx3ALq^*gGI{A1kRcqJS zC?z;Tg*nfA4eC>VM^<4`mPIpgNrCzlzx2M8QXmVyNxIQGqbwbWOsSjLWpy7ZihSfg z`lAhl!{ZoyB1_?NvA&WJiqIhGCz#NA5FbagRi^X!8vE+9wWvYssP#}P;*>}KcanrF z>ncZRkZHL_HS6G1W4H4+Rsj|WbPym?fBf*p$Ke-kdCI~#x@}#KSgxg13ScQjzJI98 z$BiErCTa^(ghS+_=w*y=%s1{XTm0HnSA??X{v8gv?3Zx(RlkN-*ZwPXIrlZWiQ~%U z^6)IQ1jYNLkFxNTbB3q09CQ3$93<*H1(r!zS++}j2k&Rgdm@rU9U@E_J;FY=Z+}wC zOSA=@hTc*YbRzp<0*|YIV9zmhEw@WB173uxVmqVK2n(Qs8=Q)1rByMHI;e<+PoQ z5|~6dN9X%pR4>9@U6G6r4;V<(y7ITT7Gr0Cj0Q8j8cNH2l z3;BL(#Y8U+E`}RL79H|{y6B&UFvHmpr$fJ_u_@qin=SJlLiUy#b=GdfNafcp}x}$i;f7cA}}knpS)r#PN^3<3*BArIo8k znjyh4?_PQK2}N`KtiOMT@4kFL+eXw6nKP%TZBS~Sv5u4gn4f3~6`5Oz`A0Z9qE(CV)nES-&RD-T zJp0U(;r3f^l2xUBc-h%iHg_XPrsv#_!0irzfkVTX(O7 zFP$~RC}ChXp)msh?Jh*xYT?TY#bs|wYKOUe)$vKvU`m*sP#H%8c*@G=J> z&1w;2o1(=cb!d46CpEuNY;6UK>6&M^Xw3lYcz*dheEz4`!;Lp@4yCQ-6KN~b*-p3B z-(D^E4qXPc)i#P7!sX|$4WGaJVz^4{gh25z$Bs9OCr_H-ES=c@zWM5N<;b7srRLBn z;<$-({@~p=wDR?v@X1H-JALJc@4X!km%*2$ue=M$Y9$J}MNubjXqn>c&pn}pUR%R! z&u-Dm&d0s{=B<~une-#6(8gn54Qk95q0rc#J-X@1olM+e4qzL^P#e@lyCNhE5)Hn& z3i1iq-TKfy;nR0s@w-D_@`A0Y@=j`)>9zsBOCr^YypL1j>EY5-a4y+Yuc^j^%*3_r zvvL^hQ9IP1ds}FvRYQev-z^Jwlj)t{&WFakq+1o`ej5Cy;d}6{oG&EUNwUZhY{^Z? zJY<-A@2%IBK5>yY)9sdHf&e{A6f##y)P?)lTvd@@hsv6OZ}I>U(ikMCiChhe!E;Q1 z0I7NuoFjWUyjd*{6nSr;Yh}cj#N|P1%Cy8Q5vPb+LZH>MvCIVr>R2jul?G)1*T$g% zy?-xbU_4!G^FUPtT)n*A09O*%U%mqLBzRBKo_dnCop%-Td4?lkSQTV$S?S1>%J1T!1&N+RxLOyGG z7;P2R6G{blO$sHg$34gZXOPhC3c{Adeqm6mLcF4FK!qgCHC85Tl_-=^D5F%AyJ!c> z-khs1)nSj_wS-KrdfpS;8}GnZazy3mL~f}wUkUq25ZV8V;02wfnH{0tUeWFYJQ;L^ z7^W$|DbrpKtbM|2O2yHqwT}{+r}JHTB0)b;Nv1G?0z8=y_ix>;X3ZLoCAs&mJG>m1 zHcX5tf#jp~tQbgSW}!%{_U%HKC!PsCKK>}Qzxx5llCU-pG?^NUfFMHvPXO&$5`h~5 zyVE@ns@=z-lM;39FIj_jRwxW_O$@ayArmCER`6 zjmmI2G~9Ik)mnr-&yj$n6M6j62gAE>zUp*d3>6=NsQt;?JHi_;J{4}g{&FpcydYe0 z(Ycyn=Z4ESoulWT9~Nq#mXRYzYPIZGt)d;Tm9t~QjOo*z_??8WFFvy+YCSUe) zm~{0!Vft-<3ezuEUQq2nNhB*khWz= z7&WAEhA(VKi8EAWPpr$d^}>}`Tx#8iNwW7|g|c;20#ODX<+oFm6j6GB22>i+BGpDU zw_32_0?#xqpi1B)PIM51wY8`g~G`p5cysiqCnH6eTJLw749@SkPe|0Mk5Z=Z!vKYk-D zSusD|^Yu2n;lJ{qZ427cEvuB6(T&uQX#fq@;!V9$_ z^|@h|b{)b-4>2ZsVChLGh0{+zJuF%H^G#kAO+w>@FO0?qT|6<4xSJ2#%;J-FzR#O+&UxxE!K z`373GZy$O;w<8?=*T07DN||}EhTE!_T%LHNoTq00xL0G$Rny~|w1#or9XU4hJ=t8A3-`Ak+e(kZHvc&82un-e3+;iQz+G4101WT zR=hf!>8)LRnzsdl?jevaTed7LUcA`!h?dA`UW9%o&z5o+Gj2&XRsJPz#+eKSFUw~g z5m{)vh@4_xTexsxxc=I!oz9Ge0DR^-XP@my^9mQz(%$3UDREbPl^r!C?G&fQ=<}B6 zo_ns&b=2k`1ESrk5O-3oTIl!T?b?OIg#?1=h!;WjbRw@^@)1l@yJT!=t}x=}nm31u zjbjYLjF9t{#(g1yo`T}Ag~^R2&+}oeRbL_*7ghttihmF;x5di8^-F6Tjt4^603>`L zUN(e^dIF5adl@$K8@7N~t|E#Nqnx-l9c5{~5)`gfA^pS+B{K&~HRo35c*+wS2|{beZBY~HS$gqap1$4Rs}w z4zuGz>|JqO-75x;sY-SDAmAaREm`e)3rszQ?z06N_T!^(mgu|Sa`Y8?!$xkdM1Oi6 zZVG8UTtmhss!USC>iP5L+m^Kb8H}DS^1(!P2{%oe7?4S}C38a=RpM`j3JNT_?H={K zLy_gw6}G?Y69Ca_zQa+Md{i!+NNBO7EPmKjf3$EexXKQtQ_Y>DJH*(Ya6Y(%0LIv` zs!SU5*u^Tjxw){YYMDcZimq_bcZT{J# zM|W?9czCCyLh}y2LW@qlLreel@$rbxy`5#65s7M`(6tM$%kI7V|G&=81Kz6QT>E?P za}FGes0fHgDYh7cQ~?nb} zTTF~C-%Y$`?(=_U&tCf+@aFqIe!s(-z1H-3=56!NOz1Xxe&{-Cf&TOyy)bk?cu+h$ zO}N0|xr$D2#y|pNu5hGGMrfv3=-FqV?Yi-u^_6o69wC2y7?K^>}7RL7ERb;DBRfarJSMqGDM%PFL zj4I%0>8nPw3v4rIHVB#i663Vq0oo9`s+n50f$ELfseapeQ@)s$XRg``^mt~32NTw# z%@Fki`~hh2XUr80q!M(D(|mfff`H(d{DtC@v8iJr<;T+iZDHyq$N^CJ8qAb2;PSh! z+WX)Akf9CWR_s1tM5yY~f0#QAj|{rY<6E$QZ?8U~`zXod-G#jB?qe2;_Ul$+O*x;4 zUxpmNF!~M`ds@AEm2FGN^gs>?j$C_6;kv*`Bb4tc%<*eEzj6@F63CRP(a8|D?Axc0 zoI1sv2i3{(_+V3-vm~w^et2}w<&ri428pB+q%^>m8?g~YCH$`7SDyD>yV~DO5Fx&s zt7B8Uxy!gVl{?-RX!9r3j;ezRpWSOT5z~HZFiwSSs%b(zF8~=o>@klN3?z}L<$uR)4rT~50)jl`ou8=HdrQMbcaOk5VsIs**1gHNly5bAeUeygtcIU z!;XsFM~N_P0}vvxm&WMeLj}M{>kPh~x(^s>SmK#)`+$0snauD5!ESBs3VDA9|@vQ5C`pyUtc?DxBKVD@c98VSnLf-Fpa35cfcJ|rlm?#o`CAh1PxD#b9 z5_0MyXTQp8M+cQs1$m1Jf+j0U#cTLHO+vy$(qz5?K|lip$(?E}C*@B3B5#O3S4wg> z?qGo2?_eE?*-y8m_7ALA!E8yud#t*AW5y1utBZB0C(kBSfJqHCM9k!NN{;{S-@jid z9wfP}aF9+I?bWMC=%vkf^*t46(yR2QXRq%5(ob9K`fBT4w{CLyV{b@3A@v`#Ufj9~ z9}g6XuY(K;d-fBV?UE zYSH|#NMwBalnFXib!ccS;I$U;+DjK4GFT2K!_`+q>ZC{v*PiQXVVGnWfCsG{J7%QW z9cCxqAxWKg&ROB24Qp+S29(?*!mY6j=grZ{(nVcScci(}V(EO}JM9#kthj|6&egBq zA==V3JghJk?5Pl=Wh$tyR;P3e%`x6}Kd5i$I&x0vI$~~oj?5qkOJQIbKM#{Z(~MUL z{EStxSoEBqWrCPs*j3}vGb}Gd(WIz4GF&)dJk^w^(Op0y;9PN@rj%x(dCDb`lQ-uV zA{GnhALmbQjZ(pU`A++hK?ubrCvNa8dx7KfiO zeysPzAFjpY$>RD(yDQK(wfj)D8!F0ag>S$8nug-saMH2!!{UY7(m8Lcw$V?~W@R1c zHhsJ{F;58dW=st8X6jF__q?00@F~a4)v1WH{JS`7%9zk>&a`p5j&e+xt0&=@dc3Zx z92aKmH>tV1w4O+@Lc6h${B}`(%~_l4iS{3|KY zBf{Hnyyoi`Kl|iknYo|RX?>sSeDz}Z-J7q6tFOG=#CQ4f<)$gaWsB=oHzIWFKSE<6 z>RO8!39=G88FPjP(SG#!Nuk%sSwhT+8KFr}g?jWIAaVRV<=7EZJv1)_CsR~-5;uXb zU%yUy^pH52c>7+)lVNN+nsHR!Fs2iDsevh%VFy?>tAJ>iE^*=*#*y4Y<(d(%0feVd zGrx*r%wSVM;<$1CQQ#hroD}OfisI$nF3sz1)n&?Y+neLj+$)5h~V1!FZys zCvrXAR4Tx)G;=}l?AbHCf)0^}$1i8LHKP>-BIy>l(igZFyuECGf%79Mwv2=nB8nTR z{+P$2rAeAZOThTz6-Pbym(@RRpg`9l&muCH9E|Y;jqB+XMhcZm;|W!--xhtPw7IO9GwA|euY-{ z5?MMtjMl9?BS*=;qzl4FjUJ^I`YWI~29F^Z)Tx@EP; z@GSrV2tO5&aNh+tvUrjef*fI~p0aK9RGgk-m`DV?Wk`XJiFHPdc}08>g*jo0Zmq_e zRf%TmZW6jPu~Tcg%xjho9hotGiti6X0`7mvAtuTL1`H7MI#@Y(u@Hg9txm$k1l=<< zUa0n*a!s0(<@R7bXU>eU^=FS6(rDepvxsX!wks78q%ESV-3X^xDYm`DGOZpGgG*WI zr5HONn1lf7WqF@w=3i*g`2_jo)fAnY)84;v4ZNDHP(8-xwiOm~4}d5qXm8a)3E^)a z>inb+!)Ncm8t%RM%CK(UsBr&jv%2%+7M-+V*(RD_w^9Y6Zu zJuT>-W*Iwy8$-(>Lq>$YgGYw?zC%Wa9S_!j{q&|Gwj<0CI=G>HvZfQ)r9qRpa}uLu zng;uqkYiaue zb?CF*=tOl{B?OfAd4lqq`bG+y=r}rB8PbZ2euGkrKL~3&cTjbuXLXA8!tQ&?z-u+uyWdv@Zk66g!@jP9kvMMH!T_) z7EBlvZu^2j62RH>WGj50gOPJ;8)sZ%`8jgbum zJz->R0%x%n%wBcJ_)vAERy9vQ{q%T+yPE0?`6QOPe@bTQ`=(flL6(&xl`AXz9Bb}Cv|x8ALSLb$*v;s zu2+8ZQd#H2&~WDIr-rv)e>J@O``?A@uen<5(BBE0HmniJ>t*D#)(HBUyc^c87Vp*} zKUxj2E(od*8y03uc$_y|tI%_1hWYyA$#3)`^dSZ&4Hnn|0tl0fk3K4#fByN#wgf5HhTnDSr9 zWU8X%V~#mSWnnV5-da)zMX%*PRDo*LK{}u@s$H>YgC+kRvBsh7u^4*(`TyocP0FGu zW+P92FO{j6-&6<%F`j}~n#kJJ+ErrSP+?kjJB3rDjcLS>t&dq7Ftt{r;Vw{YOb(!v zrQnD&Imbz;B~0yoN{+rKWZQmL#a<||+@V8UZ7<@()Fw-pJVK(Rox~Q7@7!yzcrXF? z81Bhhz5Y5XjI&k4({a3R{+M9h&?5vB8C27?UYDl*bFm55HM zfR~}u8q`35>IT+@>#x5)ysuUMXP$XF94}yi=aE|UCC+FOKf*u)qREi6S~XOv+SsvU z4W{K3nxoL-vSrIcJ@u%nudnygJ`;-KGcnsBPYNR<_H?lcMkI;Yz>cy_woUG<$$^{@ zX=llq1q>G{wi-k)Uc6Wf7?Z-$a*Uw{{!)b%XNJ^XB!%*{Zb#^wFg|;>B$6jHiG;>N zwR>=Y#=ZB4y65CteB;et`DXaQAD9E<&|jbMxMz|=upIZh>6S21srqfc-`Bu$29)8F zQfUZi6a1i@PMq^#-7r`8>~o?2!;glJ8Z`W#Se~JqkYXC5ytIBHo3bq+URh`j&e-IJ zQ5c+|#2_w1dpqhI_-Dpp2;_cWzO`-3!L8AI9&}S2NOz7k{317U!n%h>KrY61j`AGR zid{Uh2dm$T6)T06p|kd|2?< zg|r|Bysuevq11zUx>n;XGj*2XVBf@HSM?|ftRQ*1gazh8on{Vfom@{j`Q!j{BdkC( z0szoD?zm$Ots+0Fa8m(RsU`+!l(wl4y?k6CX zA>AoKddQF=9%;NA$BZ6h@tcW9QN->i=MQ8K%IEfC-VyF2_Xl#W(-cc6;R&dbtHCA9 z6-c5;pD+UAgP>HKOw8^>GXNm88rQnUkfypxkidjDPBRT2fvJt=Q?=>Sxl3f8=M(da zrqPXbACzX$pgIGdDpFOzkHskx?=ChKjg@K%ufT*<*+og@#ySG1%L~mVP>=Zat6}VC zpM}AXKdE-a)7os{(|0cidvA9;l3^6Wj52KNGfpyGNu`2%M**_9R|1tRJrUuYj(5V% zkozB0y3fPNcis!%mYBGo=73R8f^AL!62X2fr~g*e156Xy>Qq6-If2+{&6Uw=Dr-a* zj8Vb6{4Gz2j*Um0mvNlPbW`Sm^KFDbzo$V9l?IO6rY6|oW z!3PeF0!a;l1xPi@+7hBPil*c=Z@?uW02ENVgki$R9J5&asCv6*2=3I9ToZoD%QiYY z?11tFUl`h|RV=X&HmoVpHPHAMM@ZJ`$ggB^A)k~t^-A^Q9rJ~pVI$NjffqJ{t%UkJ zjoQXM9j}SeSIaZx!GvNG0A9--TP1gtz^h*As>OTJl7rOx-eOw4WLW~*wuvm~v-ZI2 z3O%q|)l+lsAo+~-RCb8tQc@2L1tJlkFyE-RqkriwUDQLQfi%4&?&C{_LlEm|b_`OS ziKB;BELz7KlN;{tHe9Q)EVJAUTsxZ1YIF_IjKt;>jw@i!oJT&!)dsi%3MK2HgX9&0 z$O0KmhCnziNK;w@N?gNYcx+(fb;1qf^8bKXh;}U*FTwii)bW)8zHre5fj*^kpNK6&iSOl{fj(6@L zXu|h83%9_5m1}+@4->}4oZk=^OVpC2(dv*}_m&$49g305hAZ2K?bqU!B0y0M4I^V* z;C zss$@Zm^6g48q-+vGxAyy;%gF~j6-MaN-1-yY0V>alj6Uj_6t=D17 zz$~Q5yfLB86C#nxaxEdCh{*$v`X`6&GKKi`b1lzFec7sSQHRzyXJt zgHmec^hlGHcWIK7W~OYO7~-IX2=I2n^(^+y-|@m`I>n)t<&fj$y_l_!P9TS7qNyt^ z0oNb^c;88T?vrXK;-c_tHx)2{&AKO}O@lSBo;9qAKk# zD%sZ%8&n4eKG91% ze+5NqSO$#X$C~+YnH|eetf~YxF}*zA0`&{)T%x5+4IJ4i9j67JfRV{X9pYLGAz+Bi z%9;))eSFz^_ddw2>m#KMdAx{Oxtb6G-tz1X>myLro40-wpGBgs>6mrxk@G4j-kg=_&(O~EdazU&!yCN<{wDXy38OeYKJm8}D$Z;D;7kEFFfz4NNT z`DJ+ZS3eJ%Z@sR>Aggg`E>FjV14*hk)nYyt!m(TYk#5 z!}>IE{7K4HCBshujjV%-m^mCZ0j1;z%0L_QmY%@cn#rOy z7*BlyHc2%^?ufsAh*r*@R`D zh;Q*-!_acRwtS0R6gQ@B7$*M158ZF`sO`OCjpFu?H55;CW!M#>+RqV;^1c9wQGO+q z1EkqI6InC(2-RNUqj!EQsD5FnZV^=L#8Kc35vo{C%TT?%1XTfL+BCVUn1*fx)h47F zH*TCc79F}&$}L0TmDw^*^Wc@V2n=qk#hGE|KEfYSN%=WPe2dlMDd0CY&-)TvXgQ?9a? zeKY}}OH*}tE=u|^E$s5UvRVnGkVm8kp5#emkb3AJssdSss2?_bxF=)=+1NcM3oU3Q z^8?6IdGrd-LY}MD%h@{rZkC*$X3v@t!}?w1WnngNXX>rK=#BsLw;3Tvgd!huxUH^m zh$s#f_{ys}%HMBl=E`q$*svictH2CBTbpDb_c;MpoHF25p_xaBqU!Gx&#yE@O-Hks zQKvGlfo;=t-t#Aad_x%hKjBT?jCS9hH~CC*ZwoT7hp=L12B%y+4oMxM{=@pm&Xg%q zY7n|3C1FHup@L?Blv7VV)m>gW1g2glBn@F|Cr7jS21Y7G18Ol-J=V}=p#;&kjj^y$ zt^s9#?=-cgD+Cm@^ z5izmIGJTGX1uOa4lAi>4Qx2EjNj;ZWZ7Z)b@r^iH9_7$-LOBX5Iz-eMLfJMt^8i*f z_0jy!r8R+!WH#7-(~zWI2-cgI`M!RzWQ%jbFCKq5yz|07PQh`a1B2LY-yfWiyj*?usL(56oq_c9wVGRN9APr|9sTT-- zhI$9d$F(fXv0>YGUBzN&D!hh{ro$N!3-(s3&A@f+cEl>Q2Fx}9NR&*$Ayk*Xcgl>C zLPtg%HX>Z0lGtn#J&~^m@ zC&m!91Cd$T1)}y967}FKCjLG2hvLAzOQW@yjHdLePCC~T2hbz{Y(0j2vdt8*vNbx5 zn%%kb38%KSMvRgLD)`}AhPrsuMRJ!qNDhj)mM4rxFRsiJw`nrLfDCf9_*-K2Cg8xJ zmJk7I07Zx8G8roCoaxZyg?R8U6{c*TFY~3ANkZ$%HF>~5MJbsnVv5R-ri6HdHkEXy zE*1Ufx@;qWLNHjwfetY)#-`K&+jf8oFKZHFk;9?PXq*v98r~gq7Q&6G9Pp|U_3bqY(hk_ zli>t7P+t8-R=SIXydc9ukA3kWkc?F=NKG;p?s?}(0YdeMl93sdwgRT0J1GXx4JZ=tas^=~ml77X9B~ z3em*Oj$hA+!-j98G0_yVA31WQ{b$Ilo{CiCaEmCy;x2QNx#-@~8FD4_SDVHi!O);e zCpRbth0y_i2!(8hWk}Ioi3@P;&Y?y^+{$1mKmpfWuu`tlU&Y(RtAlROee@>}IB(|* zC`n*cMR>N8d&;F3tqbAne>mk8mtG_(R+nLyGq%h@l@culq4D??-Wqz&t8CpTsoS8Z z_4-2P8^_JEH?E28S8WIxvT7ggWNN0o5@3_B?8p(ryx9sL**UsqVYarZ%$lx0J(*^M zw15p*EeEt91d!@vD+k?-?KlZ%-PRFQEw|J*aeMETnz3?gtcu93W!1Oo=v1gk@bJ*@-`k?Hx>S6&ML z5P3a((l|?kjJmOrhx(DkzY2u-hAdb-R9klQYzyv4>~bWBECfinc)TR3DiV@8JMH*T=B95VG@$%<%HFkLhaRBf{tr!*%fPe}oOI&-W$UYga4_Pd~CbEICt$hl%$> zY@ue~mSlj`2C*%Vu0=~A%$cy)eE-VulOI1|83Os#)Xtc2D2EW}lMC{MKvV`8gDkQ2 zDzo(x;wa0ykTK<)tiT&*8G8NIX8i*4puwi8m85r7otcv7*lq)nKwtnlRQ79j8sdkjKbDyN1=E&PFBVJLE;n{o=-rH+#Xg zeWZcM*>-))s5%lqZZY*(Q?5+`9>#24al4AnHxfHW1Tf}}=tC9biw1!AKH(yfY9J^4DnCnTsDM+9Op0nSgJVuk>y)A5Y$S1wY&z2tqI#r@@U2^StqX{ zkWTtUije%-E&zh8NUfn7HB^IzC!(=91wHbiU17zL5QcH50(OK=>nP?sA+NWU2<_-6(qGfKwZDDa5; zV?H6z6vrq9Pe8>M$DNStv>t9??VKVLB@0JCAwlq;nw!6qg!-I(g#J^+?~fG7D3#*^ zb)|Lr&T^-QS(Q%VmXL?b97#bo%^{q&`C$p~rsIOT^pjAnld9@DuBx_2|KYa0K~m`G z#lg6p-O$tf6ft zH<6h#^44V87PX29MOanEijg2;dbDE%M?A8HT+z0v7|UGAm5TNzdJA@@iSc7+q;wx? za3Muhp@sGDA047;v|;Vp)`r%R1I8`rGrAn=0*(hv8_a4fO!SZmi_?2hCzxvcal4v~ z-wA9`H3pJFjKWhIPGhDeBSOv6&*z)xa=E!>5LB!={Gr!?Y=5`1H`dcRxFRFjC7Is$5z0@o9G;5rvO^5FFP@ zjo6OFfuLY0VPqpCpQl7Dmi7|Mk*9?yT?rR);KKo05sUdmk~Km&vqLjIoOI$z;i#jI za(R@Sbc1m^)nJH(HLADXr2>Lvl_(><7=p%6Aap|DVmsd2U z1zcQ#+{7S8Y-RW{VX%?j* zX`98QJmU{3%Ow4bDi(+qe=QSUk%E60{bBq&9i= zB9&mRP~$|giiZ?7mR!A5u={CUf}XUpJc%s7O!u({<^UBk%#07A&&>m@Y7B^)yi1H z2s~{A46Jy7=C~V8XO=T`)~(V+!AofA(xvt|q*+j<)U@&ACpeiKpwgrHVc)Qk+?8>p z*W|REA2oz19iJq8IJ^ue3>X*oe)7@!O|a`mT)@^@}zO6<`WbzTY(MoHS)h?WG*)P*%s-x(ZQVa_%`{$$967`wH%~`GESx*rwg-qf&R7gPq=Cpb+AdkLG{U7!dGoz@d6y`4ynscVnr}-$W~g@)31Ay7x-vs;mf)et2z`OU=&VQ* zL+aOf5L&iuF<;~QPsY~N!bxI8<-$xaD7IKf1$u0+;*A>mVRd!&-fPLLT64X>hV4u8 zO2d~C2M@8Xo=vvW%m&Q0w{?de7DgPuK8!#8k}&?XizQi{wkfn4r(Y9JyijMsjImn; zi_~DBSvp2%OAMd7FpU5HYhl6{cSx6OTL?uDt9bADmI75S2UCqE|hE z!c@I#@Mh$z(DQk3(+Vpjy z`5x2PhTW&H5BtwrWs{+R?+t>mPVT|kYtP-nVGGU-ZFRR(vCa2GsBU{*2)otI39Vby zIHp|*m}a&{!7^y?SH z3CABJ^F|M$d#u)wdt2ZIK{OdVVQ;wvaux{Au3fuunqpKvFb5&Hm`X8>m2`*lI&}B~ zfyDT!(!X}vs{cVEDvn$r8R?TGvN{8WBjhEMeJ;whSHusLN!|8!2Et4PHl}t5)Qk>K zE{l5UGYYeT0QYeR>b>qFPMtIa5OY2DhLg#5=q43xa^!s~ww z$LQjMBW`{(9C6EAVewt>ib^dCt#@qcPTX_P4sn{~7)IBp2^|b@2gxQhWKf-_AW}nD z4Tz^=`Pwpu$k*dEx-!R?@ik>H?!Nn=9_kEG$)MB;o0&S)e0vqW=5kGR+)+M2ln8L) zvra!b%$+sE^bd^CA-MT_&0LvB@sp}q{M-X|uJ1wJ;p-~sThU-sp-bE3p?r{LXe1~- z<-}vd^G`n(jyrmheR&vHrZyG*-YF-9U+PYx`eo<%-0##es8XP&EGcB2mnW^J&*lw@ zP;BCjJGOkZb3#h3EQG5m(C|@bq-SUGL=l3gAXr9BO}>zCr7Hb_q$w89h_3V|6I-0C za;B+ZXebzZ>7_8>#H&K*nIb~_%~>CI*>BFeu+N+gq1S>7bPZW|Evti|IKd&UtQx%Y z>aW7HkK7fWdhk~L-4>pI^q#P2*5M{W)Ds4e!GfvnoftVz$#AGmf?b(On_*qledpfd|J6=s6Dqk&683=+s7IB}e<*cK>XVXi$2RV3bV4 zz?Z!NpobANdPEA>Q0$KJqVe`2?aoU@luctQns-pJb^`Fyv%jZ%PJZbpN|i^o8FYx_ zxZZx{`LJ=#N(N4neVjrGDGZyd>k%?Xp>60o21=oM^X5~iba@s!4sReSafLWFxhmC@ z?$`F4TQ>?Pxx7&Sbh(^-isMO^r@P8ox2JYY?%%!o>#%vt=5WK0eiVLm%Prxin{W2> zmRoNN*IjpQIHXT6&k5R3eoSCieg5#quXPjW>)~TvQS_(Z|0aB@+d3{%%b7Egn(h~t zLsE0-Pr6lZ-%v|)N9eqfH-7zGc=@@lT6X3TIkpL4LWH;+s5AfdU*2ytX4$=4k^d)< z%+?8;GbfKSSwU)n-%@Il0gMRW?o5mQtAU#wt*14NIskp;`KQ8Fm#jC?ys~7z1Zq;f zRuO2%H~7npNuxq%c#wL-hqfp`Kniu@>2a>11Wv6u|Gcxpm!H0GWWZL9nHFH=h96wv zFH3|fzHq}pBKwISkxO~peEl`Qcneh#XeJvzRZW^S>7%z_r>~JL03Vg)Z7<7!fYFza zuxWc+gpDF><;`kx&6NvlmaAjsQX?0hb+B83-eVlfR3rCii9Mo~gz6zXr%+ z856B`)x|#73lm@e{gZI~;v+rt=t^Tk^eefjr0%7^QrM01z&2~vY-}Vc!bEq~!D_Nw zS#WICM0I$$s%6WTi}a!bGRiLxWF$oXEM_5XyP3M>EvoM#JY1z7RCH%+P&rhSM*LlQ zpX&0mIND!)DCYzXe-&@SKRyYkpL~KF=QLHM!IJvHTQ4h(;{Nxi?}et}tG|ZtOWA1K zwww%!wm?)(pBG15>1-z9rDt zpQmiyG@m#_BrAtb(2 zGamTQ>rM#b9AgG7IVo(Cu1+;<)eVs{MbtDH?TV4^E6J8cK90ud&;k2VL;-2h8%Jx= zg2_VNX(Ln-E>xLcW8oB9BJ%B@9el3w`H_6&E;kPJ?K_FnECNwTh7#zWa-z zf(n?OK^P;fGN&X6rSnhu*@l-!m@fdVO`A41MXDlYZY6K{Vpy0k@kX0wFR&d>eDzOc zkYOxl)5$nB#;O&0UCM@vma{8)cPP0>-9=Qr^2# zFguf0V_0=$V1Nh(Qr_UY{^8{ppYz>(2S`t5Fglc4%z&tCef`^2mtP!~o^wV?Gj1>U z${FFK4?hUc{qkwUjlAa0o)zxAClx{I&Ke!<%BopPf6 zY>9E02<#oV-=h1E@6nm}>zsnVao@J1$B>yTX$+ui-#(rt07JLV^{w_{&s}#3d-$() ze74uo=W6TjyGKu6jv)i+76O#7OR!F?z2aE-_V@@gV`aP`{?uHZ@p_p*nH*6aIvP??-WXszmGe`Tt!)5zMW-y4S8cnm2eO_Pj^<|t09vfAB2D2jw}#gtBI-@d(%e*6R09Sv*}q}Rc5 ze053!q0jL?0BQy2nX5DC4<9?ML7jcZY1$R| zdid*K{$w4FsX?VEACECMIpcm!$Kops2$MN34PHkvQ5uPx-pMl09KZM|@8tw+G#nt4 zu8r(YfZg5Mj#A=e;%w1KK`DKhE~dKYwj0BiJ8#wn+gFG4&pACzKKhLCoskQ|ZU;{c z?fXs)UB)cZyYGdQk2^9f(oOQ5?tkVf$5{@gG{Y(H0af`~r{`$~w!sK2DQ2ewA*$j? zB>4vtRY8Et30aHz?A$UMMIKtmzg>$~)p1Qh$l8JBPDiFxr^uB_TaE%s^hzPOztLA? zzszQdU(UxR$K4vdb7p>LCv{$>=t)0ehV!1ei$Kh^cwCsrA~E`vZTO~77N~bd1ZP$w z$q)u(0E$hJ`|jP@vlbl)YYTb2{nqOS)Zf1NEUaI9K{#UJyzrb(V-!URA-`0o+2ONl z`9n9>?p{&lmQ>ZkipVD&Sy_FE0|XpyPSyDyMHGRnNN9IpMu2B(E!pvotbi9DqUlqT52CK$j5XYnIkpvE?>p3kuRqMZ;=#GenqS1ns zov~6NuIA-!qI&J)8fJBMRVR_mpRk6RA<&h|QK{wS!u+)ass_2*}h$m<&TG69|(*=mJQK=RNvg{;lhT7?Bo zVdTAcUkQ&raAz2M)1Sf~*x>ip-Nv zRpZ`GC;^fkzT9DlmPcN|=vN6ZQ`DKC7{KlVrLIn?p{A``?Qk+ti~PqT#wOl6zr3j| zsYp--UNjxwhWiOKyDuk2l>pX3>lf!}2EE@oHQHEArBLB*D3LPE-Wdqnq;aV^1|Zgk ze9FK4-s#*cmJ}kAqP;zhA4vMP4#eG8&M8SdV)PJ_87~-El9SN489QhZ5?%Tp*As}z z8|z-k;I-t}MutsE0T#?bAkqm;2;BYh7f*-fM&j51{gvdS8KI4Qu{x?55&6_Hb&{X@ zk_Z)|G%-EL@|wa%VLjC=633w`LcH>}Da~+qR4s!|Jvir?i_1g!JiI4^%A-Qv=o>!@ z-%6-!1?ooK__65KePQFubHj1-4-eN~zP15Ps;nhLkZRm$cw|G0bW*zj?vpob2l1K8}-%cNuN+yX*p?LS*cZb}SS6mW`=&3c8or0*v>E2+j-sszM&z)8xnG1|& z!|CK{sL5T@=!I~kZWdQ~Malk2<=jIlvoZ_-M)PLPCmU`CYjyKx%_fi;C8shy=7pF= zNj@M?cUnSlxnpyL+^Mc%j%0>PuG|<$$%t1Lr8F{1L8|SgcZ>|H-=Q$#@}y1(^^}v| z(}}oq-*M|L;jTMx5BJ`Er;hBOA1+vazHE?BT1b9)%U$87Yp&AHf(f#|zhxS9p}zm- zmrsey?izk_-(BI(o36E*{`!m0hKts&3Y)b3?4bwl3tOLfOn2!VU0S_WxfNyaDZFuw z{R8)Jj&fSzvrj+qEn8eQ?)JMU+@>s49qZ0Y9jBjSWfI?oXjhxVqS@+4;<*0OkS(v^ zd)uS}LkcI38yjAG@tN@EOV5UvfB9s1cI$tH`?mfnOgLd>*uC%guv?$;VaAyo!u?Oa z6rS7qXn5+;2f_e8(DYdWg6srM^e?kKhCO(anQj>ZSXC3ulC zBBLBK$e2iy_HQ*H&1DPXxhJM%M!z9U0jc;#ooK@5E^aV$GWb}e{FjNFrADW=q!hG# zo8q&c$&oHAOg06gi^hvJVwXZU<0(^%ENctG*%I1V2wNu4C9cSW*XT7Ku6T>N*SQ8MrenF+Ja_YvAnF_s6vZ42w&)PVvA!Jg*LHm6J+EN}G#*-sFQm_ZmYX9U zn!UP7>FF$+*=}t^2mO6#pN@Km6G2?2LIAu=7}p`Fm=b}LyEKpJ{E?@$k@8t>BT4deq(#dn;4h|5g3LRnZT zyrEo_YvA&lB8SQ2C;aG!>%s@`y=#q?%v1HY*HWi!FbQ4bZ6>f`=N@;+Evh18q;P7E zj#^KkDlu}<%~!uI@SV?oLvy#+M}B9RyLTHw$c_XNFYS#NQ=gUKrAEf%8Or`$K9hS# z{qZz5U0b)_c>Ttbw~rJj%(8GNWW(yrwx7^F0{r#CK4DI`H(s5k|5A1vF&(S`?G=@#mmMctCj^9HR+#n%eYKrVP{i>=m(2tCpG#?ef|eS4T)&9 zp)3Q9Lu=_AXYQgKwKV(cDtd^r!77Ckl`b$MWYuT%wLU$q8UMLT_L6HojMT*~cc`-pwqs$eLiy{8 za>!1t{`$Yi%W_`tw2b{aLIpx}D#Y#r-V|wWDPNAgEX7ani0^pnpibdpeXO@9saIzekTN8%Yw61$ELPT+2~cHpG|Oa(-QLnTze%(+$4H@Z&ClKNPg3F#>JnQ!_dc{!{YBqUoh+FUB| zZaoR#t9SR7;**Z_r2WSCq@l!no1?CfqjN|(>B+}(?xo*4`Kj%_EEnA?AHK{o0&D?aHBw xclY~imGh6~kb`SM>UJ^IA}i4)Fp!kO-@mKYcS#J`D69QxI8s$tSMO;g{trUUkjDT3 literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off_hover.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off_hover.tga new file mode 100644 index 0000000000000000000000000000000000000000..e00d86a480a59f75844fe2f200e95b573794db01 GIT binary patch literal 128400 zcmafc1$Y(L+I0kXhXkUyyAxc4ySuvtE}g zGv_4G`~7*Ili4$~XU~?k*DG5lARtYE`*$PYMnGh$S(PeP3P@eCV#R<86)FT&u3R~F zjT$v7)u~gbUH$s?M>L9!T@V`^yS#C1>@psgc@*$8ZXCNTK%qEYOXl9xk-w$9xWpm` zDv&80KlBH3BW!Y-xTbik3(Isi(DlJR3tlH94ORFv6Z&}Kv z)t07QQgw-k|CYu3Lcu9`O=s@W?g#1$e@k_?B(;0bj!Ua9VOf`^9Z+IPy7^T`KA4?Ag3|)8LhxH*X%CQ6UAkuG}!VXTRPv!(Xeu zG}V&Ii6lj{<@26^{Y|y5xzB^xpL3&drw5HC+k`2|-v`9)yO5AP;Zk&K+v$C>#+HZt3O@ z&5edtY9aRGXas)O8TntUjq=qipkkE@C|j{C3YRE?h>VU58TcCHRHYi`Fq*bD-#sy{wbDBFe)N-3A zPaeyCcz75*5#iyOt^!*f1gms9OIkDTRjZG*ZY}5-78Zu$#fo9a@)a0$C>{a7cR`+I zjZmgmd6cPG2E|Gh!))c2<%z~Tg|ZYbQ5Z!_6-B<7Vn}~57Qx?lLF>V-P^VHQ<~zGV z+Rb|?YdX}I@7zwl`A%h9H65qS2D`a+k5(4DWg%-&Yjq1H69}RRhDaWn_&cdnr*2|! znJ&x(r%RWvFU$3%6U7C9UKF4gBq$V^7}&2j`t|PNbnuW|Xx^*|&Yd}d zwX0U3dQ4R$#7%|O|J2FYv2_FT<&8#2ww!3tsWGB34*5sbMB{Qb(XvTXG;iDlO&T^t z{n~Xmy~D9^ z>~PeMsRZ>wb+sJ)sZ$Bxs&#?h&|-)QvkJ=_9gV!qZQi_jonxYNRjg`9cu{S{DG;QP zdnI0hG`gZbQ@KI~{Q2$YAh{vqy1HmkDh7?~H9%~G253;HE=wDO8Oppzp&++lI(mGU z6BNp!2r*Tvp?;k@Xi&E7 zvRkWRT!1OR*1U$K0F};_lv zNCl`?EC~y}1lkx^zL? zwr$a<+qf(4K&f4+PuSRg+N z6)Ff_D9mF4o~z@DIn;v_RC9r1({T1_!$&INu4?&;c=F{#gkS`U_o#{H^_!qWhYpr+ z<#eU;oK+!}q<#DLXjZ);!WJ|_#Am(Hv{nqoOBTN%@d{uyxp+`-P%SDK*4)gAS}$IW z5D=k8SIFTDg>*CV(OTW0?cT9Q43dx`>0V%yXN^~r+rN|)y=?MGUq4WxUrBD3t^~U2 z*}Jn!60Tmc1mAxB74F@+iTJ6nf;y_w8*M zkIK%%^{a@KUw1{ldUepYbsMXwHL9`v-MV$N%4}MzA+jB9i3)f7A%0*_RI60xrDm4i zk_*|G3ssqjL4=Txoxec-{16$a=M*bi1S+}i3EBDb<+a9EF?HRln^mob*EJzu*NPS? zY}KG9ae4!9q|lve6)NI`uOA{S2BTcJI%w0RrGay;@}ETjZdtDh@=kArJYV!iB>+jgak)mZ*5QKc)}vjhIShkttJV>);XvszuRG)k@{DXx2208q(i7jObsTTxe+5 zx&z255<`~v4U&L--z@AmDs|yq5NiEcnXw3a(FaZH*I?^2->fNVjoGP0 zNQ)F|vu9^HRF)i6hDcgMYvR^dtt(G%qgrEI=ML0m1EpFkx!Y{f(T?Jvrcn&Pnh~g$ zWNRHT9C(C?V9@|y`H4!VCoK7N3Mo;t&v(r9feaZkj3I2=^4Esp(X9Mq6hOZ!j+;Sy zPjyBH#{LEJnH6e&i$&?k zF9Co5fWQCx8572iQg0-ax~$@W<-=FNGFy3{sZv-d!U0P&02pwR`CiB9 zy!sbmIcT<`=FXHU)08MLSlpy_l;zdGZ!c`wu$s-5$+SBu8pDSU!o~A%;vtofF>I0( zZyd(j)hlrL;9hLsvH|19jzP|}Srf5~0Mpi|uNg`LgcpyL%mh`kg{J#L&Rw;G(NS?n zMtRZn_5c`~s+3DaJr2(cO)KZeVbh8^*t}vMDwZRnSrj2!^m6X_LEO7~8W)c5r9ssY zxugVABdA!uJU)4N8#gZ=Cj}kA(0)Bkrb!Xib63wD$D=zJap%fOv~S(aG$DaW)vM=Y zDptlv-#(#^G8Bo)XO{5f^a@}9uxr_pBC9W&HS!}XH_gV$V+Qay7}H-LjU}@^*tBX9 zwyar#0eyPnI%R!+mPn+j9Jq~UdS|f88x<){EA%0`prrY)f(VE(s=U{YNfgDvV@fK) zHda6g(m%ptNEE@~U`rA823?UjnyV;5G!o|ub$YK+AUjufQt}wwdFzTXN<=rb7bL__BYndlbojtt3ak0Zo;nl4`%^plx*N5V`bnVT5d?x%bwY}C zy||7YJHjJ8#48l1P%?#dQQb_q(CEM}#bmLnrqg6rP3H*w|kVbrZr)iI9Q`jx1`eE7}{+`fDo*U!Cy zj;))T(HtH|^zgY0r;gx*cdp}|8)wnD0X=oOLYS@}J=H5#!AIXcC3=P>LC;K~$EqOE ztpbmV7@#s*kMZ{ti<{+TR5fo@+k~4+7fP(hjUU1iPQ#W}b8%$nT3jLHUVHN}2KDQW z^Jh={QKgnu^9Be3uM!Bg=dY6|PhMb-;UPFUCtRH;IFyz|yY?BBf^+c&I0n`RA>LuxGnDatx=WDiaq+lT$THqsSR-73XoGj~Lbv0d5X^q0wL+zQ&iNP1~?|x|6xGu6} zbh?&-Z`@!kn?0H2JR66$ug1mWyK(i*Aq*cp02j}lF_IRg`8^+gkcgHHB!P6o*C9au zPD)UO%bz5>ia|tWK3X1MiM0%i#)pO`Rw(^@vGawsKx$+Cj0<(Em{2xu%t$n6= z#VA~=6v{AMuVz)VJLC|MAWHDOj?xt?qHLuKs8qg;k*Sn4IRRv570q7={l*VMs-JtJ zbl2Kw+q9Jd$Z(V1tt1sn@Din~Vn&V}i4!MISZ5UWT!vSL`cP+rv~~SvC@{M*(!JlF zWh{VfS)9QG`J+U6>lP(o@1~_Vb#M!Aoj;0umrr5Dkb%@<&RDr+s)}q3COjs_mMQWd zlbX^RaDu26or!vd#3&rc5SgiJQe*g8*h`$8_>9%?oElvQOC)Eq;NaZk(C>9eF;$VB z+PB5yckl6c7fTn;!Pbpy(KxmN8z7rCraHDN)EVo@f!QL1+|NGy%y{yTKmNc6AAEp)`}Set#EHgl9REV&#*Hy(&>*Z@ zwF+;&^%j2o@ke;{M6&7AryK9NJzuFOrMi&Q?T~gyePm9a-sEbXmbpra27=}T^htg3^XEZH&Nv;y~DXm&M z7k!2f!C)GUZJIZ7>FZf|#Htj#o`wx16)am)S6p;iY{rR{f<8NtmSY#H{r@!v4U_~CTJ6zDJ|0Ln%^h8JA6Ho3SUK(F zjg`DnV#(TPkX|cVOr*Ni`w#Rcd}Z7di=1g3hl6@X1iP-NEk6g)qM6+pQ^sKX z#+BHzZYfF?FUtDQN{VwvVJE*f47<0k#g2_DP?rXM#*CRv1m|Uu7fgR0yLfN+mNn?m zstGb?%4F0h9C;>=!a<7J{W~{u2&O)Dw=mPDG+JOfcxV_R$`(Mtcb!nCo1fmyZDQp} zu1=$p2|xmu2!HC-sZQ5Q@#&|ZLb^q(R;?_Cpr|JVO@o&?x?Fe#-D{5QbZ+JFI=8|J zuYr9#&_@zN7-S)9XG2!PE>-H(m_K(Go_+E$iWDwrE$0$WM52~8F-Z_bfy2bT3@s`7 zS5+-8Dzl>yVds&8^tJ$wTud^AIs=7_rUdA3+p~~J3kY;+(h!~u(qkk!`MpQ)5=e!RpERJ> zR#RE~CR0eHqNWsqq)wB%nE@$~N?8d}lEn*l<0%e%*7-pC9=z?(r=8p0By!};al)XK zoEpkaJ&;7K8fN&6x$B)*YY2^(nI55Jkr_w~rE1k<(7tW^q)@W1sajF3sz!VE>eZ_aU@zCE`6V*=(bN{1_KKN=Cdy;_hQuyo26xAz8RN};sj>?P0)%SMBS@L2 zSa%F30V<|l50D2rPEiA7M%lFtQtK@hUe-~mC=v0H)Hn?{hvy1Kc8)WL`Nx z7pXV`i42*#93&6V}g~5HhVeIgM zm^xuJ<|It!Zz@Ns+T+TlbB?%q1w)COS0$q`>*`>LWK@~u{oD8^NF`SjQ)jvwMEqEz z3jwCJ5f3($|CkzE3RAX{QSHi1;`vf{T*>Fa(Y@ln+D0G=9S3WYj{gfjrud{t+$r4} zl{&w271 zPL`ie1qF1Jqtxyw5T{Upd=3e^ACR9O4L*_&X%))Pk(#{3i?EVIqal2grW%A4i!|9) zu7{s>tfgOJ9Th`#E1Tq}pMFAu3Yp^i_3Pj~DpS-|BK0Phbu1n8OT5ZD4q}Ab1qtJ^ zd*c$E*uNQXoj*)($`yS4?hT9_IvAHPCPj>iD?bzj6)8WC+@e|6TUXq6_8r-l0*na9 z+TNc^AY1=WLae%D7;@@V3n9QF_}%R!7Jph!*hZ+0ZBqPyq2lj(LV@~~h+Ddm5HiE6 z@y|d1#Q5>!t>?Mb=xPC0jmdm)p(2!NZzF`z^z;ZTR17m<%#fZ~HfOSFaq~3-7f^!# zW+{}W6orl;AVWix?le7zMvKwML$xI_RTwmrG`)*$=_i~OX=<^PXDPf!}#?oBq6)Eb^IHQ45%E>veKQ$^~~T zfG$a=?I^HzsrCK(FQIO2ZdV*x<#u+5K_gWidmW;n&T>u+>@bYe$i^-Kda)DIJ+`^4 zu~=e6%l`#{r1hy5b?Z|#H+Jk;sO6^%1Ic9X>gp@ZYl)wJCOzmupAKYVXc|8PSxU~SJmn9En7B6&9W7c>tt(W z-QNVcux`a%FCpOPXcqq9WuVpyCM7{(I>hIoR&$de-k5oPi_ zz(^z_UIK=)r$R`Fl3MZf=~J%|+`W7EKZ814nOBh-HmpOfyrEgoGH(QiTztJOH(Ag7 zwywn6*G}VodeJ}q;6A?o*T?wwi)S2e+JxITZVTn3qVQ5b7E^qGDW>k$T7=0*|KHJtoqd_ljtCpNOA*E zi{_|aMgVGqEc+WHgu{0p^{GZ#lZFBVS0>AzCn|VxyE)^niM{rS8zkXdb<2p4^ixi z8lr<&5v4dx|Fo1#8(}jfaU_1DD?uD-W9aifuNGy~8s)^>ZG(d8GL8u)C`Cm4t~p}V zUo+T%elkuS$;u(OnKYLFR1!+kum8A^v@03%P@-0>P#)bncSM(tG!hS8jwBe^q&XRXbNfG+;A$@LGXa;d1*<2db@=IM8^?dB-C`Rk%jj?Xk65QiJ)H@t9 zm>xI9h7dFp^8!aTHm+N3`nhbm2p3RnL4VT+2{Clu+@=4xp3OcEN|7RYaT53m-7z7T z+-+vxkqs&FAeKIgH@JN z(Z1B(44Pmx370{0s3vi|1NeP!V)pbY92Hz| z|B%KD#VF6N+UUj?__SjaOK>M8#lZp`}Nmf zzmvQCcq^3^0Mw1&X`~$#cP($ z#jY)DaQXa6OdS6j25>y;;r%<zdQ00b(ehV@AL zr6#OSYc!2ut3e2ql&6nNCc1GR*&br_XBP(Er1YE;aNK-K$pPNgV6GoAfccVFz}{_$ zO|4fNbMgU8lt)JSo4>!5h^{F|1~I>Wo>})?#+3>(b<#NE;%7X4?-t&=aK!AxHB08u zkHQJNRO#~P;xde0Wr?}=Nib()$s|})JZo!vJgvais#ObA zD^->gB%33{?gljF+-lWt~!qssk%0|NZyhc=qfWjvP6HxVSj;6w79iWhUuAV88$@UAh!ku3Uj&slOk7_yPU; z^)o_OnyQxW-8E?4na^=OK>5mujIWDi@3eF@N4oy1RxHPX&gppn(L0!xFa=jHoyE~Z zd$FJM&M$G~Y{Oc***C4@qN4ORqFj(5bb%-=xMX4|$)F}pd{yV7B_A}x!~f6|?zO~m zO|}`Tf*e#C_g#`P??+F7ZW&hXg#k*y9t^gm_&P;UI6(nlx3F{rbxB!rGOKy1aZ@MZ z+2h+dPQ&!*&UH9N-^6SWeRq}6I?4;5R z9Xiy+s;>J0XM>?><$V<3s+KH^tOQ)fJ&g#s%oKa_3Wd-slo3l8Ex@*|TMcll3}%{| z=n<+?I6Nj;IbyMFch30s4!8OhcC*SwYo|}2#?GBP%?cGA%ekXT5Tay>cL{&xT56XD zrG+nLapugKHXtqcsL0UDo6C==T85~o>Gcr&P76a+E>62Wes~w&Jb91{yg4&$D!XJnRcdo?CPh_vq87HcwzdpP+``tL*6S0WpSy5JLe+E&P~q@!?)el(r8xS>4BV)L5B@I;KvZ#F=t$bA;j~&T-b3FF6) z9>o27H!*B*f84rp6`m{f2BtoC#Jglh#LE{R_o5{fctienr{6zoWwBBM8Zw(K?g#tULrw5C>q36f26_HESZaaU*(R z8=*>-DyUSc5-L=vXl9=&vmM)U{tD*>=thoq?b?!dNJp)jqfYIbD90%uT=z<$&=nm! zv_;G2O;D{`HKtGjE!pwA^LqQXtq|L&Atyyw;u|W13#C!Jb}iH>TiJLj!|sNN%9h8e z@?hFQShZpqwi9bAqd6fxvJlM&6;QHxaYt09kvB>sXab(pdU=E8iON+h+#C+YJ61#8 zn3|}?e8wyHB?TwxJgw>Us9U!V%9bt5naoX{5^)VeeXemSU%tH6gOJ#veOt6(iDFnH z#pN1ePJ-`jGoYI`jm};cISTtCQVdc(Y-`GU?vPMasZL1cG> zU9?FoCbAv*j4_`h+gwEQI8$&6be~F$H$Gy3R(r^S<`LL3sO~lIqx{NG5Vi$~+{E85 z{ze}{&dlk|+zQVUf?Pey+6a85$Q?|vYUtg} z)1VlNL>Hu0;4MRrk|mf|in-1-nOnDLikda5Gp|KV-SLv!72mK( zf}+|(R=tKF1EQfVKzEHdeQzqLGz`8$t2)F~DU>cseqIXFUA4V zjZG%Lwi93EEeBtFkt0)DbD>6N<+ylHhqoMj74hRMnd+;a@YS=sVWx4T`tS%~dBj>m zSGzVXQKNcw_If|MI#E7qcBo{ggRUk-R~L)hu)fpl6Qiqeo_vNb$;X1ZDCJoa1C-^?+&t@(VdWN&S0JROUNpkmore3B8#~eT9oVBwQ3nx30XbZ zCpxrkZJeqy3t3%cc+fT2hVrTkg{s)89;X5Hpg%!A=T}!2qv|+WhnpLg+vZiK@{y$Lh66nmuV8}CZ=7rlODfRINAdBzE72oDh z!Ng-q*_;BqC`&mL@#@?S8`LtZ7@}C^TV@qE96{xEUm(XuAom9T2)oG9N0B>QMjND% zBO(tM+G-+ZKBicV!cKUKD?`Q#RAbezR~Me%y?Y?I9UDXfQuo`pYvWu^RhME{D=aX!UA-WN&)I!a8rq5er|79;3HpYh6eKzj;sD@}UkTWUbFW=+w% zcTfI$P@Ffm4kEa9WoJ@ZdQxSoTD6Lm(N`A%ZCMwVVj6X*!lEz<$;T9u9Epk~9jnv0 zE63F;LexwJg4ANh9&RfKCq-5?{1VL{@}tc{BpcK56B&jk(Uh&itJ;*>8>!ftEi*O=dNEAg`)}>ZuLGBTg-h!ryQ9~kdtaf$|{76S>;Xn zEyo$@%75!tE%|FfGo*r*PxS1>r8uN{VriyU>ZWjoMkC9(N~Xr=&r5ZjSQ1~T-}^

$h?g)=Cc08U;8&&uFT-O-`RL^*e){fpTtB%NH_zr-8bmOLjA}&U9Hyl&&f) z0VXx2SivHw#zk=fAGE@-doyr+-6|Z|x&qxha7&;RDY0PQY{xhxhWvcw7lMwNsMO4K zOs#245{Ghw$pIIV!&$hO?1Q$*JgG7YW{sdxRu~?=JV?0_AL+!(5U9LaIegjomW|h~ zG{J6Z+>&?{$fy(w7c7K)nZl5Ie*5{vF^ENdb{$`q_%m$M{e z^rSISvcz~YW0A--70Li$*s)d(@U?Fe1?!TAemDoonbc;{4NJj|`ifBo?beE-D<`2Nd} zxIXJ&IK$;e8s?I>NjcC!V~YLt5O6aVd5T0KfA$Cz%1O<#P)=@iq)`LKWoUK+k zgq=#KLGE=$^c2d)e~J*7G?cCgkz0Ui=8vFVwYE0${ym5*WQh0+$8ht_{b<#s9+D+X zZj+$5ZQWvoWx9KS#)JG|a{wrac{Jf5lN|fBwGoz)C*$dw`>88?N?{bEXet{;p&mgo z7+w&i!V95TZuZ3-)P-{ROH(LU6lN)}0fpVH$LlnO6*)WCb>#?0)`8^^@Mm{KwkwMQ zdAv$?psFo`O=jIcm7Vd5kR^h0apWG2rxeMe`*|aoG)zSjOUQE|1etDRvdiG-ocf>@ zq>!si1ru3z-^G#v&%jtv@svZk6+2Q@l!g(D{umF7P_-? zqbWC?XwCI$t(r7I3r?Wd(%V)|8=`B6Hk>S7jA=RRZ$w|?$BeLr+xYz}js||iv5Q}D z_u5$ltH7l!X+}z;j!jS#(-H7lYXt1Bj-VYik!F8wOi#;yDbn#@%00CZu(KAD@1qxb zPaUM(Umxj?#3CUr1zS+s!;PSTq+FZ@(jIDrH2kG_+zM&`9FLec@1oD{7wB@}bM)Q! z1WlSY;Vx#$Fh3D@kt>TKwYWp7luW{slvWChyL3}WyT|LsYGhGf74PU)V3K>u5#8H*-|dn9QcGkx-W-{ZH$$dlP3@TRjV4HSumL+>eJgnY z>m>ziKqXf(Rl=a%wc!ceRSQAE3@N7W#95To2OA>!-n#tNvt!UM)+ECzueV@F=!P7V z=*9`B?o6FbSnvzF0KwD*X`q0qn+6$!Td-g#eCe_vYmjnODPPP$7jJ&@<0Ze;G-J^2 z`LSNa?Ig}Ioa#qTuJBkx;QY?t&-f47Y0K8FsMUWKY7dx$G96z>SiOOWZafUt`^@0A z*{ITcCML~Ygj5aCM?W6Olg6(KF|aar`w{~weBc;r!PAFI0q$f^+&4h zb&z&feJDf?8glIQ6R(MnEJMA<@NCJ{cXV84;<;aZabsm&jFXZnZ#h zp&m27G#<8)fj-bBR2!*OOzRMV?rSW12KR+_B*SSH@0PVI2;QG;pOmjYeTY>Xw!-fF4- zEu+tv|ME0jioO%K@-GFWDS77b3 z1zbl{+sNpJ|ystJQtkfSs>c7tI!(COV?)5h<+v-USS_VMp@A@rpfE|^^_nK7&f1X~Xf zZfW-kw_Gmz9|V8(ug6%uX&a(D%|lejd5BjaO?2n^2yHtTqvmbF!7a-%vQIlKj34Kq zl|51Kbr4Gje=g45%ODA;X4Jrtucxrtq|iFkk$z>P{DPmpdyd104xnhy#fV@JiSDwH z%VxSP;y?D2#-SY+qN`^U&L7=@*N6AO+67aoezaz56Fn3$QrKm^%QYl6(;P?n;4DMT zloWhzr=&RMf6PhMrhOdp?ezK{w*t{izC`x0yvRwlN0p&0##F7sT`?|U-KI5Iv3jYY zQ6sUE>EfUx`*&i?j!jrkGVwJGAJU(D=9D#@lw!|u)D^FqQmim4mMzKc z1u7Ehtx=VuSso=2Qkmmo-+lE7EBJT({@XX)Rp$apVhqWxMn}J9VC?(9=FE8)f$$+izCC4}om!2pff%U}4g>$p zqW=e9{p&rfaj{GoCkV?aLWtwh#PK2GcvRmGSUQul8mg0ZiDQrQ6zJmBkqx?(+Rbma zY?@6s#-J-L<)`mIBYgLxnBd!K0eRBJZ|%?y3kcnfICo?_m6PsRGk*%Yv~R^-yaZj& zH1I-KWTj3o=!(2V2Qu#p5w;qVaa{%Z!g8WmzoiJL|1x|de^eJDmVSfWc?(m!%tBwM zV+Pjbq?TRVH=+W`w03Mg8WY;+jb;&%q3OR%7S2KS`gKr`+I;!4rA$|q`B)>S8jc;_ zi%PX?pkC8PXjmu4V5{z=8RsjPEkq4k1a%rWAVf_3A{|4;75ZyZ*ZB6!C#>CH@!PLobEAy&tnE?U)~gie z&Prg`=OS+EL~dL#85`LvkL}+A&)9+Z^zki>8$H~nz6-b7WlER@H_G__`D1+j^j-Y) z;zKN*Kht`+%MLo4lakf!8fT6}+{RQ?qNGCKkmrYSfMOWPeVDNre%xEga1`vm)T#vqxw0}t`Sqk)-gI@R+?>< zYfGF*A<@D-3f!-c(^OICB|m-lDGnakM{ZtZ;EwLR0MTBK&P$vN>xS}a8*%pVHcS}O z4J+roj?V2g8!Zvasfi^a!KjW8#Ek_}Ef{-$UXE#JP-R*%2n*I&NG?W<>u>a{UM9A{V! z?BClqC|SgrGK=O;$I(3-F>yq1Jbm;Q#*XrXTsz5p@#F#SUO9<_JJ#X=r^z2<+@77= zSx0bls-r}Y4IjRQ?qn9pg@YFgra(A&^a8~2XoUMx=oL`Qxn<^_uV?uCh=1CQz0d*m zW>;hW`$v5B*&}Mq+Ys4tE+RV2MHJ~;nul-~NnJ$ObGDg-QFAxrz~*JtncH~TyP76q zI|7ADfn=bRkT@wJ8PtMqT_{%)ZWG6jqFzWn{qG;}(>G6XVEb4Mh+EY&_jZ624 zBGNtL^x8S8r+1pN0cW@m$*6wqv3mYgZVJ)Xi}9pNh|A=z5+dvfS28Ko*F;a6>Z1*i z&YV1gQ^ybU_y+g=*++j%ZQIyDOf564QpNIIPI-%)P+jBn*<&bEs<=Hbg+b|GIC&UP z9^T~kW~aC@0ynl|NtM2o%cqa-a5*ODwqJh}9XRh@{ZDyO{w|+6%5Bqb;ceclU%R?F z4Ml@el-ztPud1!EJYk0K%G@JH$Tku$py@xwIf1DLRga!rdOvnpADp2QF|cn>tLrf4 zQ0p1~^VKur{11ABzQbo9yv_9k-11{!e+=W6AiX*9q)O#VHoKRDjm`4H z)E^n;R$CkkdG`1&E}lMwQ%CpU?C}G*#I3x#w5Jz^%iXPQ4N(rx&F1rK&MLH_Hp!rX zisnA3qB@K%mDu72=-zZi3ba_fZtxHGJ?FSLuE|0qvwGK^8pk@k?WWHsm4Z|gXCq8f zE1~|w=kH_V_C2&xyDvt+{M{Cr!X4ddK6IgA_a!9Ug&4nh2j1AV2Fqtn!gX%B)R_CM z$-}E$$jjTFLvROoZ^hni8?cWe|1imGcEU8fFNH|)98#CY;=K9yZ=d1hi8oMX=xUVe zzY-;SFGEy^*(lIu9?A?@g)#$IqiCNM7&Lb$E}z_kP0Oa^;ag|uB|$%x2Y)cC!@VpAeWIKX}V_U5lww z$p~1aE=~RtcVv6YbROTigm$f*{ruFuMTO5E-@!**d#uhfZp0w#Y%buho;}X@-Nt)d zpxTymnk1YYz&lof>d8@EvfHk5(l@HOfS1b6)t4GzD?!T7Z5oTZsCkcA8xrX1lB$ux z{rh0d@FDPw8a5c&JGXC#Nw1H^ep)ZfS1+{ASG96wj2b@JHZmH`m}5q0*PNkC;*uKDQ9+VtfxGgV=xk9CjZ$jdSPDl9$fn@!hLtdT2_PR7Sl+j4+wQWX34J ze~lm6iN1OEfD%$$b~@XX2=+4Kh7IcPd-o>~@8HqB8=P5x8E@UZiPh^iB3DFy)QfG7 zi&w7V^3`jbZZ(b)vuHngpnlb` z{o7Pg;77VLmeV!C4Uia5zIbh&{Os{Pmgz_Q`pu^{1x;d0fKr@Gr;pk_{QfP5k~y`s zLg|<1$m(bBze7*c_uORlg}FIR_hHwR{M)r<9iO9wqa8GE^azuBDud}UW@v_?GMP1g z%0$Fdr5-^;vwXQSHY#WXE79_Gm!OGRfqUxK;x`8R_3UEPoNWAy8kRbj-Xzc}N4Z%V z>k@KjM9Je%O^k6AUnO1)Jx||NsE&z zurgyjFqtw4sbzUX&uKYOV=y`qEEi zV*d2iQ=C1r6FceL-p*BPlV2O^v(;4ZsynrTo>yDx{W5$!N<6Xz*ITOw^W}}=n@ido zbu6Q|+E|A(-eI(%7Gud=i!_Qp|D?3;$GFH&HKMPh=xslILDv|ui~oMhZmDsfUn%HT z7{;xB^9dXMdUeNTlJJ_Pv>K?12;E9W!c6zBo8%2&EhG*2WC%!hqa;Ux%UzoO`&ACk}s@2PtNnO>;Gzme`%-f+lOyhRKRV$a8 z4^;D-SF+d})-JbQFqL&HB0Hf~kd42*qO^FOCw_&4r4!l=uD-bm5qzWnszRy-<->Q? z-Vx|tP7HarGKWjA+Oi7&5KUG$s*Y}oI;u|PTvz?7kg|S+LwWdeap+a;EMY7mr9z4i zbS+Mi0`vqsRwUA^|4*Jc9?v-0;oQMZxO8+I-a5SxE9W_r9mL+^2ffpIkFyZMBMl&( z^iid%Ds;-JoQQp#+-N1OUTC>fD)wF`mD3oUP3NLp&FA#Hr0CXrmAaNl&zl*C^(z)( z4IS4j7tOVe@cZ=WYUNZse?Rj zW=yk%0?|xowi3!FIJ>ac(dN#1%O$BQ-_PTR?^++LR<$yQaRH&N$An zj8hlNrNKFcQdXx?CsFOYxYW^bY-luyyA`QQH7z>G7nxTqo|&b_%>jyKAs=shCsjB( zu;`YG#k5drRiqk6P40*!i7w}h7>#1NZe4KzFS8L2evh zg?RJp)=z2&vvO}cjO-#Lf{d+}R_!WDOD?5)i%T!=@SW6u)1PFc*n8~tPIq*xwy4t6 zB||UYt~gHm^3FK!bVDfL=T@NJEk4%!)&6Q_2cZsnl~+BZidR)?W35V5sz;6(!mlZD ztr{n>w&a4~mYfW(ZS9M23pOd{(kFCOC92#?Uwuq`A|pYK;ZdRvrzor0wV+h-g;%NO z3M-y!LFbxd^neR+>(s4ji%=HLpGAjaJf^%po*2$<@l*!AM+vGNDo?y1oLv1?HRINh zYD?#aGrCZC#%GiVT~*k&1xw+3#!_|fdSmFOTY~UJU%+B%*@l;#xg2T=Z*%zZY>jOq zKp9fe5qH!Zby+Zl& z)+>~G5qeuHVU0F@jvUk?^XSKMlCbd?>1cM=G#bMBcDLWEkz5jS8_etnf3LOLG6<%Z z(joY0)W)r9b38CbRkmt9%G>O2`4!h_g}beB3mLUk>ckxJe}(PU0eZwjIb3K9%0|W_ zR}!yy!KK5*BT7kN?S;8gbKj|%SJmlf{pRZz&g$`GKm7O&Vye@9$e~=P1YWoVsokaC zsMbANoD^hAU?GmthilSEmh{LTkt+)~-&MEbXg^y?Zu=5+x2U_R&GlZb?2?hAWBjz& z;h8eY_LbG_fR`!R5jZv+UXa!zQ&9`3^d__d)I}_mEO7@?AJh4CHFmr&POz@&k~)`i z!#d?mQMDI=OLZb+MrT5Ifb|6BHBcd|ew`JR{WD_lKz#SFkMQLu5Aov3L;UN*`#8V> zH8p`UXW9mPq^jN-(kBy<4cauRhcSbCV9nxLczEXu9^QS6!vkfEWt4dCoZMV=)N$nH zaCF}FTwK6o#Mn2HJxeB=g=oNKeihepCEyZn0^qtzr?y+%8i1(iPLZd=-@7T;g>TNsOhcdb7_DTpFX~az1!Dwuh-?+$#KxV+t%^x3{7n6x=X?)t@&0JSwcWKlQAe{he-fvMrra~ zxiqzu>LyR5g4&Vib~ng(hgafsE4{9W?)44Kto&(*8An}pW)4b`6uR{`)t493mjg3p z{NF3qQ%kswr-{ueMs!|&j-P3`-Q(1^H#o;ayFqI_SH0KF>Kw%ws#38W#t-X_{#{#P z*0iy7j$Fr!r|;7|sq6rrzz>(%_}U2ra6TW9&%6X=hlA8U%B$%ZexwGvsBk8Z})$8sigk9lpJpYn-ve@>1>o>}XMN63&%Z5>6)@YZc zq&{e{Pc0-Xrm~z^Z`ZjpXE0I!RKnV{)^^YJX#HxScFz(uO*gwtu{EstBO8TAD!$?H z;`K8J(Q5B^Hqk2oP9Xmd3ODjZ?Ong&*3~z$n){9q@6+D)x9dSSoYI#zp@|zW$X8!I ze-EEOc^6-N@&Mm_@gZi=t1ZAP$AV4~YRolas-j-)TF{K0Mh*C7#ClvKQoIE6=A$;3 zmnLOYUM|y$=07JCmCqYWr;u*y7|qzxiOwUU^Fa&j>ea4^x*Vsi$tiA2Jg$Q0(k?`ure68uLYz0#!h$!nA zN|P#+!0Xr}!k#~&K-q?qs zeLA9F=a$@ypdlR&&eu9!e)mGu+3e9r71kWSiYGk0U`VMEu4Y^izk;^-QtI%F=gz>) zxXIkPX}B#Iw|TvW(yVfe6)RE*4Qf~8S9jzWT;g`IT=)b4bCrtG*c3g%1}zgu&Uj} zs)rI$ab42$ajdU4EcI7hnKq>>xvMA%BSNN9HjP68-wr)Vap`s-FD~_zSEVqlE5Gbi zN?BRZHIMZuU+GP$&~?doq3N5?KO`!D!$YL21+K z3o^|^Xd~!cd?<&g94?ycWjGF#br3~FXogu0giOq;#PJ_e$Cm0n}kK*^X11RpCQ(GTD-3J>$4Ig zhYsRs%mDko&KUYinsIXrXl@)^29k-Of<4R#WsJJOWqVJcDRjl9`M6r_pYA9z3b=rk+DnsMA|Y- zSI!K%BnH?nbJ?mdAmg4Fmr;~Vh zG+~iVBJjSWZu^~giYseW)nR&@rRj7eJ>$?lBV|{Ut4IrHPsh5IOR#47BCKA%7#r5D zwvRW2vbW0-9}^Q}`^c$?;#jAdOX9|aP*Dih;7*!6Q(5K=B?W}^X6H! z>D{Ih*vBRTyYv+eY$j2uZ3p{!;ZLaX1KsywSk;@LH+AAz@&Z4aO55-+ zuC>$mb^Y(mppbWc|!cyzoDnz-V7!Z_Bzm(HaUCl2mJk1p+PaM7a=Wu$cmB1>c8EDzQ$nT?6V`{Hd*aMQ=a)Y_^pCuh#l-WTLv z@pZw_qy+EiC=PC4B6vwK!?d&DU-fSKl~)6D`-xxDIkn(*OXv~&edpMDd&_wM8FWY;*Qd@JtU zy@Q3kUZF-~Q*L}p47uDbe9RdX*SUz|EWD@tXP=JuPOa8x z@}K;1H2Ln;vj!Pg-dJZSCdaBKRcWS~I;V(3?Gm1c-G*(TV;-L8rnJ(cP$^bYw)E*x zQ!-p2^5|*;Dw&OBuw+V8)8FNv#NXfJ4@&my7fuk!{jp}n65FYF=%D`GX>k_Db2j1n zm5VtKWfLax)3TpDxXziH!%VWffLEvU%Nb*g0PA|H`ZVffqH@UzL0CC*^$%f1?c%f% zQ&B|wbb+3dV(xZRJ*lTW3hAjxo0F(ih8Dt;6w?rwsSPzv&}hioQ&v^UNE2F@9(-%=5g4spE$G)Jv7i z&7Z4?$FXmF=`#t2jb7Nw(ierC?wvcbe;no9!h`m?&^_FQcKPB3+%#;Ivntf3=~pq# zr&XH{MeA*RH@bIWdZ&)!+_3{V%b#ZPtmIbJ%AeZN!LV9HW4PM&Su+)Sa7IHc=R0X@ zsyq?=;74wb=kfDG`3e+5g^HCpOQyVi8du-ytI6R8F^RM7k;6BlZIPkjnAngY)!T&Q z&*@*+9F1ST`-~+$Y;%5QaL?oM6etqY1N-%+^QMALt3R}Jy)CEw@a@aKFMS&Wuylsp z{D~prhJ`o964vA*GW-#UGH0Z=C}+~|gk|MWsMU2{6QmVZ4pa)At90r$(v1XY;ZAAk zIlV{ei+^-os5c{BnXxtxbhG6kKo3|bAcE2T*Zx8Ns15CMe&sYVTTgv`JaPVCTT=7U z`}c8;TPUC5Y*dG>sa;d6uGh2!zmWD2Lq<)&xYy(G&f9lTykcFTo`4Qnb* zpmIm7UClcARHNpjPaskY-@*E4+^`V<*F>`kM`E1^+CR=moX&FjaPwc^nO;?e7#)pWS z@g5@iD=_~FV%9vz-b076btP9ZP(Ur4HN_T~$?0R%nJWoV6W|g-F2JRaNCf@P1!b4d z9O1mmAy`HIblT+cm=Vw6jrgf%Uaej_pVQ^nVbbtkcyj+5UgP>;32wLc{K}lYGp~fk ze6BswWX32~`TiZ7IqufaYU#`y2e@Zb4K${c_Y}1{L08}8-M(>+(b5tM2hGQoFgdh) z8=5!a)-3!I^tlsea|h8BOb= zTOGs=`;N?|U3c&CXk{^GchO-Gw~pZJ&FWER1$!;cX|GGNJIk@f@W1^0A6z+qik4;{ zRHiiz*1c<&&T~f5eXcHX1_yaAzdF?;qe`xF>FDUL z&Wb?MgUs`;o%k8j_H8*5)z+xFX)HaFY**PbKD68S52Bb#{=AVkSx<|?v{RjShm;Ui z22@2t0d;?F)T>aOx>a$Jl4fLY->`}mMXXcj|M~mpxPA5jhVT0bp&RLu<$|qz{6#Wc zoX2BtUcjF9i!rokYcBmA&so4#Oc*6DiI2|dhx4JG!=0Zzx{E)){~SM36Mu)xSte6) z8cig>Hf9tjQI6u|`fl7Ov;_|C+Kh`7$Zzc4fbTwgAFpwerK}4>JIk6#5wXhCbu+o{YOvm!f**hI2yHs{ zbc{qVPWSFV#P26v;m1{PV%OfixP0XjPM$hr8{j9*ns2)*A3kynAAR%zX3Sk=nvL9v z(!d7|9c^Dw9^J1aCJyasjeV3Z&sAK1Bptvs0_8r?;q;v5M09kQ%xORM>~w@+mTykmiwkFk<&(gsufV8gGw^t+0rl+7`Bx$rGbn>AT9S!fGJpK$E^(G;M51)0&3{oI_bXrYgE~L$V&- zyU=njWh#dD#?|6@@oLLvO>9nu8dh~>)E3}`cv`@%KOLo_t)px>cWkf2$RyVlmzgi&X3PN4uHz|d;^oS@tqjIE<4 zQm_vzRa(_bIS&rn?=kKMP?GMRR^Uc$eJ zrcK2#goiljUgLOcINtD|Z=P{4uH6{0^F4%+t@Co(t#+);y^-NHf8Zc1#xxanYJH@- zUY(l8fNm4{OXD{xrQ&jG7`InaEHg)mL>;9;In_l|LY!c0*HVZXM6t40+)8shkfFqC zFTZXnl~qgT;|xC_uh|AC5AVV91v81g(v%SA(W`rB8;pLNE?2E>89K0^;Zyx(^^$qE zkAiY=^3X2oFg@v-9?W?jH#z0Mx}|&F7NC_h6KV6>r8cYK{>_V=`7o4yus%IoH@H`8 zGt(xMWHHdK5$lnbYeV!)9W+3NFg?~nRxP$exkp$yDR$HJLMI6vmGj=y**MIR#yO2WHOf;M+1EXbr~9+F33$Y3TA5 zzu7{Tab8!4ym`NVg)g5y#!b4!7*oUU!dzy5xWy8!l>eG|(81qH?l-L}ks5{Nb5GuzB7hoaSETCBh5fjSZWy z!V`yb`HJBVmCPQ^TBC85TDX1e7^)O0jp1FXck?SRdU!=#0@lr(Z99b>+q4-2J9NhI zE{3RBgz>~{{Z(l`oO6YaG?V|* zdjIGlS5cii>h-VmGn~f>=c!$Ndi$=uc>erToaH*I4?p@44{3{Dzi}1)hK`}$-Auir z6*Bl--`;T^&8C|?sy{~d>x8j`x}jgUc3zK~GbATsFqG%=>Lw2y}dCOOHMVbmOB?QMEa^CDjxIUJ+7sHtQ@j%;o3U_Zn$POSSeXTYg1(=Ko!IO#-3*(f!Qah6C>JCY-Ett zcC^gOA>d}kkYNq?IJ?>msorXV{Lcp?>S;fuzR?1apY%iM`#q5MRx9NDY#=he-5we4 zv_;-e2O`bQR>=OKv&Bt*ttmXYKj?|<$*(rGr?TAdh#U{Qpy0m-+tXnm^+NQs{z%O? z=$QM%o|Z!X=Yx=qsbsj@76lkLjVN_)5r=pV|gDV|G4rtVVFO5D93P zmEEJWuv|?)L+WFY*jlw?RU#;-5@%2Ij$QhFh5iA1X(Wc_P>oX7CqKV<@j2GB`&Fyg z0#Bbk!^O*2(QCj+3>ZF+zLu8eGx3dD)^vvJwYK>pf5#4Nx8eE`eLFbA^%Rex-T`Jw zU}Z_(lho!tQFpVnFq;tDR(wj7AQxI zJOWnjtn6reg9b|Dm3$`k2+O@n#h;(4Iilktn*G&%i_IKi-xX^+Z}ei?OcGtOoSHFi zm}XqDv}L%o)m<3hM2BU@rL_?FYj>nS&kx9~;%AqZ*GI&LX2`px6>_a?XyK?$ytkr0 zqBpnX?D8gdUH3y)H$v_;vAoW0QdTrT_<90*Bfqc3G;|DG$9Wg48d_SRtGPQR<2va& zaicbIez za{?6=#he4CRZ&3{(KW7ljcd-juCA`@?)l!|sayBnVf{ZJ&ogx0?&|99s<%$AQ(Qmc zO0DL&q_@@Ftt5FLPq5s##@Nxt4ei7lT4o>@4tx=c6$XM4FJbEE0CWl*w@_$~KvK69 zM+^N+U%OD^#5y?V_bF;*pDa<2D>4NWAwo%vM&Ss|`;VAlUw!?BUA_AzYt*LDZn*h& z`~JIc<+Ge*9eWH)MyI4BRWO;%oV!?&S87+<#Y6XK6QD)YM7YO0%+YMX8q^Hok&%(; ztq4|6I+`3t5vpX#g|M2`BG#Pg%joi{+qQ19zr6aq&6zbLAXxb8D*a}w!i3K{bF;#Q zOFU#48x>FFX{kO`N7gRwNbtbA^mDU-)E1uW%koq9c##gen5#Yvyl6JRQg57>hH^6I zPf&EhnrglzfYvbBa1Zo{GIWab3|^`&@!rw`2Ulo@Em3Ngbh8`*x$d;i*1kat>!d_r z9Zqg#BYO0+DFZcpO|{l?Oz%Nfzl&0VO&OrA4m$L(g617;>fq5<*g{*2v@f(t1LeVJ z(AtI<^tG|YgROo27B;@m5F60Br}b{r)n*JGV@0hx+n_GmhGNht>)NE9jqWwT#uX2- zE{)sTdfIsuUm$?ekIul&RRvaMRHQ0{!)MzeUP!n;IqT1!LVDpRB)SrCv zv8;o`WGT5*vWwYVNgu%3gRrV$H>7sQ9)oT6{8QW?f!Fgvxs!3e9}Z^BcuuqRhUk&W zBqPazv06KcVYEGbU#9=TtC{)x1sCXQ(A;MzseN-%HdLSLy1<>csw zc0iq-pG3BIq-!Xp5t&A{_Mp$`U0z9Oi=;IO6w=q}XkYnL!ZT{pJoiOhgMUaXY?LzZ z;4efy-OA+TNZSZU)JwI^SG#f8TT2pYPWl}ZPir?-4&SdQ*a<5OtkX#?ty|ZwmLOiE z7Ml-{5x%gnz&Azd*;CsDsZ1_!wi)VCSeU$CXhlVeKUUp>f&$;PfK5~il$Vfm)MaBM z@_};??NBaM-9#@{INDp)nVxEe8eHWrS|EphhgR*Z*~yKq+&g2f(pg>X_{w3$cy0AS z>RaeteHXtW&rkq*#D(tkh@?vnXOCYmO{c%K1emT9sPtSnY$F~+p$q$kV<#Cr<}6xn zUyD*7eCCjxIxpJ4fBV%gzjBwgFBss4aE~DrusH&CfK9Xtz`oywkpOH$sG!oIF917y zl%xo!(rzFLVgab|!HgdbRizUmzk*wn6YKfs4k}aJe3uclj>p%>onV`3KCI{w&L9kq zZI#^yksG=*Je`(#ip%x#k-;AHUsmdzga1f+JmMMb(eqTH_Yo^tqRTPj7AX*_%L^ko zHY^^t7d4S zkMA;3TwH8jh2OR(HMgVB?`25l$JGde8Z($q=KUj;p!fJ>*e zZ?PMO2;F8a?1}|bJxF)*=pji{RR~uNUqnowD00fOCv+wlZ4o$drc!y2ZI!HwjSER3 z9F-C|8A^lHx|Ne1TR9cpHc0k|xsiP=mVhIrkk@?15 zSJ!06f#YThxtV9; zl}jj80*esub`4tE@oNh$`)%zcU!{geOcL>eYC^yrJpkH*mX?y1+zjcxlYzI0&NKlC zOqDMJb0m=D-@g@@ojADvPgdtC1^SPh0_hwk+wv%p&C!1B-e;t+H9~^!2-)BUS?jLK zI4C^PS)!IjC4r(G&#JD|UVG z9behrgL;5dGViQXYefQ+Zs>KTuj&SjUdFg|GB?sl@Dn@QxU&%|7KR!Rt9yRE z z-1}p#XXh?9eDDCRRVr`?>;O5+;R7t6V7~ZZ(S6zZNd)@TcEuns5<#ZUlnLW(-`eg5{d^8A7@>A^tAy)wX^w@nKoha3>!OfnvI<>O(Ob)DR$(T z@!E|{XNHf_wme;WSc|q@tZQK(8#rW?S{P+BX3npWyN;T=u|GKzCwc0qbC3m6z&)$57GHItnANuxuexQ!8aqwC<;{t8 zil$g?I~DnRo^p~Cq`qHj05~Nz9$o~j!?Aq`2IVxH3u!BSh%50iy%hZP%AqHf0O@6Q z-jnv{2OqF)uU%z1pNy5iVv54APSZYcg95uP4L1j+6U@z}ftm*I*3x%Wh4&+74({ID z8f;aD_Rpr+Ir^S^Zr!cq9$W2I`J*3y=su6jMaW?;@&2$1B_Gkg5QsM=UIMs2({uPr zm=miQyr1(RO;j2=e3%y5j&=2u8eU&}qNz2c^Sru(JX$Xe*?1_e70HG}iQJ zAV!ogJ_^;Mc2k9o6SL4nqeK(1onSt0=p!14Vp3hu6H{mvi>?P+K~l&Tu4Hg>tC_NB zk!b&IMa=Je;1;`emvWt4SYo?(Y_+-5#(PG=)-uWt=v!p{i+fnV-i30G_OQOa3#@Oi z?tYHn131^Kz>15ys!oBN6^-3k<$J#f5)r-7S{BXtV)L9Jjs}rdpr~zI=hyG@;}nuNzoX@SE*jFNt>QJhS#fc1OH<0T zQ&99$HUQ+5<20KRXB@g!DM2y|#J)SpfN;Y4A}jOPQI>zqagIFR1;Nm1ywJfc;*DW# zVFfu?z)lH;s?-IkygK>?GaLPYc?M@-=+O~gf8_;jZ2Y3#cFT=!L1YlLd{l-zMu5Bh zs1sbl3)QxDDGwpoOg0iD;ufqLPQ5R_6T>);UAZF%!U{Q&8OVpX@ia@S-C8zatL+K>EoWq1L0NU0?ZT-gXVKnS4(oE&|?T*9NoG@*I|IxB@a5YBin z0L>LZH#39QttR~-sq6o1=jngTdGhhw?ao`zwO{}JQ?N1Ry(n+#g%_-{8*aS7HkK^& zOap|xCm7U91wbcC!7;`<+=GujBvSl{?Y;j_yZ_p2ZOy^+t;{Fm6lgb2;=v-{mmc&0BL|>U zLKhlcd`!{A^u;s+y_CMeb)jnL+dag@2g+W0@|ONq^^?iAUO{bFDSYSLGtcl9aStlV zJ~7XXcAPTITsp`nRVsxCV+`Bfs|>v7pL>>z;Gci;k*!;Ey1n`8OLof**Vx{N9}xAp z*xq~lbtkvLW)n@7W%x+Wk5lu_*Iu-r|M7#(oi){p3cC};ae`HI4Cxt6RzwQs0a#?1 zNY_6}sWB!gD3NRdkPW9gPF_PEBj=OZT#>SzM&TK23C#RGjlzmAKmV9Lbl+9>>YLBm zd-Bx3_t6_N#6D!V-Fmt0xp%j1Oe~i;i71)GVR$21Mm;7q+crt@|wzzT7|vip%he z0%wE_H{+DJ6ESgyU7!bBrT_l-zxJQsf46`AOA$8z`qh5Z@!!AwX8-xm@A~_X?Y!a& zt5m6?Z_R>1Cqep+qgfN>Tvb{N4`D=kMF^a;NR2xkMVXF5E@T-rT$p3%j3ADH1UL%d zb3L4k)#JcK<$~7pldU2u^I24c)BrQH+_WH&2FW`n;qo zYnBF}GVp2)Zn^1t`{d&fJpm<29|)?v^OkEp80=YTsgFH)ha0EqF?uxUld>OEs6^kj zSNIsoz@AafP|X~z9|%xzYyjMt{>Xv<8;C>pHi1>&;FbbsJj|yOK&9xrjix=2ukUZLONBiHZV zWv{*RqCN7E;$3%MV%@dvN6DH~9Uu&SN5!qN6B(oL28?POd8N8Bb$`DXY)LfGL4g?yezY3CGx~w%@~AqUYp9QA-=~1k5oO;E8n= zKmPb*5_8+P@9=#m-3SBmZBX5fFGo7HWvM6lW}JbyvvwVMBVLAQFIR-q51J%jefWm{ zUbioGB(WLmLx4Z`K!E-v0p&YIYSm-%5x_l zoI|bzJmr8Tz~)$kqh|Gz8?c1Z7S1^mOH!pICUqgWQ~)QitKm9tQUig{rZwG>(sYma zFJ%rvu6af0UnyoEJiPRnL;$060aUpE67LDeBoB(GS1jEng9&+`~6us%1dZ6o0hy? zDrQql2EULV0q_8n*|TOEJH=VKd+xl=dUS4W{ffF+aiOG_f{xZ#R+OfV8~6h>*^-J$ zK3^UvUdRMQ^Q`+IOUm!shv;A0$l_Q1{X?6JAe?jE=Z+pqBs=z!UlrB-&#&KC2>++9 zAJE?oBH~o<&=Y?$)~f&V%?I}LSMO`d*2j)&+6tC0r)ZEyS3-Q>$jVSs;_pf8@YYL* z>}9P;dHIot?c6taS>|hVDKp1YkqM{;KHxcvsUBZP;4n2I) z@*(%KGW_I5K$>Eu)m_;kQHyjNM`FFvQl*bLywy$`wy6g329 ziGxc3^NE%6Tp1}ncsu^DGQj+4OJcL@td7K2C9|*vXxOT;o=co^;!da`*HX{ErS@yUAd&?mW4p zz&CtCJLQv4lthRO3}y395=Ky^urfjYHfhbzSK3vH4Lk0;`6s8lWf`c9Hp_A_FF1vE?4q+Dckr&BG&FH}Qn5CH;CAL9d<9m+%2;N1vDaxq>I=!z;DXLL~C| zBS!X@TdCz40~~GaPDR83)Cr`)3!zex+(l9cKE{t9Z`WLNjU764$liSOO_?_mff&QrNk3XPY-~p6ylshe!2y-+lLad)&`p<+TOi;?X0a^{k&62 zy$kQayYL?1xSJx%YH#RidGC(4){UF_;-zNF!3^FI0Qq*%#nG`RD(IS&NCHAu5N3k0 zd6eY*gHP|*Uh;}c)BR_%aeG-(T{f1G4E@C8hvB}yI{#!56A8u1jZ3)NNO2(v7JBCr z1)r)b)T7tAB$MqbuKHZ|!}?Z-Rsk!`gXX!9=2 zLE}aYwk8ehyIcb%c`Y_7U^lx3+IMwhS4ok}z3q5dBWFq;c{M zx6+zDp5^ANEFkD?DqV7+{77C2R!z>RzrFRcFX4Qb9i*N*V3)jqqch{#`uKILSEZP7 z3YWqv{1x&BQCqieo&Ejqf442jDYHq0quTP@z)xN&1Jcjo>s>j3l&8rf32 z)!uN!4OYTEwLvJ96l6v|9VlPm(8GH4v4(QQ)%bjxZQoj=DR`@0d&PzJ#)}8-CAkGz z{^AD7BnqMNc#!|}(7m?x%o4XC;C4e#9XWECJ@d=~Yb^~K6m9{+d6ZZd)}#r0DGGr} zq_|3!G^z@I4!yEeY%HzOD`von$2t`%1HdwY=P}`)td#NNs(U?De{i2n2r3{u2|-17 z1qm<(!CKetzSi+MKXUmEB^+sY_j@VJlwd5CDgG4w1)x zvH0kD+s^dxviWmoi8zNm@*vEymd2lx#j0>|`UZJ}O3V`2RnMYA*L%^ji`sOyW@{CL zt>70(WZ&Lmi+!Zcg26n9BTxZ=U37K&^y&7?FTVts&(x54FH`EO=v1&dDk5`D~bGS5#u}Ts;hSRd}r&qQNZ!wlSw!>w@tt?mp28H zP`Ze+5@3@LFdGP=1- zymwvw4Jt(*lh};xI%p?J@>uh-%PzC><;y!~KT@V+*e5k);B&GCMj3EO9J~Q+I(bw# z0Rrk0D9)a5N>IMij+r5UPsetxe9k(ORSP9*$>N3Xz`aD7J+Hm$ax2-ePA@HLrfXmm zT(Si2sw=Osabrf=IieTKmEwUVz|0m@HJ<1(K$|HkkWhLfCcc{V0zKEJbxRLJVNWgc zO`bkyz74&4p8RFwon4O~Gsa07_yLl|#l^0b6crU2too5h9!a7MOVz2Tp6Y}W=9?mV zIV)DIa4NoL&6-fR42Z;i2BzPA_uY^ozTKU7+~KS1Q)q-mXNZMGZMs<9l46O4<87F( z&7MBV`e^$CG`rzio6KZ&H0o2~3=3sjzUz)#EH5`t-k$#U_M5LcHKKE2&ne<4q6!$n zBFE;6KxhPqlEm-E0`(Iq{pdYMmimqXXb77YG9xM*2}$)tIPwJr-XmYXMH6b<5stIu z-A*mRb@J|p+{I8GeWU>%fP=olk(>VyY}Rl!22nCaH>>P>^Z}bcd8lF&$JoN@qio)k z5w>LZIP2c2t&57@yo@%{rWvv6gzI=@gA32s{_CQFXA4UgUvRDmVs(}1OCBls3T&3{ z+pvDEO`I^!7HDZ1W_zS^%s~jGbPZhvue#;t8*Td3NuE#VJf#Z(X3d*4@HU)rA4iJ- zk&a~=yDX`5wBVhr);Kp(-qm;i!e)6dDKO@My`Y7M=e)kleQPtOO;y&O5ExS|;@L-f zL*yDsm4FopbZeH#?A4uU?%z^TQ86cwGR! znK}dRNCFj&2U!v$B0y!5pl1&)40?8r&!^hC3KhCr_T}9>FS6GZS^3<7#}q;U7ncQI z-$kz{G_$||{%c#ga;e>Q`z^M5)~D%l#4wqk#+bsMbBIpV%aei?%xTG;6)>9BaO6t(~a8$F#_OwFS2b@=`Dr*=;07 z)^fo@zpup^39BvOlSvG<*q;ehOR@N)1B-Vus(~#H)dPgz6Hl zYJ}KsQ$&DoaI$ul7|!i3#B$k%|Vpp2)_?N-M4R_TlQA3T9pL$7hh=q9dUicPyYSu*I(_MZ@vjv zn`MF)nIeLg$x%>HV4a(^wG$O_ldFiEI<@e6hS)dy2mQh)XYwl%!sgDIDFsK{7A{$2 zOZ7+O1^vm$mE!dgwBquuyUL{Z$+tF8Z`b3scRe#EDe36FlXNdU-}yDXUSLhY?2q>> z2Cx3r?<)T4M>|n)KCYH_Y|$vE;VNmtX>wXpXe1I+xbL71($o6>YF0;mc$`>vYKrI! z2lpw=P>fQXKTy|FcFAVswpuxVobvLB+DIwFNObnvh1O5jE@m;bFB7s5@qCGV%yJ+C zlu6@3`i{vH$1AXPu1%Cu!xG;*+LtbBl63S+#eKli2v1tFXr4`;G+sQtzJrmr;NfVc zV@Jw<)2Fx1ojt={skm1W#F!vF*X7c3l=9W8GcPeo?nZxQXz4Ts-<@nVpu#bHh7?T~ zi>}{z@g=t8(ala}M~@t7^XANvz7Z&0CY2@P8u0%5>#s?8UUJDLDexvhZ`SLtzn;8? zE)Tp?(9QnmKmTdpefM3so_*DoS8CVG$HT9VnZV7Yw$XLduTu{@X|sGeA5T&Omzlnw z*W8(tU9nuhdZmk(VWNkfnh^MQU$fInHf^vw@4DIMNkL_tn9gIQSRRy++DcTm`C-8A z^U+rhrJ}#QZTW&0iVZ?37=@|=(`EvBQxOwCa!%#mst*MFeDS^2(Yd;!lnzx10f-JI zAiY{_p|M7x$KwZVuro1{T57N_xjWKfbhhH{x87v! zS~j-s9ot9@Xk%U4w{mfSJ#nCbfEIO%IUzs0$Y#*x17w*1qyu_FHlyw5pQV`4v+b%K z7ueZ}Ro3w2kjomFGnfZO(XYAUV%sc+ch;u$o)Kowv|+Nc_>kS_zH4^d z+JhH(v=;$4r?@+Mplei_(kt{1hW+{Hp9hfT?b)-(g#wU@GLJdxtFIJZr(v)hAP7ZA zC~y%V2jw4H{`AvNhdMQ)F2$YD^b~zf3IzkZ_LLjDpH)+g?OM^x?fUlZ7o6qU%u2LV z5!2ZxBO{#4x3dQSuDfot&6qolx}z4sSOyshZiDj&Z2g2J=U)&!^}c!t;;hIrq@dwj#?H(ofPysb}5 z<_w96coJZAit75k8!p_@;YF6t4AI?^dp>Xo90Za>O_y(3bfN^Js~WqwoS31$J5`)8khHndRP z!KgO?jE5`sfWNC&>YgaYKKGr`)+k^8PYoIJdi(ZDtLKubTx=+qmEjX4eBvAFD+mVt z6}~xNVVk3zV!D+{Eucgt5K?nmh`u!!#cC;Flt56kUBOZzfdE?}6NpYPHLDwIoSKNP zg1rE?rh=YO8qnBG;gpC1$tC!=>XP9CQdY@G?m5?uxgL*!H{(LtW1wu&76DWK8?YEOAr?=jE%f&~=7IX$w?%cW4i4IoN z=d{1H-(3e=JZGZyGi85|dXuc54bB>^!e*Mkk&Bm5$cy~kV+2Y1%jW+d;(>=sz*pMMMbq=nl6S1zaJ^)k>octc_LZl3eocjQk8j%+8%F}n_$Bgn87S5UF9%^b~2DA=!ap|#pDFy(*jFS`)Nbv)jE`v$*Xq<7KG z4(4Xem|?fwcANVhF|LEU=bwMxu>B4kIM5YwxHj~0@nS_HLK5?ydFC1C#I%5S5}gQ} zQ33*(f8m7}x*r{G%rl{V?)lNNu&}_ox9H$&1o1t#(<<2RT|2ugy1!z@S#kpI_(n#C zBlM5)b^a_4i%bka;Z)GRr=QyA0&OF~rfE}csnAr&a-fN-;fYk66rf>^B|9{deW;C1MH;)-DFRk3Qyp zw_bYXY))Z&_JE8k1OhQQ9C@%)(K{cY@sfi_m>#|-N)@9{vtXWYneZk%?<6Gjcx{%_;tP+|WlHem2Tji5?1-%15) zWM8FN=Ni?k5ea;pRXX8##RdyqaAc?^wsj~bd;kkfwEjfQIaKn13dR;V2q57%H4*?W zMdgrZ=x93BuTsq$a2}K$(V0G#E@g4if7alx`dVAb!!Z3YUVhYrAsY~5a%xYXGRbC* znqWOIn(V3yfkDH?m|3O*R>G z5qFT^um-D-NT0TBB;03XFRLKGPO#8rM^BLwTFzGxO|Aa%j zdV~V9UwiFkchs`)a6z|DVj~@upQ)pcokARstivS)^yGFT)<Y6P^Ek)#ST$ut2*2} zNeCkh2qz)2JmSpz17}WBzLW-1<+95!x4gVOBfyq0UxG6!6YhRc#so0GZJ`7#hZo&unp69d*t zw2Lu)$%1*l(GSVB7f+gI{dP=umm)IQs1YMm&`QVGI<(FNI%h)zvoN0|L%IdL7BO5X zvdv8V6t(Rd{DSX~vw=lDwaR~t*neMJq^to0Wvt|-5Dif8BkQD7Fe>=+9F=`SYEUM? zI%U-+S_jt1(Jdv>g5rW)u&Tg9n@EuJ2nq2z7~;uE4j4J1vrG797IK`TDjLIB70{!u zgLfwC>7}aEiP*oLo66QsSWpAC2KS`4hX5t-;42Of=W&g~HQS`bm*S{Z{&c_gK^s(L zlSheAj_7OShRXUZSaxjJQU)5)FcCA1OVM|P1m_w6J>+!6i53H&0+zm!`Ija-9t

oVt3w<&iu95>O1x~$zxZ1az~1t zu3xh{#ZG;NlP@tT0ZSJ+=>j>f>8S=xZi zA1$pSdI4$yl0FFX?o+EN@DJ`QN$6LaOM{US|==;om|*VcX|U3BIj?15h;&_%p^t;Jj^S= z6F^l*G`WLE-t^XJ6P(y;!yxB)-6bFOEe?@4;KY~1`D!KSeP^WrE&7h?Wga{Bss3f2l9`~0TZh^&>MU8eeL2&fv>)AZFgeaNZdP$PwcP2@V z2X9r3AaPMaRT&guUD~^w3gAkc(+H#UcSDhUVYgmzWj|eNmrk9p3Q%7gS*BEqn;y~o|Q_t#jb|D`0Cs` z5En$GzIdr*{;%}WB!&9U&?YEnXc@s=BXi4AMf#vD@hUu$?`6pqNw4$r%KDP{H(q_& zjhwFEX??5{7u5k1nKmq}u8lQXC#ze52W%z5i03fkoB<22pq&6s03A3=>z^RaN^-3C zx$dWz@^z$td7tQ>b)o{wQ0}--a&R39&S+y0MC4$Oj+p-qtHLmmftXpzMIY7fyZd(Q z-?O6)@2`wJa&HY$D8YzMAHhnwoei+o7dTPlM#B0FpE)QUsdP;Sk>ZkAf0%r6O+TWCev6_;M$Rfxe3Ft~?cuy0_MJ;B{vF6K9v!-+Bg%A=wg^lMNGQh>}42#YE z&MK^SYp(1IEtW60rV1p1J{qSh|s8CSWw}B1z&Yj8vLKrNtY#G5CaSGPRLMd12D6rj~KHY9(iu7D7qG z+6he334P>?53&qQD0m!$SqUyykhzNcuUf@j^XQ z%$bvL)bo|M{J!2_{9v^u93LlbskX=mgBS0G|1$*~1a|s-@{I>b5D`>c9|MgCFVGtI^i{=NjyBd*cOU_ydG%66 z5MdQW1m(+sSx2ajw2H2AN~IP`fLj&9DvBO|Duh-1%dDPEx3$IYGU?P%Egnl_#;MPN zuxKYqeNqd?Y9I|SpEFu*g6UvUPEHLM#Jix>COnlLXy9cX-QHPJ;9a;v~ZMBEiQf;)& zE&#sa_S9K6@QPV(JnviF$Ht5rl{B39wX0HWs~VsIFmBWlc%n2+ur6!3D*bJOjUF_} zrcIupXs6NMJR1zaLGuM3H|ZQfUkw>DNGp7{+GedxB=u=7qH5WXG9TJL|r& z#ClwOiFIAG-mTeK%Bhn;v&w?id8tA(m7@Qy%jv7F@S=;YYsqF0cEEMaH2{`&GrLQM zQ+cEv>#+C~E8re&kAd2aJq}nU3bT+N=70&7B2PhT2lC_F6mxb!wuW zrMSm_y}G&m5jp2@-~gJ;@poA#i*ek{pjYG?c%e(-RGD?Dg#^ny1OtAr!=zT4#*`*Q zRD(nX=w*T>EqTLFNw^OSfo-vc$We2(W=_i(S`xC@sgt~Tz3fVW;(2Xck*boZa^oNA z(6E&qzpl{Z5RN;dmMfvmpSZU$2;q|)CBC_wCj%)*H}PpmurA<8B7QchFZuWbk~|dd z7W$GFqLM@*ApW!xGj(k$3y37BT*eJKGL$wEac-iHbnk8!m-*#|Lf-Ov_Q2@o`os00L)3*_7xOXChgCo=Se6!WK?tQ3~=hCC@|^MH8n&6{*D~ zn)?4C!5@{^@HmMu3$=b;>q-$WyDG~i;~z}N&je%`C?@WBb9)7i>FtLOLj;4PYz#?ij`Phk4@t=5kvW08o$P?TETHBj zCI_(b3z^BI3sPR+V~>qXOdViJZl&)i<+-S```T-)&WXp0YAK7a{#aAhq>&hlqE2yo zlmZyyzh*ZoK$<5d`IG}kpzxn=E|al`DUUu>LGi4>-Mf#lRq8b!+-$;w8~>pfE_bhgEmPgPb(dAK!tnZm;g5Cx?wg4~%ugLpAsZ{XF z;UNYtIb{Jj4`V44BMaiu;|H>uD3ZVfP_sdo{{m{hP?h9$hqE??6-XoVO}!4&$f|AM zzTM;aswjl7N>%=<`H{d*XgabqtSwpy-S8vY8QGhYq-;O{h#WlOR3t?XxNQFg5GkZ- zTrSdRCeCQYiIdXrBxP>tbdE8mc2fG;LMyFKt|y7<~Y7(8&xbsy%#S=tw8!MwSlU1jc=JW(DwA&R=g70^HkO9urJ zwpU{7M%`Ok&X1GrxE0;3!Lhi)lO2|tf9M%b%qqoM1*QO3)b=7d!`p!ou%4uZlN*TO zHIQXzOGD{mWg0bBNGgsEDS-7=C2^7@j1nqlpHyEtS@cUL$Oe{01VD-ZtgBJTt|RTF zPF<!vsxiAAXDI$l2#gADIQskbzDVV+F1WyN~hXWIzwS6FE>+Y zB9?0e0(c|ejnLpcGDB|i{jpMf(2k5UliFH`J@UHz;{msZxMQ44F^sHKe_sGLwrOWnR{Ya7*nhz%K1kEra2&$O7W>D zPwQ%Ve;a3&A01+iHOMDxKz$mPqdVwcR6W3iNXfZUobm|glrmzlz>Xk*OD?*=w#l-c zSiRI%FH>aIQf)-GXr?V+G{a6?IK!6Bn`%quPO;?+rrXl_Q*GJ&Y5tqzQk_pMnl;g~ zmdu%KiBslGvdX6@<2b_HScFEkye&igr7S5Vr3lv1aHE!U1V&TjQmQAjDZ)f3* z@s_tp_1N+?IRBMM%bou?E~;f*m??)A}@_p0_rP`T`DBlS1R%bep{ z`8T*e!q3IJ6?8B4s85-?2`=V_nxl2+s8p*7s#T`_&}M9(Hb-08zl^Yo?@zGmw$P5a zvA^3-8rPSXRPXKI=`w?Vg}x1#W$HWLTRP|BTG=439dBdCjL?paulW+1SyRW`jLBmx zF>S&qJ8|;Z;Wl~PaK)Ywi!#JxOC~4|WxV1_#*ZBAaVKMkE7l|#gF>0u5#mocQjcpK z$Bj@~*NHb7JydZkDie1yQhy%5q8Jw9QHW1TaH2eSh1wxnW%{_G0f-7)az9)RCxn@X z@}z6!$fuupSUb#)vDH!%RxX$*7t0hodtF$CL`;*LZZ+u0aFBS8fFKeyhmU}X%m-Jl zB_l|JLIu=|OmIbzaW39XYbB^PO8FEbqTQVcji7p(I;KGBf}Jiw9RnzX;O&IBH#fzI zQJ%v-Ci(T1tZ{5htFf-LRa@7|CLG*gi{8Azj@w$Kgm z&QZ4J(NCor|sJ#;!I|_f2|cgVos3#ZGzqLhF9(3@g5Ofo=KzMr&~K zAYI#Nt3JBij^EbHPJQoEoA&1tZ)4+E*IJ)F3#{qoBdp|`>#WIT!>r$fOYDAo(_Z=U zT~X84mVbQ6fdpk|`tco1H&_Mc(rC7ceFr>&D<);!vyn<-Qa$+eem8HzWeKxOG?Fzd zo0z=Dt^&yRRfAK65)gO?pM?j*YU@grA%XyI$~hP@Aqe&L7r8dqs0&x#l&_bqT1Rie zFSv5Nn=j!l@e=uU5wgcm?&28DO&}DmjKC zYtVKP{#a*}68?atU`WRSF1!vHZ^+Dh_s!SZ9XIZ>+pfP#ndq%whgMh$m#^9Zk<#b_jXH;;{CA*52}U~&s&g==236>}#b z6yY(fPi9k7wq32OO-_%me6;O4=OWvyZR%R(H?+rZyW1|?v{n0}wXoM7f6`_Q8*9S~ z`)YI41KPbzo7K)*U{Bw($LeUa)?H_xZ`YrHvC7BU{yXlnMdPLXYb(1iU-^p_E2!n# zb1zcTut&7BSra?7=K;I<;!CZwl-LiRea_a-TclmkitXbUUa*l0TxfP;1AF|Q2W6qo{MTCRSG8jMeAyBP+5Sxr20-ea24 zRNWRL`v)dlMTR!8O3ZUN`0GquckBwR780@Y8s8xmQ~pU_s5%IQnlN`VTR<_v&civb zQ5kAddg*3#7G+piQYqz*BadO3GP%lpS6!L!6j)WAWA)^+&9JBi3yY%@1z5^2=w!fw z23{FbY5o1PcVuza=F0!kPQkzH&wjP*uH5cf^E4JG! z&pqX)-u-(YQr^?+JsId5FF&U&C_|JDY^c5d(jm8ouGK1n{aRKBKCa(&g?{}rb$vG2clU*QymcC|d6e|_~i_gNp>|EN81_bu*?`1FG}wCsAL`>((M>O*CM zp6)w%KnM`n!`uqnJvb%Rm-9W*2?r(RJm(Oo1`g=w+rwNY@9LSG6E1nu7w|a(x3J8h z9H%URSy%vFRj!D7jD-$I64*oKaa}}5e$$SJ+vs`%-$5>jrN9+Oswks-(rbF`gnn_> z<0rUZSdR`a&WToio5jWp>y)|oek}pVV+foaXS~Rit zt(pn=b&@6<6zZf+P>7{_cns_o-z7qM_pV*+%MV_&FW!C863_3u&&s^~)I+xZ^ktGU zLTV5vi{!6fLyz5Ki9>tuv2qiY%ZcofnYH6xrKxgNs<=R= zeo5h0gfiydE`Ti&Uqt zC_UpLA(}+DKWT;3PNjQg+hqIiPks-S5iuTO;4@L9%vaP!yXDoZgH`AHx!lLJKn;7buQI0yyYV5a(!3 zqRovwxs6q;fk;+8(QL?-TQc+2gi`E^uYpw6@SwsBq_TXDyXq=}gEh$@RNquPgkt?6 z@5iUXAeFLT*LwEAqqcsDY}TjE@`X!8`)pl3-+C2v@B+9fW&n~m^5M++V<_%a+|R@J-R*4X2_?V3^uqJB z`nRp%^Rz60J$0aN8B(c^yw{PtVUaXs(b4dZ!Avl>fGTRQo#l;SAg9H#Hg0#CY z6Sm%V#=9|WtVV7v&dBrzu=qTY6^N?kyD{|wHm!vt;6LcKPv zTWc?paZZ=IDD#B8GoFAqGXNO)yKZkG~3eZZwGiuv6g_c*8_<@FFRQY8O7b&+jY#;TNkb zu0>D^Z^~#gVg6WR)jlfFpHlq)SZL}QqN$r!1e$urGHv*`W`XtTp-c%$0P``-%eY4h zoku6rkqkN!VsmCp^<3LC6=cewkjSpVN!qpP*jipM!MkN~hsy#LX|uRjkuSv~i_19O zGgYqpo;?c0B*L}?)CQyu*Q`{@8%Um0qh6{QsV>aSsjiNV8X*=0F(Ae&Fu+cy#rc8| zh&ciXIvZ5y!FQMfFkET}!6L}#w8A;+xHC)lK>>LpeampuF4t+3IzW>iqX)yZ55hE4 zz*DE`Johk7qO~dX7OnW#DR&agUrLS(s!63P`3|kMV(Ptj-t@(nkeU?5MNsv~a44=~ z@$efa;adFZcgaYYcN}oMAM73_D)?vQ2^58Ow{+!ZQl}7gd%f{qh=lp(A68ovJ4C`r zq)G}2Q3ZoOC%C;zQ}s>JfkS>*zu(N0jKpY|sD2IYpBW94bYM$y@)Wi%0K}k%Dr}t9 zzGWlp*0HsAo|S7(YYVz{Y@;En=hQ9?iT1qEZ~#`00M$D&xB~TS)W{J|H%aJpjg+d% z6UK^t1@ENStPEBo_$UK%9H)yH&bRq1H^7{U%81$0x>lxmkRh)E zRCPT-1;k-(Js|UUaoGEvTJsVB0*C-BfN(k{xfI#dft#!YQ2qWRfhUxZyLblA0!|VB z5n8~MI<)E#PficM|9|1h#Z)h;Mrkw6kfHi+srgd?gs2PrcGmbmhkz^HN1mF(hCF)*oCi z0L5vdKoKSA(y(-Zl>=Z5JK&{$lox$|3zni~b*vmMQwx|u`QlxXI=T|xm0M6?nsCBgj5ay z*3 N4S05t>bv^{ACG&m7|)c5ov z63R0$s1Q?J_ATyZCrb1J#c^6wH;rC!NMD`4;xw6ehIq0@G?Xr# zI|{w*8m_C7jQW zSo8`xuw##Ib>1xdR7mUK_=3hI1AJIKs(o>ZDojU^rM#1so_^v_T9lP`3b8l~X_2Tx zMwt+11`K>b>B86ZvE}2WN8(2VxcGvzl?!{NCn-itf_EpukOG#&Qyha?(L-wNXj$4X zJnt-9DJx5R1(1`W_WuG_Db3tre^?DLh@?7;wvlss-GoGkt9We`To?8E|B&5rr|jEE2bnv&L60*KpUk zbZvEMDOIIPNaZ=wR|PJeJx2K&CdebHoeul-5cq0oRG7WN3W}VOVzG2%1;p_#ojcis zcip0}V|J>T@4Jeewq$`)&Ua2}%Z@=G!U_xz210a`J-6Q|U1g?joo}bf&aq5M72CFK z<~CBl#iL_W1Ir*M2R9r;Dhc?Fb0Sz*MT~5m;icoS1H&}Q6C70$7^O*`zgrfq`g6-f z5T*db?I~Mp3Wkx?39i(1!g)e`U+0uAPDUaZz54Knu&=}ZNA9;DzyH*}`Scy_+Hj+- z*>STqKJ`XBe%d8=!t_h5?%XS^|Ji@C?N?r!F4;jd|P&%C*_!+OJ7K=70q+B;+J zc%^_OZO9lqWBDAVO;R>l(Z7846~qM+A0P;CP4ibk$nuE~-gw?#Jh<2Qntx8)yS=RP zRIOy-6?}Z18CJr=Gf~zMHmf?MZ8XR%NA-h`-LFS>a|=)$Lg>?Byj9|qc$er9q7>9A z8tvoJg{~@T_ysK_!Vk(8Ic~f=f{ds7i{>(5)Z|Kh7YC*ujvB{28qqgewC3f2Kh5DOs%ZMmizQB*CD#B>Z$|a&83l;P+Q~A^9DnacW1?0_Al3Ef5 z&y}`_5q736*7Ze19qIZ~T|aHv0;LR?=GPY}@`!7vsO~()4K399g^D=Z#D%;iid|Zw zUj#ycOupoZnl<<3#wGZOgv9KToX>afD@Q`K>eZ@-6>pN*Jf(wB$;UdYq>xRg!WJ|X zwJjC-iXg+Ls_dBj%Xfd%3i$VZN2_0c_(WMbx1~rVP;-D*;HB_7{`~dd>>ppgXFq=N zt{;E-_9Jc47s%z?pZ11l*vRVM9~$65-_114bqnTdUApI@GX0ZJ^It-ohVE`?>r|K{I*9Cr>t)Q?Hoquc#IrmaQ{Y<46@>JjhPd z|I`N9U)u9e-fwH}kpXbGS^ewGPSRgp{WZDaKX%vSPuo2=U!_p7iM9h^o_0#0ih6t3 zPcne%lR;lMd-gP2zhRZFTC?0v6WC4>$mRk?1SK#V=I5z5ZR#kS%HNbxmf%Fi$&-~KXQCpLbk{`HoIQPlrh}rA6jd=n zf8)muv2pqvJ9dyI#*H0p3C@(G#OX=8t+UdU93vMW_{8)iWp^L@HOn=kT_8oZhYlI6 zgyY`_Y&O}U1f1o|mshpqRt6F_V^}z_EJZbi&P>Y5h&c7X-<9#`yWs0q z|L@)zcJ7Yj%s7J6_#5qKtdj1!e_TlpQwi(jWnZBr$jqczm!k`djuXd#h$l#bbU2o? zQgvJ#2a`@zRR;ycG3nOFv@@OiBRM^cn^$nlD)>zbmb`gHB2RLx3MsCw`>UPcAE-;b z9!)zHcl{(ui`4`yi1ROMp(UC6{;52X&+Wg@R^0Wv)eAdoxc;kYWojzT+Y$QX z3?~wzTvi4dua+P~I3&<1L59z&rL($zgym410+lyYD2oM!Uw+ohv{};~{0b;LM*IBf z6>HY4x!<8j9-B3*Rw|d@&&I|jP8KU(arqU#sj2gLUcpsTLWMH-n-9SlPC&FcE;E*` zj(aEWyy;rsZ=0>VAHMfiCGNP#!9ySUU1>U3hCod=pL|$LrP*{c@zCA3TG_q#-=#e? zM!LKj;T8wlTS!qwNE*HDWa&su8;Ej)AcK2kEhc*c;x=bw_khyXrdXY9T%VH3@2ib zzKEI&?RV|kNqO=v@&r6ZlHZF8x>ye#dlq)_a#8m#mf&Prl0I`K)+p@O$qKt_cepMc zEK#6BwH`V{8yw^PUe@geszuF0rEntcKfA7RQ#ZMRIZrvkkDO3bwoA_NBbVJIVUb`G zLMPG)?+*LfZ#ZL(I);C7Kl`u0{K!82_^*mGhPU5-#lFxL_PD89rLts1 zGKfj>)wIK&1JK|`bP7;PfRD1+h5!dY7)E#u;GuQ`)R#s5J6?YbR3s*;HW=O9IHXWE zu24H{i_UXhe&DntRAew|D^cZ0DrqG)$&0|QVWOZib*FF7i+sslCuJ~uYJ;Z3G3-*S zwwMvCrxB-#zV$JW1GYTEfu1~iFj_VM;w5~V)emIzk5z8Ij0v*#^waF}OE1uV!ROg_ zZQ8VB`=vHu&=5OLVR&Hpye)*+8yGI69Irzepw#4#o2FJB1HJq#H%y?AruHb1QRibA)@aUlm?hM!Ec*IYL zqdcZ^q8D-Pc;dt=l%V9nA4$|)GBXF~bPZZET=pP#+{myu9>|s9dov3$*RNSA#A;!) z{m0G&yg3J+xZU>LeTn_{@8o__m0x&%znrKmY~Pc2+BLf`5$vn^6o@u(Hh7_r84+^x zF!;XHWLBew(*Agl9LA8bbVO4*D_{S)Jt+&QIT7-q%yONAo4m9+R2CE*9c2MUeo_#C zdhvx3pMHNiKt!zwiSXE9;mJg4ptOWV)t5KfDJ|;1iw8CuuzQhqm>AY)Aql=2}>2&oNZS!!>k;Z*_?SfR?8exgV3Nw0~P0P%G(z>qLCu z`qe80%b)d^q^sG_KXbo5`j9qa0IwC_c>T}z@S```ufP3Z_lk*EuU<9KQkOu5Ora~1 zoHHSPS^P?K_AD^r$Z;hjlXNl~-j9I9(Re1O{0^s*xsH?!1ah|%uv%Q{^AR?MOcrQpG zIOIwE_D<1A_-N5cHfOydewCp_0V2y4|Kh5YILp-_kJhoXw{4X|GRbilc{(h`H_H;@ zh#ucjkozUoTR{uk}V7yfK7KL4D(^y2f{yZtV^|K6MI1^rHNq2g0dK5ow` zj_VcevvDc~F8GjqxW8_=iN5Gs!T-yd`o ziitayvS{{;{^0Zy-u3Us>#nx)<;u$l6-@2kb$JAI2BTUa8g*oZr_+MUK-am%NkQF= zRVTPYKyJp8G_Gec1Zg_!SWFEK$o~WArmLp_?oX#F^&sZYq~;C?bdn1oueV~4c3*R~ zU47-{+M0Z`jnsOo$zw;@+U1Kp9qRJMbCgSXjJ0af%q}`>gOlIE{d?P)XRLJAxoEbQ z1}LRjjgbI zH~W(kFE?!_YN`%`_Ks$wLPv1S^+pa0d4q)L=BnSIb7wnA!JCdOc%(E{%{gH%gjhmD z1@$U1e5kPuHTCsZSNBsL6{WTUyLdnD1lx|{fw ze*HmU=Dw=Zr?x;hrcaq@`ybh3dmp&d9((X^d*V;`*b@)mYfn6KpFOenetY7v2ke08 z>KW@+xgnK)a}Kx-$||Af-s=ZJ)3(^ zcB-n6j#QPl7(OoI9`3Gi(6i3mtbO8E$jdZKF2C+_c53^;qV7)OP-VMI`GvR)=+o0@ z6gh+Y^eXh3*h5Ndcd4L&rB6>S>h09t#%uK<=$timto1LJyG+U`p_FtiAI?nK3hHF& ztZPS6BB67p6dI{(z+?b3*CTa}6Pw5KDe;r|JpZkucU0HRGqEQ0m6zBo8~ml(gqb0s z^-@wnlD48QwGxeO-KDb?KKHWq{`wp1^636lIxx`2XJpdID1|yYB}WuI_N4Xx=36Ux z;V*WgW)u1j3F3I`c(2E8GEt%6Qoe{|?|SFG{=A~UerR~A89om6IVHWQ=z=@Yi{tYJecDz7oDO2WKUW>Zf)(6{va1>14-i(kQf!=`p5Ze)0b30km`&2zI!Z#NuE>Tw@ynrC29!t6PA?_zS1F61?$ylV zK3AHu=s)k@GCm@VpZ+L2&>WcYnPD8bBR8Nf?R!tjX%60ClG4n9TC%fXH!(739~7|! zI61I3QOX8l0M1YOMaN|x>+_H=gCj#Jb@k4?R|(I`0()LM8uq{`#)5cw%Df|A3l#(e zOd(!5MJy zUs~J@#wAynay?h9LXcQd&`Rt+6?Rmig}4aT&=}PgB8x;E0i@s(qm7)CX!{ujxTS)W z%7VIRA4L@nS=5q=uHZ|#!yIkt7)vN$mj2u1-{`Oil!?CclH|Q4ebX6wC*mMkPiI0s zdV}jJ-jW=F(g>oK_hL%>=1g7Phd6?0f z4EdLlZE%#iVG9nz!<}S7pu$2a87z-G_Bbn#hDLt|)Fw?(sveC+PV{-_)VdFFP2WUS z3H;JRs@LN;Yj#KJAdZ+Hb(R<64cjXQqGQMQfr@L6M9jwBhFfW25?FN1`W}PXEd@^i z8>8ivHi@5*QV{F$nYl3FS=Yy*J| zqGonv*50|<^bj8xe#OsqSo$gNi!h7%c9*1*dQ2vF4g!6c1T^XQCgBUPAuS>kTj0WO zxTgR(y-pTQZ{@y}Zn>!3}2Y7$oepYZvJS8q!rXxT^vy*%FM!WvpoiJBUZnNXmQzIO8{; z7dQhfg;_}VGBaJ@s}R(pWap@Uq?vR^9EfyZawdnLOjS4P@tg_(4-sp$h^I@CNlScm z7`Y}Sh&k$VSdSK*M><2HOoU&Al`qQ420}n@6G&46wh%PTnM~-RF>L~SUf)5;jd@Vj z($vzobJ&+9J^W0^QZ^sL7dcKmxj^Pu$FFA|rpvlRcS%hW`=qZUlja2N1*%HP@!~v` zJ2(TC3?LMLgEu>QV1#6Y*MLw;d14&KK~hTIPBV@_w`fFy>MWGj-AYxKVPIf}DhJ;v zr7s|DKKwdG8(m10xTrl8z@5{27LjYqmR;l9Y;pJ#zPTcJHlMyXD@E-A;gbRR>)1v*W9W^O5c)`Dum!1zrG< z(@VWUyxTjt5+BYP-i_JLbG(M$Ilp$kLk`KYUE4NcRRbUHTaz@G7Ur^`YhyYaL_Ibp z@IN) zV@G8IG|X8jIVs=X)w0{!(zHhi$QY?n#5pA!1@?_Hq3LK{%5KdoY5B}0Fe6BH6$&Ery^p53gUesEh~-NrG& z{T01|UNoY8=5@ADQ8yc^2Q5@|D1mh`+)ccBAF^SZUOG5@h#B2%N)%jY_6|!$)Nm=& zQbX4`EUU#%;zloL937~UU}{L?12XF!26J~pr`n2xkZjY*DU(!xaoGJmeay1C&A*2B z%K>d}Kz4+;u04IZWXX2^JH?zGna-xYp|TJ+fPF+CC#|UoQYI5`X8NA>Z)tk*eE49LWMccdkyJZdTUl;QIYh2M_L-@)B%8XQH>12c5`%n83s8AJ}sU zT}y2j%z$U1s<@p|iG&4E!3|Euw9+b}`lcl+$@Ez|8vz^ksbipGU8X27O(zNti3rm= zHQ(F-m;r}V7R=S&S{rSvvbAhh<`veFjUJ)kKn)4-%NP8H59+7np9;R8G+KOOf?VyV z*^H@^oS92|FA`@lTW+K6I1VLgMm##HOi859 z+}%bLuRBpa2IQVBcOpGYU>aS7s_&nvuB2c2)V3`eTg$`&J5lQ=@~<+hqY(AF8~$vy zj;iV0%n>WbPW?zwaeDZd`8Q^BiJo(C9TNfg|2jJlcq@x@-LKu~pdcU+rPz-m(u;KI zz4wj<8}_bf)}~4oyC(L6T>+08lYkA;pvK-sjj?O2$w@iM+~@zynzh#6l5_68{C=Bn z*7r@HXWlmN%y`PFUB$-CV!oeJQ3;Gc0|x36Fx7`zJNrSKZ~cb)kVA^1dF5ooFhs zCKauNIPPk7JR|8;TDf}U5F|L}-S4+=l{d#<^!G#f(`Rpo%^PnEhxI-*?0JyR8PMNe zZFS^L_XESUd85O_n{El$UA8Q|vi;GpLC0R!t5-i9cifRm8+0_!GDJvVSW9QmFiIHMO=!#lK(Cm@mGIn(A`mY>MA{Yc4^R}M;g^)fHDnKv z$S=$1MsM`6GvQ?pLYkE#`Zh(2Me5M12u^B#vDn%H6w@`^w`k7*`*{BAi}3M>FNY0x zUK?6<)|yB+k%~z0*!|r2`YziN|@q5=DDWV|QnkrXQ!%Vjg@Y;z~C-OdB2TxCs zp2FgiP4${;6l5l@`=51&L6hA>%Z2xZ{j_VS818%I;BGQq4em5F=903?Ze*Mu~ zb`t#CSMP;S-ju8AyDvNz8omAe*6{u-+wAsPzkYp->kvvbB(U}F%g=@%KYK5Hr%iib z|KSaVcZPK<7R%*xHxHw&qAH=4;I2ubW9zX9Fu++PbT0*A%i-EEC{;0D(Ket$66Oxn zN!AJxs3cHHD3kx_1(asIYbn*CNn>px(^5V4#P&uVXeCcnj$WKCwfgs=xdf5DuMghP z*(&=&Xt8Is`v6Y{9U+Ek%5TD?*8*1au$WLuT+?c|>h@J0+9vdIBFA00|K$EGl z2naF+@C4BIB@wt0uzPKKSm}0#UOK32Z^;^@vqE8bYhoyEF$du6@PqWO$IZ8eBi?&g zK2$G-)*77_@+OIkd(jsvQS+ippC9YbDuKCvZl))=Kl9ilaWAK~ckg_AN7!)3wV`=C zarQ1EKSKN7dhT{mqtI)3XB{W}i*V)Yi^B8T%6NmWwS}H9STNu89Jg`+&zkxdpMDgk zPoCf-e82qck746I8+5|uxNyg9H)#|0N%jQfIFaA}`r+{At1tREFNTUnAZow=`U~Ne z9Z!V2Z@W(0AukKpUv-Hl*d^h*E7z&qOT%fpsb$inN!l$tO}l7kXy@$Iu;7?u!joHn z2%}D5)#y#Idi7paHG^j9bfp|lfMzS*b?9e z2#8+U)(~;)&+J*V!jZZUrt-)m=ZEZ(^XJD1_7wS=tY* z3oR&XH)?vB&J$h#;PYY5FP{&yZ+asfbI*t2n5%UzsIH-8lNvyV{zCUg>wcLzbLKb) zGRV&4KSG(J(99X3GXKt@Qi`0bge1<=!tR84L&Wjp$A@2Dt8<>O|AloQCP}kBi)HJm z1fmSu%deW36kd9O22>i+BGpDU+5?tw*cVnm{GbQ{);cKXlyek)BIrfWj> zV~=dqiNGJpxc`3m{;NNP4|cv1&N~0(&|)9iFIqPX2em&iELnMhgta@vpS0@!!RtG; zpZ@)DwKhQN4r6a3edOWImY*R`$O~V8`B`}P?bjt^e;hW*p9#C+Xr6g%+N;Ff2Jqze@Ra{PD+2 z-ajs631m(<;e>E8-|C!y{`ujG%P$XCU3N)0UiS`RqlXydJ#fz1XNMIlR)o_|J3Wxc zT2eUg6LnkBa;HB{NIh51$ZM8mW#GLb+;j6)I@@snyhJr-%;<3O#TSP~ix!2eNzs_v zo_fkDn&-#LuVj%fa9rhExag6@?K|YSy%jR84Rq+yBMg4#g)rjNPeXqlnR$SQ8`+2h zF7D;wikHAg(U#jyuI_hR&5(qKn9fK<5?l>CgO(@GqGx$9o18}jD6;XswT zpT+^(0+Jaej+ITe7%zFNTjTLDN``JfT(?q=8a_0P)c)a-dJfSIcR-4vJwSKm zWXFvj6?PvwcwiVdWN;WZcu?q~0e}<1uiYqqPupdCXlrbDHK)77hl-jpg;Lxlz_DIRMb)`sZ|TxydJZ<-Lm)l(+;hVjXPjYr zL`q~dZ$e*9*-{SUiCdCQb^a2W@g_^a+w$2*#3{6WL{2fUop#!3;kH|D(n+!dyoNwC z*R5UaqN&2=r1a`>V?yN0T4hfSNq6~au_8$=FS+Crz3UmqjvX28R>ioJYK6;u$L`%j zMe}57Ds`{0$u+I(IwVMrL|#8SX}P=r@cl z*g4>poNkX!H9)&PmM>rK{sTkATgNff6&yOujSI1N#c`EabR1KZdhkKO!-=+>YByM5 z8X$D96==ATkG?re?SjkESLh8_khu=}Q+3D`(%4Z$#wVi8)`8V0pLDWqNl$OX=y_Pd znWz!&rb!b6GRd}NZYZNl{4G~OfhB+8qsnWGEGI5z`@5O|h!)chdtK6~ygQN5Vo6#2 z@L>Is!e_zNuq&NnR`>1@W83QU;1U8DW5cQjp=8lOKjU|bWklH^Qi~ zoYvH$e-TTI~(}W8Qp3CU;+6*Kx<`PHBWQ3-P zg`RWHIj$SuSzoE_)TvV_>7>ynkR{+(8A40^5&pygO7U(NN(e!qdbAm$et%srE*YCTmZto88lZJey#zS`3SWbnG6wy`O4@1ffBVA+RDoNzeXk**tV7R% z?l3$u=q`_Msr`F9bq(!@Ngi)6mKk7>NGd@}18lJo8$p!A?-G8M@V;F;`bzgaRri2(ueeNwSe^U#}b| zZIlt{ytY|0ArI#wu3~Rqtd8HXQos@^R5VOytv|9X z$<-&0A+W(R38OnCYKORm@XEFs5|I-=B^*?Qkr38`4Gudhavvqav<*OrfUXj4*Zl|q zFw#1MZ};}Sh8mW5=G#7?9%Uvo{6O$9LGZAlv%+D+X6sK+A@R^Iy#nG{yF()gJ%URZ zOZo9C8{v4oC=l{~kM3Q=)G4~1@SJl^6dACk;I1;_PLwrE$f>iO{VJa%9aKsc$+*{-C>8x;g7u`m4wuP%zAO_8hkudB$5-XgGm9gKJFJ9i81hRzJ_hRll3p#=!SQWzM<&%V8wP*~NJ%niQ2sh6@LTwiKbe6p0|Ifu@vZp(T_{A}6oIFGM)72u7#qz7RC+gi)&W zQ;c?&EYGQy+-5L)=5%chAE&YCtGUAhZZ|tMca_9xVk{0nX7os3ZZ$!R$K%EIjdoX{ zNow~IYByAr(+b~z|7{J$dEunv=7a_Fw543?f zT<>`|N8wYBouyL|r~7wy`os~T_RPtnbRFf0FiTIuG4*I&RXHlm&~H+6dub(+8cd%w zB21q&QeSkVAt@D}rMwAGoiI#)!^3R-KIy1wren~yc%bXYz(*+lo!4*b!45G%o}vQ&e~ocY&{2vs!s{kT{um`##2# zVQe~D;HbJ`OegS?rzw|V2Us<$fN0ycapD-pk=#P%Y7?&tghjmJS5b`VX9`FhSFWKO zCAE_7oGE$;jK|3o1DS>F_L9=e%~<_W@Wq4r3%-ydRIIUr@z^n=VguY%DnQ<8=7QiE zGp2e49U{$)T+D2%O)CgQ(k*VKFK{n-d*1v4=SNVi7YQju6gN=)nfn*~I?)m^zIeq^ z&x2(3j~gh^b;vV|W0)L_@dJ(P>0^fWtM2%*rCvkXs@tfu=rE9ru^!oRn|6{1*{T2e z{U_nW*S8y)t7Z-kzdl>C-NR?j3N7zCZhSa${1M^y>n;h`uFZxIU)%1b8P2jh?$~Il zW@&~+5~Rw-KffSM7&|H)bL716&DUS};=7k#*rC1O{lZ-vZVAsk{aE<%hi~O4LeE~;^gQAMS7eu2Fw%1aEI&GouR{IU(!|K z!-fyjrkAcZwGamls0wtg34x`tLd2z)t~VjWm>9*<2;IEeWB8T=0SG@8kZ|7?H?nw= z6@naLsh+ZJbX1&eWlktGnh&TMH3b-1vVj=h7VrW05gA&4DKG*q4pNH>1eJeb0`_*Cf z>|x=-)24?9PMH=qo;p3;dHlq1+|(iA;tNj=Yqa+G`Fk&VSsjXhM1`$P-6r&-2M;KtB$ zc>f`xTfd>9vYW0T-L1R+>!CMQu^nNC&@o;|;*QsJ8Yg-LP2$c;jFM>{NKDI-Jk#Sy zp!$WM|NQ5+JhGlsEa6&@H=t`oKqDk{2%TkwVPZKX0ni=_z5`Q;(S{Cp{wB2cRO>()I`H&}X~RiRvbZ z+UE(%Yw8;*Y@*}nXn9Br&geHNwfKXurh~^G`Q$yGln3#d3NAW5ogk3ME@ZjEu4DL3NH<6D0dc0BvEj*~w@X9TYH`SAFRTy^<6NysOM zCm#DvxI(KWCu?1f6UnaB;T9;6NE?`xxYP`IW-<6QnlN6#)gM>o@RqZ}6ON$ygn=4^ zx!~xd!UY#xVC4nYiV}n71Pui!CR^s~_4t`a7m%~EUsa8ZJOS#R5MkJsk+Q3-28h4V z`DK_3vMk1w6FTp_bHh#r46{Ex7H?MjinPDVa!ji8^&yLQ!b@opXRqtyWGf}ncvz%WC? z2%lu)q!wK$u)`%+cYZi!Le*cqynxX3itb22P2NIRQ68 z8+gIg=gpfN&OZAb4<4c=u+BoQYjo_`$!#Dh4r&MN!N~p8N*f{H8)Ei18G> z+(g!<)^-x}1_;x#+bNtHZA>G6Jhj!@fT^__4R?WJV{!nUEColL$vI8}En#Z!Q*!h@ zA=~z|GWJ4&<(4huYI_zRrpASI$s;66+DUBT_|ARyi3byKkKx{|)$6a7!Z=%1JsrpE z=352psvaSj*q98Hr8l2=?9pN2aXME2_+w02X9+_sWUFWFuL2WOwLTIk1o~986IOh#z4f0nud0S*;o%Rc++Rkp|OZ3e8Yx_QDG<43*TQ ztg^DwOZ!YHiZ6)S26<8#5wWL8VPr&-hz;y0+hp71zMLG$36XZX+*`nKmSW36^nwKo zER!5_%rSu)_)8g9oT*ZKkreXNx+$T5hw&LRB#~?@NF+2Cs@;JDG#+>`^m$IM#kbt< zm2ZX*{DCO4VcIgT4lqGoTEYluAQDo8SlebmE-db;Der z9nXcHk8TOAG-&ueu{=XJA;nZhd2aneHf38tyt2>;oUzFbqcAvQNgi<-+S^Lsz&|q% zLm>D2@~ue|4sMO!^PrpJK)Q3R;1{`(6V^R60&+37GnD6$R_x-5Jy`vgELke746sEH ziDL=NoON&$z*d@YnT9u^VvK}KhA)ri^1d?nKEs=#4vO2Y>P>do%TWRcA%*6%Pwb=uVzY zNiLzKUeA?GGvJMQZRfx*zOxt9UM;wkGfMC zO4-z-IBUo9c11=ZzeXa+L0uThrKo5b`rd%B1q}lIKSP?ipMaEybn67^{{8!Vr15SX zF?@u@Zzdi^5xa++Kae>npWBOhN4TrpAIQ0nrdUD=Pe6@a4K7)(KoUjzgb@%Q1f|*( z#O$s#BS9M1y6TXox=E10gf~hv4IY81jpkFeDO0#hWVYuM^NOa?jdUNBrf=Uq20T@y zs(>GhQzYJPZ7Lcm)e>HT38}b?lE{s91W@M}nscBY^2%Fb5JB1?@?!8`x0gb*DYk2ufc zIFad^%me3J4aeM9#n>+gL^bJNelheI%b+{ECd#`+aFx{*=ox|!Rs$4BY6vVqs!`U2 z5T#KxC8v1f|#Wh24rBW|d*F429#}2ws5#eJK4Tq~ z9pbo@)I&olkqA(jZ`9k(zx0+a>LAiUnobh;@g>6{h;=kO1}VcZ!Rd;tA zu4P!3S#AcdtxRV%x&~;0#Fiu+7r~r4k9>@)4R8e%O4d>b$twhr1u|H}fv_2c*r3(>AcMvT`HT4qG_V2>m=1rSRG$=^%PjX?*o=~&)^I!2R} z*e@9UgjB)^42(W;5|T(qdh#JZO9Vd=jK_~3XZ@zS_Gf9MthY!kq_sl_yuYM=(vIDV zYnS?iISNkc6Qt)5Yr8&y#1{i_ ziA1qug|xgaVARh4rjO?Ol3SybYV@%w9M0${1+p56sp1-oV77qchAjn6_+A^~7C5kS z&2Qvk!nm088{%S#T9Pzc9dhfwa-*O_F>={(W!td*TD(#OD9WK>WQjVlN`Vj-kWZE%oY${vffXc78bVps zX)O5}c?}5hwV2ixiwdL$^RA6*HCZbw2;|NIutn*KpI!u^_QyKc_Bdr&xEuVAWKjsY@imu6A+`nT7slwD~8cuBcH~g zjUZ2XEG3DL?<9aO8E^a6u^E!-@WE-+sL|F^ynzy9Ht5O|$xJe>*J1L&EKQMlV?tX( zh(spKwFm)4V* zXIG2;B&;TM05i*}{ z9W?7aF9%@&l~P$)s0(;adPNJsu0=3Gg_ukt;0JWr5CV9u&ov`&rbX}Gz0GroQA~i- zG@-2j4aCGDKJx8Uu?TD=G{(y}1rUoy#l;umB6ees&)29SwLysK-Rp33P)aSH9%-`j zE=_XMOq0zMLmada0p2dSp2fcTJ6_mKr#Q4UA9B1BFJ|kb6Ud>NXzB_}z!eAp-gnZB z`=pwRxHU)n%6UfWEJ|b3WV0N+C2+zkL7ZJ5&Ez8-lRS_Ir_1v*GXt)YK3V;&mUVhnS;pQ8!4>w$QttjIus?tHClHClkzJ1`p z-3$*xQLmtm!RxT$*fVVum!1@T3b>Xew#AlYMt9heP=a9*VYC4u)5n<+}(Gm*d zK1QBev5+kQswvnd(pPxKok`XCeTwU4JJZS1^vc!&($~bU*HzNmmmj_*aQ->G_3|@e z<6SpDTRg^^-y$>GbX%H8rpJtqH@s~QZOl(bzK^hZ{q@&}XP8rX zTb9j<_}{XA-B)-dT^F?ryiya82nm5)T45-|k+7@057`6=CZZLUn&L=AnyU4w;`o!4 zt73+q02)~b6S3fMR0EWfA1DKD%v*W_YnOYWCjCJ@W~n|*dTLO>rO-?kjlg*76R=6D z{&Gir^Np9od+)vzc51ik``UTBbLYDb`>7qJJbC}Vz7uEXd+&uTfefK#4)HC%s~TF& z*Lpk2MR8;5s$t?k`pAPekJ{cV)+lbjwW@fU$-}NRs{I_nDDMk^80A+&89-WiXCi9` zAEDYQeDUF%g6fZk>Lx+8k2ngPAwm_aX&$Oq=AbH|Or9)P71Pk4K(z*GMvWR}jzxzq zl5)#Xcx5(^(-LsXsCZShgi&Bf3X5imUO;U)Q*E-C3Q-?CXpkpl0kW}sOcv_WNahESrSj+% zoP|6~tCur${@rvrJ1e)0TDL)3J%5Hspj#x=05 zna+Fu=HqvT(f1MRe_uT3;$-OPeydJ`enHijN@i-)Pi24ufA3IYfN~uBUj+BHE zwS@|r0a8vq^;CCx@er7LnUGY4shu3n=BpT~5DlosH1$})FQ*8iO{!yIo?HX+5?#(* zkA?>xzy3x4v)Ccs1iCmP(V!Lvnmcut(CgJ1V)^KaqF z0$VXWNe?`e?CDymL~LW!1yTsT&)260t(_tkg%B6vnN-J|E?Q9xPihaLWevv^sf-bZ zVgXu^VsLn!#~ulqS^%LK2PRs)EXVwahbC*4K2=7)3k8Muz!j#!1(fY~YliIOQegzD1wPFbL&(2*g7 zhlCX>iOnX_Kwct}5O2sR2NV<&&qUP81qrCwoZxP);tyx$BFzfU z2^JIT3LG^WPfXV`y!9cv;SU6 z!l^B-5u;>*3O+&0P?xU1MD9|Z<)DabdBSM);wpIJ)=VZCkU@?Xe{-zf1RNODB1C{1 zK+$2jOork*7j$UyLOl3i6{f;IU*=0KCJC)4*W>{M6{TdRh$$*RY7*iN+Emh++7|Vn z>+%x;6oSDb4s?idF*cycv+DUiyRJRM&pb?((u+NO7rF|!i4c-!)5E&hR@_w z^tZqMMQ5>G6;3>UL0;4Z3uz7zj(H<0PSGs{>({LbmtL~gKHOMtJS&RGFEdD|(24Ko z^nU|5Lq^7630XT^0tM3PkcsY6Dq1UF1O4Cyd?B_g`T&?B^Fen5#*>r4CPWlF8BTz` z<<*~Mr8`T=3oK0VgcP_w1?FX^mc_T*Yp+RbiG=CmIt?A^V|2huVLJyeg?kIS#joA}sDQCz*@xEuA5kGk-O%-VqE9s&sOLVo(?z z;D=DiW>|(4-Icfi*X|r@B*ZNbhEgct$`woHD*ca;l~xkUgKp2=^6Q73xAO&*BrvKX zJe$fr5bhw#t8JLOfEUm_`1mtp5Kw#-455-kOx@%R!x`9mOnp*!S(0#d@;+(IZ`i|lZ4k+xe|8u> zLK~peK+a8OPc2ns94Z0y0sUoqe(Q}_!{0?- zCyX0qNsv)DHcFs=B=N6OLVQCO%pRdFyCrN3Zbj^TB!?^nNVs@BC#fnICnh_9X^3VB znS#c$$bwg^YhONukF~XtA&pY!-ovg!Mnc=YnNZ-OSV@nxiD=1&Bk!SSvovSycc2% zH9Js}0a6>pHb1%+ErBp+!e0N2tHZB<^^j!<ym3}QufN)?Uy3|vuxTneLUVv#3^iP{$Bh}G-K4TFjvDSKlaJq{ zM-H=<+;ckD#dI}R^r@m6OxAH@MjE1{wCNY}7&&OWupHFcsDylnylA;Uudx@v2G{nH z1|DbI^(~|7Nc_0P)MHJ#HU)SX3+sxzRCN9=vGb+`9Tk&1Kf#50eaWG6h+M>WTn{x# z%tJU&$Y{+u;@qd7bZpq54W|=E$=yf`bk|?D+}BaFb?Ml7)5GZDULN_m(J6(Cb! zvO;qfc#F-qE?T`boC@)))F)5O6259CW{Y%)4-kI0eFhE+p~PRv&un-E@8HueD-~f=FP^n{#Xlj>ARja&-vlHvzzHrpQDogrlF3AowrM%?~7@J|`cc-;4NtOo5D2J}yvK zT9@xEcdwdN?i6kbdAQ7x6lBvJ!fBfymhi)LTu|E{5~_7lRVBw&)#}i5kS%YJ6goQj z{vcaUf}P1?{MZ>O-A5W+ zOc7;hVLf|BhiDpYSbMfLrgh|iaSQs4E{D2+;{nqKvlaU@bcX$Gll|5GljhQ ziq2aq(w6rWGE@qY8WBnO{-#l*M(b+Utl6!kq@+$JlPS?(ss1&rRjXG2#(OlrUUrrB67dt9;A5ivMx$UX>&F zEL)q&Nru+=akNE;L6gE^11E*{1GOn*(3H@=OAkAKFj9*ds!U$=@o9G;5rvO^5FFP@ zjo6OFfuLY0VPqX6UqXpkEbS$hAx{fYx)Ltpz=s1gAQtn9BrAn*W`|~aIBDTY;pn4} zc6pSWbc0bk)u6wGHLAD9r2>Lvl_(>-%^bt7mxOC9w%PVTq z0xqsVZekE4whH($VX%-?1!KO1=R*>`yRI!w}B33(UR8+KGuFNu}f>U2m+opBSzHXE{iN&)LK!Vm{kkm?E zy+|ckYdOslBi(+7bO@~uY9Cr3EIQCe|CP5nxKr5okd9^~#-8exWdutB*#QS18rpQx z3RY|VSKhkokkI;oL%_JF9x*D3>jf?!^hp-HVe$Irn{EtG{pJyQLdfGmGyJsEPPH(BX?yS z=`}em=0^n~O2;P&9}X|W2?NH3y`Oxvehuup5f^(37jYJn78JPeGkIE3kWmzm@e>hP zqe&;6;QX+HcXiRPaWJTqcin6q2{CWh4BH+c;y7b5?2rZ`+h}{i1&gAG z$x1>c7hV_*s23BV7AFEPTzI1KXvYn;fuSBEqb>p-CB>zXQ?)FBlNrfYlT#`6qy#K{ zmClVfi}WUyjal{@or}EjfqT76lsc|p5vSrn3CIj}bCCeH(V{Ce)Mg1DiUOf8WiZ+( zlEje8l^%q8_3F;ixc-Z=HMMY(7*V+}(@PawtfL4$wpZ~+4gI{lynNqPAN0`t-}f=+iEhWO3U1&|s8)jahiH&Vm_X zw+I%g!9KHegwB>2G-+NK{foE5m|wmVM(c0P4ex}Zvro~5bmAc_3ucME+vw38wK2w0 zZ%WRwRj_9?alGwtC!j+y8qvG#0_O-9mJ+j*wZ56b3B{ojLadc9<9!9f5aKI`d2kjw zR!eMIF1sdz2xYt6k)!Mqh2V~Y3{KoZ_H2aUqXw{BiBwPg=HYPl6_@znj4Xwy+({O_ zDhZTM(yJK?Tz zt3#c=rmPArrmP7EO5L9si{oD{s(8r32ZhO_ z2kRaa9f{X?4?8a7s*q$v-_f8VnuRii6`TwtcUc^CAJ$J474;WW3-y8ye)Q&xz6AhO zCA+S-M2bN$x>>4F$~6-Nc=}CCz7e0pW4T1M*`7^QsohPzU>=mtE(K~sPfe5E_tjTk z3MZa$tjrr7gzk}AL+)aM7X;B{?1Ww963AH~IJ>rM%V~;H^}rm2;9@GpFc#At%4^y3 zM+6e%r%eBvYODTdiKsYoDalBmB$4F>P&h(~WU?Pbnf8hJfikJv{#gKFK?F9YS^#QB zhbNasz53c4q1*9ShrK3W99mCXt-n>F_0(0N<+L@S-K^zi6nivk1H zkHfLLxZud!-wQ`>*clew`;n;B{LpB(dhW!%_ih=dNrqu`eQMCb0JpDfLjC*p@f1XA zXr}@3RLoyn#t`{>oN8C*_%gnl?8V)GKh#5=0V)}kI$<+YhnjCMqt{%niH(xq+kP(DaAG!m4a zvhcX@!uGA<_+#eVmxpm>YE#iOPB}3=uRDnl>#++NukhrC8X8#*|;_l ziuJs4$L5cAPDrUG3*mAKGDfj+QH0=W2$m63QBqpcKvnu9NmDGI5nbs`L2PlZ z%9*Bup#fm%)mKBWh1Y~O(?o<0n7JnGalp*gVZWJcL#MebbPZX1Evti|IKd&UtQvgy z*2`hXZ|)6GKYWM&?hG$%xj)RGKEWi2dcxo_STMD{6C=YZ84gwKvrij4$X&5+Rk;0z zYi*@LKP?R08i-OIbXN%d@Iie-@9yyedd|Z@q#}PhI-{%g2%Upp@3BQ)eQT&d)-};SD4ut`Mgtm!*2r z{n~zW$2#F8QzF!F&zDn@;&_sk&|Uegn^8L^_Xlsi5;kty7;e7pws6~q4dK??Z})S< z9e0KsZ@eKK-nEnG1nnn3CNQf$e|+~9-NgA$_)1q4effvi!*{x^;}W%;ITNYr0bwyD zHG}@7Tjll-wP-F^3B3EtbK$k;p3<^2hsd!_023m_(N7XksJuOz~z z$(<24itrR~mXm8HUs&ywReG8pXwUB--_ZqcpS%^m*3n6S(qHADgn;_r>c*;L=Fjok z3mK7$4nlGHL~!AZynlZGY53O*7D zK+dw7_@0)hx)7;bUOwnOGAB2psznq z*}7>yafV3Hy#(Z5y?TWE@4rhL_!8|87X=Ztp3|L$>(?x|uIpugbT<7_Af-b{e5YnS z@SoSM5yUyh3|Mkf*f?FCYS^k9B4vuGsWRF{Bi&7sEsJ~{jnT3t_M?ab(xNvG*P;cJ zg}T#5s3KgbIKS$`DYQi9wc|bLB|^|B_YO@j085N!L#ZsU169&rDAk{Gs<(OMSCWnQ zi~_E(*HL}?4-c^;I^=cty~vjg(v!|N3S@cx^20ad0d2a;&xajzZRKD2)9rr$`axHb zEwtp}0aG3jaV8jNOf5Kau4&LQ^XE#OJJP6NB2td=lF7HIW+d3!rlJW7jXCkyW0ZcL z{ilm)jXKiIr;K+94-6k+Gp9zK+H1Yw(1WEEwXifja6muZKXinpa0Zy%Q%zHAp`%E{ zXVAEZ< z*lB>_r-adh#xHNUB0Ti)rf`#3I9CY+6W2oDd1A!{4sFsP+Ajvb+4@**%K zpOhcnit~OGI5(uav~a3aZb3g@Mx``#9#BO0N7|uoxczh!af2!#*O+6NcUaabLuO!h zCauP>YQ?|+5elTdetmj|*Is(gck>-AJ(2y--PkY1r> zI{I8~ZP6ln@^TCrK(`Q}d|iTdV(k^j!nfBKkQpoErQ%O@)EV#O`IE^J)uHntX|*#l z1Zr=_qrf|jYW}GVB__OIDjTp(hNV)`_Z3O`I-jA%@Pr7XvC10*Z1;SADj3w#pCG1j z<9HfbWA%I0aAS`lrKD+6;G!9d)2gg?cMysqVO%k#Q<^nv=A$3~h;>H;n*{0Aa2#Kq zl0fKlybp$2!Fgus4EhNp2j*M@_qLLJ)#dAP8w^iB`ItRO00`D27}Pmuo~B)a?}Tsv z^rdw;rUsRwd_2b3~bHak7y_XZP(QtrFy2i3Q z0d{w1Q%Z@GiL*r`1*PjF7c}&(5ttqsT++_;+d1sywbK2wC-6?sQ~Ib&5=$v}GtDN3Rre`>TC5_Va9( z`1yQXa@?)KJ7?y1c2eh6ik|cnW;pMey9mTwi^qj|EE1z%*@kcWWP!RNA~>@eNro^O z15j*&+<)ITp0(&eSX;>B{hjX^P=ERH`>Pc{CLI38V(Byd1o&uH1HT>oW6cSJN4jTWTrjFnR2 zYF^$cs@E*8VV0MdwHC?zHEWm!1iDfgDz!LYn7`&gRV7z@yb+D~)t`m*&eQm>MV}`6 zP68UvP(Zuk5TL_%!WT57njnRK*SvB($OCAB#GG~dDM6mgA(Xwa;~D8%(c(sR;uOh; z3JwVR7MCoQF#@Py}5L&%?3z83KZ1DT)ZsS^nhTrhhEtYTBSd{ga8BwZi{~`HkYG^E9tX679L_T#)o#dy!BtnHK zO-#?R5=~*Fu#)O!iQ`ZiAzpdglxDa)suqJyJvir?i_1g!A$%f($`+w+_$^)tpp+n zQ?>B65i`CqOEf37MJ8oPl_fCk6kBUT8l$n1e(fRN`YxhdDz^I5#R{3~{IA3ipAgsI z(4=vbyEN^d5@r7e)RMc+l~piCPImQhAIHhXy8>P7K z^K?7Z+qxn6!Ofe)X8oOg=ILR^l!@|gzrg(DOi98Vn#@AXWouR#mC%YM7oBe_5$hBu zpRmAVPnweyzV()yL-xM=?hBc#uevN`(NimmI|WgT)4jo5rO~(P{(G!MG8Y)ls?*8S zP?I~S(F@^7$ytb=yhhrD453Ow)k49N_YOujLWQXpQ1D7leQ3R3MVy<-%x`X3ZVT%Obkp`LQmdpZ$! z?z`{U5bnL_uJFKp_vpy}Ibp@(i)4e`W+C~}P4|XdufIk+3&zO$zSA`5Vts%8`KQHY z_YA+@d~dkt)*Gy*zw^?LaLKA=VZFAWJ@U}z@YEAqb(hXDxz$^hTU7Sm!W-AvKlI?n zD5sTv|J^sfWs9rE-G29k+f)dZ$GWpp$LXh7nZ$P?+U4f3Xtw&1IIh1`Wy?$W-Xy8O zkixN}MuxXvdN#cG>W=W*^V`CXr+ynYKlO4LbK=s_qTA@uyzA&N^{lnw!ELXG=bqXU zp5F3Mc=4IX!b{ISA1_<*_T}iaYY`?_VTqWHP8pj|7A#6wKQvE z==zn*!m{il>x%bnxH-%bi(?7@jyrDgB_M6J{LVGWshU*L)u@R$$&KEB`7>gA2$!x~ z?HZ(*j^$qS+%1U&QRjG|C}v==S%)BwmHCjrHsvetc?~O|@z6?qA$|U{+#K=H>~xrv zo;I?XHE$AH>hC}HYo&KM5yWLG1Q0CD03da|i9k+OD;jR9U5ypF1tlq+$D)jAz)njC zkBgf&GNhKkVaprTZ*WpVW9kG$t1xyB73OK-YvG*>&C}B=g_opU3$d%^;5wG4XvI%| z$?(RZ(w}^Dx&G!n9oijDu6fRy0MgLQd53yH)p(ayZy+CVD!$|VLtJLM70S}3!W+s( zz6LI@CUTfOe!^`x-xxmo?SJ8fRfVvE-R5$e=k7eTf1PUwBLPEkOB5 zUBq`#fI6^!`x7#7ekzKg`#`mHm-2E=y|Tomrqd+K!C?K?wRSm$P@!rL{a>}I&>1Ch zd~(v2=xQx3e03E)M1{f1g%Xu6WkkrXmEO1`oLdcE(HTtM_U#X~XJ`@+onuLg z;rOLYgYu{;R5?UEUO1p|s z6p<7le(dm;e^WUh2!S`S;4Ia#rfpL;dR6FW4P4x`#5@<*UWpO6iXK0Z)qnSuNb|f; z+Ry#|Rf=aOzj$U9xUY;ze$%wcMqX6LR58xRN?ti>3%%dSH~o=3A65(!k}Vl+%oTW_ zo`fIJy9aXdNk@9p{@eGYp~MI3pstXkb4WSq$;W)|x!*eZsmTK@7xCo*T}%@5*c;U+ zmyfvl~TuWQ?=6Z-3o=9Y|7Qe;aq%LME;w!06{v3^}N55m*u(KNSSij zeLxfzd?gp4H`6<->^Z0dA!c^E8%b0u)#b>sc7XzcsF(BXD&16Six`= zjKs-u_jqR`y=FYSpUVDU?!T*}^5g zyL9U^x$%&<)QI?&@oZFFpLjKj4N{}x)u4Ds?@~MdD-~yV)vkCIiA$owEm%$S89n1` z^=lemrcR~!8dYD3i>X_;ZhS=Dx^?22h^tqx-kf^O(A8hRe*O4x{)=nC1nH+woL>ni zQL26*FD96mR4EnXvol%i2o7x9SE^U9RjE>?Y<`WpjsFy3B7&bX$&w|Tnju5_2U)XZ z`6n`KR`??$BjH3w22x?!_*GfDPEx|BQo;LamCBkmi{99Y)TvS-b?Q_|lO{FNrcHx%Y16`= zK7Bek>C>l&pB+z>@+mI^KhetfE9I8RkRbzNtgKR&mo$BbbV!jr1yUqUhSE){V#LiQ z828C~41I3}d%`{in$Av4RCk>J=+1NMjy>>XGX@=xL%}jdkn*|YY-(C-2%DN7$@J!o z88h&c5t%Y&LgvhwktIuJaLA0rBEoFZK3U?yQmzIdQ>Kicr%IV}gU{z{$^lO~SwlZb z|04L8j}@-W6BYGOzPx#nH%}f!^9#bF_)iI4{Yv<}9KRBdviy1S1aA6s>%2QT0 zj&`nGIgvekHssWe9NDcNrK6&9TfI55XU8iQDkFJjJF*OiAt|r1K)JC|UpXj;>kEw_7*!u8?Pt?Cj4G^Z3vUJO@GFk0`akUUW zmKBVC1>vKrA$&v?gb%5Nr2Wew=h(U!#9@iPn}D}kHAbg5o1#pq5=LK9&4YY4c0!F+ z<8$WBX&uX*I~V*>xpQNpXkp|DSI713X`*?#MygC6fppE4D;J6tEsB-%=V0;9rI_~n zUew$)0IB+u00a3MRvF5FJp8Qoq z)T^x8yk3@o*Rxw^bnD!~WkJ~@@p_|Ias0>uEM2q!RjX7&Z1i~8IF28S^=nq3K>mEl z!oD{p4mRKl3Qcbcr_+mY##eYme4`Ute(-cszY^&$}?E^q#AIBmV?vo z1@w5Z0E@1zLettcNQ(?c2T$l^Vh(#q(!Ts9*uyx^WGYV*SQ?vSrGO2A!KA_J{2V?^PPk1j2G| z1NfFUhA*Khe5;$ox2_d@8{5FQxgC7l+9PadCxq?kg0OvE5w^cO!VYvtOxVF5$f;D= zzHSKH%e%We!?&XYd|TVYx2Y|B>s!OOwk3S4n!&fc349AVEK@iEx)w*9OVbc{b_qsw zeG`?+zGSe>;t3;-|6V!~4lpwCOFu(l`WezX}4Ua4gL4+`Ue z4kS2AV5r3!Vf9LkMm>uXHUtnSN`O?#Wr#}YX5y4K~3p&l5orzBRJZ> z=cwHfj(LI;Sw#F-byJk%^XjvA=T!$5FPMXGzWNe3u3bjV_%XPD=Q`T7YJtrg*5bs` z1GsIC0* zLUfCUM-Xk{0zaPIVnAs$JspENS65(6&vvL>zSJ|&lzJM8Ozf$KMch-eyZ||5p@Ib= zjw#Mjw8)DPb#+fOyFh{b22hbw`8K2+PJvZCuAG2jyGbKWRnE|`Bc#z$(nypD(8w<$MH#h} zqdP}MBbL+?dXhERR920uS#QuZUO<^OqC85i>VkPsw&B$}Rgpej`hXrO9r9_ZB3(z& z&27*XY+dLIJd*^TF!lZ^6gj$QcnaW~Urpdgctu6f0Bkcw3%2$zEJcbGO++&lvj-g2 zYg6Mn(OLIAE-QF@YO0lYi}Fb;&n84!pH?R*fvC*K8THqJGz=nDE0k_^2aly89By{??O*o5)nR1&}OuA@(V{ zYYYs%0}*y+5W>z5CW_AuL8-9wL!g9m!cOz<$pI|QQPYSWBC0tTd>XCoWV}N3Mj~4C zW}Mm#`Itg?mj9kzp9MaKzmPKy-`nR zX7}P|PR0M8e1do1zK^)sGh8TCC`U&1ylDzWi@bnJ70YAosugJ0_Dy7^JuX&VpRC$X zaEA@6LbZ*WgWx7$dn{VIfUzDzR8T!BP!qoAhavpp2!vlAiRkbvqwrGrTgEzb)nw_77c~=uKpcku&L_0z%EB%e`vtYJc-P55=EJ`Dvv!&gzXE^ zM^jh~SkqcloKy(EB>Id(jOdfzrOybvV7G|d|U$}5V zlzzFCJt0Y~xot{h-FzJEryxC|8kON!U3us6AcM2`bYeIULHPOM94-R*>KKGy=jX;) ze#W`i>r7we=kjP5^5+Qf(}}@No}ZX=OW9sZ>t$4B7ueSl5Z%8Ms#YkSNdItwU5GtM zm^T$icCIG4x1nyWS8V76Y|-+{>BIQv=g;x?k535fzGjEZ!YfP4eEH#h{PV-7`1`jn z4akxLQYrP^?aQZuf4;{*fB%e;!v={HQ5uFgwt)SS3+yRU zeyj=4$sT@%RJi6+Cno&nI218DDd#HhuteDTq3#oUQZ+mUZoXj!Ena_hlwRKx^Pdpd z^;}?UBqha$4d{fq)5l=>!pYdOej)bmT7#p9cHr8Tv)H&{mC=U`(HO3f5=0u26HFU| z-0y-aO@?pDO#6@pr!_k*3H@Hr(Iwb|4EcRg%&W;z7_Mii?|mE|9-iHJxBd~jd~fbw z1XcriMDTSi&fLE_g?dd@(L(9cr5l$w0Bo;nUFAUO-nA1}uUJelq%)gH>U96Uy>RNp zQQV`7J%j^&VDBz0UAzFhc5K1A)hjT3*bt;knI^=qM^&e3OqEf*NJADBt|a(Ta@-RG z5Pq7#K1X0*4KM0=d;$Li-fCJD(2mZ7C&Gv!y;R zqhUU}Dw3av$8gip!_=lW%WF-)%ab%$e%P%0+Qly<`r0bm@o-)I$rBKoVT)kOv#H@4`jCym@48WWPtw zS;AcPVT5EZnwA%g@2ZHw*Nj2JeVCvarhf!xpS*;li*6Ov8Gn8N@1TPS*mk7x#0;{M_>R;Db zFi|V~DtYo{-nqy@6RgjVfJ0@&XZ%>8rM4(dTDGCIX!+m9RwrO5WB&D(h#A-g)hd=j z+B9jAnja||8k@oe1=tv@SrUh}OXuLF5=D(d(w^lplY(*M{85}eybHCeRdPLT1YCJ) z#_!y^h^uD~*6sqtXqSC&Bl5Y1GYRq|Mm$1 zdm5Ri$(=wIYy;&7C!ATvvL^yy4HsCivEQ7%hRM5rgx`(fbiNx4C+toPX~a}61j-@Y?o?LU8 z$%+=L#8`<}skRv}jDtf4>(GXCP7j6eJhg|5;}CIqJR+|6`H2o(Cm`a|c&dG4;hY-@ zhoj(7o~C17a()l0$sQ-ssH~!Yc>F79c5yNm-dKexL%SQB%|&~qZLEvH#52TPT{?wrn^s}n ziUnxas2;M&9wMT}W)JM%j6?gjV%x?9)Tvq3XzDtvq72=YD^$RDzkY{hbh%}oPLKC& zYFV2&x1~48mm?pJ6yb~18H8A>3F4>W_lV5<6M3D4i2IWfac?sGzB?0xE=-@6A+9Y12iNW3=WmJMM{{L(Py<3ean;_IKMIVaKf7rAh`FoL=OeUe{_ zof?#lQ5zUJ2wcHvFjG+VQK{}`Oj@_b3#7w`48$jo-^I{D{m{5kL)^T689lpq!Gd{n zuy4;!ywjh-71-#G&L%qTM9VZ4q&w#$?8#)Gv;_~I(o ze0c*YFN}uoOu(L#1t|7GcZY8cS%<$ST3(%w5qqbhV##6zP()EOW;rpODfLixYd^$3SV?*mLfVWO+%;Rd#KmKm#l>RF z%DFhSV>Pav*n=Bq4q-r_o>U2s7?I@m7I!mX@tPQoX2HEjUYOFL7Dg5GNZx;OP0INp z#B#Fg)TMqFS`$|%21=TJLiIR}RZ=7(JUj=P_IJ9YlA`*XEt})Pog4gI$K2V|uqI(C z8aAlQ(aK~a?=6PPwIW4+>ZEA&>D3JxQm4Z!?HYy<%Vi)_1LPGjXW2l6Q~dk*NqKf8 z?*06QvF6|Y{tK7C{}@vqpG1ut%aHDrAI=e$J3b0UF2|wIJG-&_s|Wb%kDuY!6P@bZ zUrr`Vt=Du}njvzqNhQ!YtRuUKu7%duXQJEMu}G05xv2m(tCYo-B@;1g!T{6GU!Z{* zJ7EMm^z4DIWEDkTC`4a`tG;PnCVKoxbRWRWemiy(>;P@uIoY(WP%6^rjD@ z+3WRPbB|_O6wR`j38TLuZ1H?KUJoNn5~#dpH`my`!YsyWX=|Z zW*7qroE0ryDW=IQ=hf-Ku5aKxB{!vhwOfnv=RbcVM&u3u;FoW(`N>V3|L!qy6sqe@P(3)H=&;fi_67T(YnPE2hBV(*O;kS;}Pb9QMOMRA^sX%;My7x~!c zN#llKUBW`FUN#pcixuG@WF+%+18v3*?T1ZkmSTOv0@R}0CvDnvrWNF8zh_MxgN?km zY4sAcYVs=5rb}l`ReQDq%$>qrBxfdO&kwM8zC2toldH-Xr*Yb!eOvJo&D zC^Rx5BlD9bPmY<>r{M7i@8QK43fmZaEG#M!224~FZh66QpiYLX=lEAi*bsBHtFU9= z^XQ#x9WL#THY~eg9W15_=wRMFo0xQb9^*AECzS(Bj&;rL(2|MxuA*u9uwM;JD|G5D zIkI?2r0(hGnh>J~Y%x|0Qm#UJoy_8)mnw|9rgLftmOZ(OX`*oC=YRZ&9M`AAF*Bcn zNPa9jW6cpOdLAM@H@yWXwvOSh&nCZ%J2EE;+Y~8Np+l?J5k0bx8RNz1E`F&*ag;1x z6moJ~OoW;mUgX8+Ew^OxA{HIt*DYJlk&C$mG5Qi$7POelJGqfVWGG6O@bXI~P>MC` z&I=TQIdgI`l%pq6ott`R(bB~Oh@Pxk^p^E=xTi)`&MfWlyUX)@C}TYS&!fPOQyni1IrIV&rvV zjjJji(-ZUV-nk{Q7D)z1X2=x<(JWP})EG!1@bLZ}V(obpBu^0_G@1s12&KfKG}_`u z$x|e6WLWc2cPvhF{%PgHy>cqU8G6D;?@<6EeA>Mos3J?&EC&p2NvK0z)&oz;a)TA0 zv86co)e1vkHtWlSbXJ%NL)%*t$wXT;(Z*m5bI_X$n>D?Z2 zlc;i1Z4(WI6@f-n^b2;jilRG)B}d)0d`GJ*(JJc5XtccSvRtedX6ve2REhYSg&PuW zIcWX7@KO;MX>*CR1x=`m&}z{vqYuFZtein+t;7;H0cGzFh3oZ6R4zti_y>nwP9OE- zU%#X9?FAIMwDqVe8V7vHk`m3T;W}v|@hb0xd>uPF(ZYY#MVUC7P!`~560Jk}bVBd0 zZ(&&fo)|xJFs8+hEo_+`xnX*13-PI>}=SO_DgOcF5`b@hOXWKz=sBd86gC-?e7cRWGs0@lm%UTv`%=`B|{{V#wq(8reW zw4_H9*a#i)M}|{liMT??+v(xxMV)Sn0G8?84<8}P)o6s>h@nU!L2pUNCeW@0rmhT3 zfoyXKWW57yO#qWf(*o&Wf^5!|QO1Y;lKFmF4-p0Fol!zpdE4!d646RIa^A%1zEhB{ zAwE(7S(PftrPTZcl>n7R%ZYrG0>lawDMV21KsFCl^2Z8Pp4MidBIBWlCPK#U9Rlkn z0d;Xa@?DvYZ~puRvFdlOonJq++_0Mzs{$1b1zTMV|o4ssDQ4faJN~pBd{r9 z4i0Qvg-a)P(N%R8@7=kGfqi@9%&DgVWg;fG2S*gGQ(p zAHne#5m?nVfEk9{SOBpCq17S6B~+K2w$L7zT|I@QAIYj>$f^<}i3{nrC}I9vQuiix zUE(F|(gY+qI}Yc+{|J*r)wF+5X{+=g!L;LuyQIAw4Ro2ANck^BO>)_m6twiI(!eh` zQEN@ZN!k(frj0cfbEa0&o#OmAMXAgsDd2<>SxXWTL39)ipkp3c&O)*rp+ow%(4kdS zwf`2|f18YiSdX|dk?LbKXT&IM`rjS554qlWNNxV&7~+P=pw~pD?I}IYT1<-<=7fq_ zWHUP{%sj;@fC^dN@sp_>E|16F%`4~-*^YZxj^ojdvlM21h>8;dHdDYvmIlX^@PGq4 zk6fQu9J-6$VWlwKC}4yXb@=S`}2y#g0%t$o2vj&sZlbjE! zYNw_$@1Svd~}x39v5qdW2TjWdRl z-aWdyyo1h0aYK#1Nf5^!BaT*3)TCepues48=qG!T3eQg}BQdW*HE{Se{G2am9b#sJ zg+v&O2onG}&VN&!wYCL{@HBMFY2@8H0?&ugVi*ZL7UU$fCsq9atM3>Sp*BH3&YRJ#% zF6x7s~sP`eH&kW`X0V{@|cU4D{=MmMbnTaSp^pjzQ+%qz1pe4SkBqij5LgKa`Lqlk0qg|CkFeu6Bs}+QeE}GO;QNv8*haQI8?Mj=-ucaglT{Z2 zu)V?p&GK-`O(u#K*QtA(n_Owhf4-3L`u`ekX9xmCfk+VyIKa*EE#D$F0Ee?T+qIbx zsLXkguFKI=UI51aHP0ef$IeUjINSt#+f9)CMlKXDXzr96?e*+EqefB0qrJeoRNpf zzjls3R2l;Q@XKVA;TLHvoEnNT9~^NFg+f37{RfKPoJ$iztI&j@ObVH%e9nwJnqNMd z`kwhki6u8hHhwbD7pyjHUAq{cef$nT@8k2&KE~%yKE)TGKfw=N!zOj~lTJQm;szbo99 z3UnHaaEV~VS4OU?PNvEKm#R>eAq~qzs^w(QNx@u>>oRY(X^pn6TcRDW?cZw4rGZyn zLCohvP}@cy0Yjb5TgA1h#CEdSyu_WnD)g>I&`mAZV1!(QB!5@hZDu29JN@HFEIA2b zvZ5aeYJwbnGW6$!Yi&^uZN+maT2XeP`K}1JfbS}?MJL3`9-cU11lF!x^c3LyLYq^x zND){3nYuJfaLe?RAmnh1qsdy6l~$-&VNCs2kbA}hC9j+e2ywQH@~&}7gO1}uS7ze- zKYw%mA-VT{^8miH}4sLM8@D>+mCPt65#To_VpXB;c!m`C?HOLH&@&G5X78+(DiY}__^t;!# zoh)HVlO`!f_J2TkOll_aU=X}=pd}Ao6U~HRpiY-bsdh`H&dZmo9!5UAPnb=mirt6` zcUd|Y%1H8Zr`jyqZyyTr!P>nBnxr+6SwW$Zqq(vK{Ki1IAAmo;1^)UT=T06n$ZC;H zfmNOlKa3lQoMkOsAHF#S2@W|0uW*J7G=Y_r#H%P_w+O}Su@LC=_s2hfq1-zwDMn>v zON8Aq>+bPE+0?tGB192guM7O(EAye0)5JuI&mDAcb6MogfWTGA}_v3v04Ok zm60LH;{-T<+w z3qr)Fl!o3fv6`H~JFJyW!m%1bQbHb2?g4y@K8Vdk@y{Mm0#$iXaowG&$%W>*aPF5h z2nMTH!rpC|POeuP@8ttlDX%Q@4?lma66L8y2Eve`P+s>uo-Gw;{OIAt%Fp=l;T2pu zx!Y{mC3B|HNyOa~au!AAK+X2A+R9Rx)OLlSL4YQ_C z#=5nu+2<%s6$*_BPJB95)kCIGDHT!3%qri4XFbMqYgD|qiWvxE6ho7uM|3%-2jI;| z8>}aP)AfFbfrD|Mo=3xbtC8^%dwN=n7{j^pI|c==%|hpQwqw(mxADpEjGX1)|Ni_5 zk+eE}3KY?Th3b|HtJSlOT(p={7v;9~$EX{Nt$lJ`RVr7StJ4$l=>9ECi5-V?r;lOJ z&Mnx+olK{>c)4OJ7cW*W<8Is37CKOvX!Q^)(0F{w;FLyVpEy_F#o>Y&%ANZUJ>lgg zE^A`c;1}k?&)Dc`GewnQFmseLc-spdRbUT>TUC6W3Md_`L~#CCy*_2BN%m|RMaD;u zAC1Qku3|q;={*~k;Se1yQ~mU4QXvsY^JdS5x}D!}0m{9a&SEasZ{wmKNoot}0+H+w zQxXGCfIF1jvL^14Wy(##k8?W)!=4;NzPA^^r+i6unW&Q00R}=etjtDDgx!oy zTTLm-h?3UVrlZ$}@#g!FB*e7%m@Zvf%#E9cwQJTGKo=P-6-4Y83M&{4#UP7PBFn`U z$HjC-d?=dBi;NLdW6+?Fut|Mx6l00bW7Ok=C`H9DsUlw}iycOGIhQFO0?{#Ha{18^ zcNlc&oEe5pm!i?&-U_VX`dP=fH^C>`DB4DKEBc1fCE9}JOsb7?TugUi=xPo7cWuPc zgFCp$IvTH3t8Du_wryUA-8;5m@9rI#F>R9VT9RT(OThfXPeUKgeF4UJCS-?%kY%`I2^Urd9j*<9faZb9%S%*u5No--$92`(r52RNj~&f$(VIAO zF$)aQnt(^y}RnS1z7||15p1$@lHviP?-U+q!9;xrrqB zG}v03@GvOHb70^(!Ui-$N)R^&yAY^+9$G?04XUb}%Hz4D=8t7nLYI|Il(w1^!A$oZ z6|~AisZcpfb9jA>0yNO!E; z$pxY>5V!1XIWKI!=6O%9{!9Ae%H1TMF}G95kEjYD>BoHYuB)9}Nh1@o|u7*q$% zk?WU9Y|c8TL@};}3yoD}t!O{E04YmF4t9y>{6z{HUyPi|4I2zNcGeOh3^>-iefv2J zEOL;uLi|zQ6otBI4}t6wi*g-@Fggf)49)h*QDA}D%%h>~qg&Ufplm*)SOiCPFbYw1 zs(*?Tb+++cfw<$coBLqg?d4{dh__cPUk>x)XJW+AfoAx3?)Vla#*D|f(IZi@LOIl{ zQwvSsc%3UD+<;5btgDcq^|c^2>9q;zXaS6nQlY#Mmh7&%iUlf(=|pBTpE0KD%39tx zVDdUy37-em#IWNdhHH(CoQ-~Au7pN`2biGD!Vi#ZHIRqeTb_;l4Bm;X=~J2eAS(|Q zsqvPp8v1x*f-{GE$hmpf*-A7Jc+TF=aL5IHiMXJ6m_xhL@wlNpf&`$CoYA2%;*&w5 zJUN6Jt>CCUrMFLNruZI}B_Acbp-u?kP7r4acY=(pgw|K4q1&12I1#Ut+Lstp8g#kHy*yiT69}GWZjQ1hsc>l3h+p(p z-3f5Kv%wXpSQWL0{3>H;GFTe+9Njf$8hneP*U%S4SoXq&3!6hpI$oY}=TTrikbf0W zfGEq|Z!z)o+j$#&!z)uS;=W_({L_nuT0`(}lO<9^Qgnjhd^=)wE=_6OoEapG3`-yI!3Q ztzB*^)G0z;domBxKw#UXtx4MYq)lj{LM}djf_)MSl^2*Z4mA%~!(+e1t+_o=bsD0D zY`sgnsK!-6*^Rw|h|7~ZiZLWIA_}|vz8v8vTHvyj?F9>SF~vg!#4`*KLZDyST-ps9 z%fy0vS4gsyS)>LMgNv)Yc~UiuVN?dH|0o{fT4B1YcM5(6HG`keL##Pn9L*lKwJ^%5 zQEu!4!(}K_@{A?k))8;yYA)WkAWOQG=A+7%F$-$Q;N|Xm-_T0bfhcb@GV93MBvJ#I z^C=QrI-WQZN5|n}qbP2^JdTi0$l`8f=N#ufzgy6%WGBlw$NMnMk|QFy#b8+z(L2b^ z!~-@GZL5jz`P>dUv^-j0nqu-aDl(_Z4)sIvS&J7fa1loYy1JYss_A!GM1L1;ncZbG zlcDYcX{0vo=){xdj4EH(g6|6;&Qt~VNr;o|JHj^7zVWF~;&bW~KYn#6lkGrLPC%D) zIP>&`In0SOcm5E=(hT&5wS1HI5s#^ivKxA0+@0kX8(>)D=mfFm0?57^l!Q9VOQw_* zbB(L_1fv>!}AttPL3w%6j3>B6=L6!s{#|nN3#5{xdAV;ROw#*}sOWiIsXa&H5<*D${ z>#~fbTSHK+4}mbajZo3n959C_fulexiAk+pX!`SNtWACf8GBk0=kW#(jaCUCpFAsM z3Elw@&IW>S9R;5NKZlHVP#H8jJ`Vf8yMX&w&f)DlS1`#xmX7FDWO)m)cCBmBMw>Aq z0LBDU2E~#FMao(EYCKVE>fHA`5UCx%eku-&UvpWyKw@y@7DmF+JG?^Lt6J>S!3^ph zdt%IxOxsbfq}5vQ_?;B6vVyT(0MdS?jCc%B?^sFGMn^M@tbj6WySrfIvY$k(n1**o zibhVTo2*2bM%8$ZhlKE_(U%V)xfn`?5NRp0C^H`t*|8=URk5){pS?nCO$h_3;W zAri$0_~A)6j>=0!Q(5zob=u)1>jNxqB~iA7>}Yx&I6X_^^<(33>i28->^_f)cy!r< zv*<|0JTqV^T*>NeStAq=lEsdXBEHOApgOJ1WWvaWqmy~W(uFnl$1fmdHdEVrMHI^5QArsdJ4p>4P9YUR^HMddN1Cf~d@~P6 zDYv?tYb;Pni=w(9E+cLcWOt5Iu>x5@pwd9#ed9DqJ#iKsdKOdBM5Zi3;o-_v*6c}R zYnE@0WtU^RW@}K1vw}~tH)Cp!3fsN#kcHwN85AR>AVN$|2~7v#QH?W%X4fKz+~^
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class new file mode 100644 index 0000000000000000000000000000000000000000..306bc08c9eca5d510d01792bc7011e1ef8b75cc0 GIT binary patch literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class new file mode 100644 index 0000000000000000000000000000000000000000..f69a8e17560897ad1adaae18fd15a3f75ac850a4 GIT binary patch literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class new file mode 100644 index 0000000000000000000000000000000000000000..43d486e461eb753c8772c3c239c81b3a83a13216 GIT binary patch literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class new file mode 100644 index 0000000000000000000000000000000000000000..d473cb81c8c6db44be5035f5848de2cfe8504c66 GIT binary patch literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class new file mode 100644 index 0000000000000000000000000000000000000000..95af7d70364676903cbaee10411198d19f52394b GIT binary patch literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class new file mode 100644 index 0000000000000000000000000000000000000000..7234b135ec1e4b601e8d271c48caf5fa07bd47ba GIT binary patch literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class new file mode 100644 index 0000000000000000000000000000000000000000..5e520fa0eb6d9ad0cf329fa2572250588a3e365e GIT binary patch literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class new file mode 100644 index 0000000000000000000000000000000000000000..5e228155303a29cd063056a485473fdd564000c7 GIT binary patch literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class new file mode 100644 index 0000000000000000000000000000000000000000..f4a6dd7e4e5820644e459a4aa5652e5f2a69beba GIT binary patch literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ new file mode 100644 index 0000000000000000000000000000000000000000..2452fd26f12793bb5445461ce339266070961506 GIT binary patch literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u literal 0 HcmV?d00001 diff --git a/androidgcs/default.properties b/androidgcs/default.properties new file mode 100644 index 000000000..e2e8061f2 --- /dev/null +++ b/androidgcs/default.properties @@ -0,0 +1,11 @@ +# This file is automatically generated by Android Tools. +# Do not modify this file -- YOUR CHANGES WILL BE ERASED! +# +# This file must be checked in Version Control Systems. +# +# To customize properties used by the Ant build system use, +# "build.properties", and override values to adapt the script to your +# project structure. + +# Project target. +target=android-8 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java new file mode 100644 index 000000000..31e90ffd1 --- /dev/null +++ b/androidgcs/gen/org/openpilot/androidgcs/R.java @@ -0,0 +1,31 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * aapt tool from the resource data it found. It + * should not be modified by hand. + */ + +package org.openpilot.androidgcs; + +public final class R { + public static final class attr { + } + public static final class color { + public static final int all_black=0x7f050001; + public static final int all_white=0x7f050000; + } + public static final class drawable { + public static final int icon=0x7f020000; + } + public static final class id { + public static final int objects=0x7f060000; + } + public static final class layout { + public static final int main=0x7f030000; + public static final int objectbrowser=0x7f030001; + } + public static final class string { + public static final int app_name=0x7f040001; + public static final int hello=0x7f040000; + } +} diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg new file mode 100644 index 000000000..12dd0392c --- /dev/null +++ b/androidgcs/proguard.cfg @@ -0,0 +1,36 @@ +-optimizationpasses 5 +-dontusemixedcaseclassnames +-dontskipnonpubliclibraryclasses +-dontpreverify +-verbose +-optimizations !code/simplification/arithmetic,!field/*,!class/merging/* + +-keep public class * extends android.app.Activity +-keep public class * extends android.app.Application +-keep public class * extends android.app.Service +-keep public class * extends android.content.BroadcastReceiver +-keep public class * extends android.content.ContentProvider +-keep public class * extends android.app.backup.BackupAgentHelper +-keep public class * extends android.preference.Preference +-keep public class com.android.vending.licensing.ILicensingService + +-keepclasseswithmembernames class * { + native ; +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet); +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet, int); +} + +-keepclassmembers enum * { + public static **[] values(); + public static ** valueOf(java.lang.String); +} + +-keep class * implements android.os.Parcelable { + public static final android.os.Parcelable$Creator *; +} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml new file mode 100644 index 000000000..3a5f117d3 --- /dev/null +++ b/androidgcs/res/layout/main.xml @@ -0,0 +1,12 @@ + + + + diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml new file mode 100644 index 000000000..02a3f5dd6 --- /dev/null +++ b/androidgcs/res/layout/objectbrowser.xml @@ -0,0 +1,8 @@ + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml new file mode 100644 index 000000000..eba6becf8 --- /dev/null +++ b/androidgcs/res/values/strings.xml @@ -0,0 +1,7 @@ + + + OpenPilot Android GCS + OpieMobi + #FFFFFF + #000000 + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java new file mode 100644 index 000000000..190668d80 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java @@ -0,0 +1,99 @@ +/** + * + */ +package org.openpilot.androidgcs; + +import android.widget.AbsListView; +import android.widget.TextView; +import android.content.Context; +import android.view.Gravity; +import android.view.View; +import android.view.ViewGroup; +import android.widget.BaseExpandableListAdapter; + +/** + * @author jcotton81 + * + */ +public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { + + // Sample data set. children[i] contains the children (String[]) for + // groups[i]. + private String[] groups = { "Parent1", "Parent2", "Parent3" }; + private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; + + private Context context; + + public ObjBrowserExpandableListAdapter(Context context) { + this.context = context; + } + + public Object getChild(int groupPosition, int childPosition) { + return children[groupPosition][childPosition]; + } + + public long getChildId(int groupPosition, int childPosition) { + return childPosition; + } + + public int getChildrenCount(int groupPosition) { + int i = 0; + try { + i = children[groupPosition].length; + + } catch (Exception e) { + } + + return i; + } + + public TextView getGenericView() { + // Layout parameters for the ExpandableListView + AbsListView.LayoutParams lp = new AbsListView.LayoutParams( + ViewGroup.LayoutParams.FILL_PARENT, 64); + + TextView textView = new TextView(context); + textView.setLayoutParams(lp); + // Center the text vertically + textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); + // Set the text starting position + textView.setPadding(36, 0, 0, 0); + return textView; + } + + public View getChildView(int groupPosition, int childPosition, + boolean isLastChild, View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getChild(groupPosition, childPosition).toString()); + return textView; + } + + public Object getGroup(int groupPosition) { + return groups[groupPosition]; + } + + public int getGroupCount() { + return groups.length; + } + + public long getGroupId(int groupPosition) { + return groupPosition; + } + + public View getGroupView(int groupPosition, boolean isExpanded, + View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getGroup(groupPosition).toString()); + return textView; + } + + public boolean isChildSelectable(int groupPosition, int childPosition) { + return true; + } + + public boolean hasStableIds() { + return true; + } + + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..19e9b2812 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,21 @@ +package org.openpilot.androidgcs; + +import android.app.Activity; +import android.os.Bundle; + +import android.widget.*; + +public class ObjectBrowser extends Activity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + setContentView(R.layout.objectbrowser); + ExpandableListAdapter mAdapter; + ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); + mAdapter = new ObjBrowserExpandableListAdapter(this); + epView.setAdapter(mAdapter); + + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java new file mode 100644 index 000000000..12a4263c0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -0,0 +1,27 @@ +package org.openpilot.uavtalk; + +public abstract class UAVDataObject extends UAVObject { + + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(objID, isSingleInst, name); + } + + public void initialize(int instID, UAVMetaObject mobj) { + + } + + public void initialize(UAVMetaObject mobj) { + + } + + Boolean isSettings() { + return null; + } + + UAVMetaObject getMetaObject() { + return null; + } + + public abstract UAVDataObject clone(int instID); + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java new file mode 100644 index 000000000..a1e5773b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -0,0 +1,50 @@ +package org.openpilot.uavtalk; + +public class UAVMetaObject extends UAVObject { + + public UAVMetaObject(int objID, Boolean isSingleInst, String name) { + super(objID, isSingleInst, name); + // TODO Auto-generated constructor stub + } + + public UAVMetaObject(int objID, String mname, UAVDataObject obj) { + // TODO Auto-generated constructor stub + } + + @Override + public void deserialize(byte[] arr, int offset) { + // TODO Auto-generated method stub + + } + + @Override + public UAVMetaObject getDefaultMetadata() { + // TODO Auto-generated method stub + return null; + } + + @Override + public String getDescription() { + // TODO Auto-generated method stub + return null; + } + + @Override + public int getObjID() { + // TODO Auto-generated method stub + return 0; + } + + @Override + public String getObjName() { + // TODO Auto-generated method stub + return null; + } + + @Override + public byte[] serialize() { + // TODO Auto-generated method stub + return null; + } + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java new file mode 100644 index 000000000..c5ffc9d21 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -0,0 +1,117 @@ +package org.openpilot.uavtalk; + +public abstract class UAVObject { + + + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; + + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; + + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; + + public UAVObject(int objID, Boolean isSingleInst, String name) { + assert(objID == getObjID()); // ID is in implementation code, make sure it matches object + assert(name.equals(getName())); + this.isSingleInst = isSingleInst; + meta = getDefaultMetadata(); + }; + + public void initialize(int instID) { + this.instID = instID; + } + + public int getInstID() { return instID; } + public Boolean isSingleInstance() { return isSingleInst; } + public String getName() { return getObjName(); } // matching QT API to the current autogen code + + public abstract int getObjID(); + public abstract String getDescription(); + public abstract String getObjName(); + + int getNumBytes() { + return serialize().length; + } + + // The name of the serializer and deserialize from the autogenerated code + public abstract byte[] serialize(); + public abstract void deserialize(byte[] arr,int offset); + + byte [] pack() { + return serialize(); + } + + Boolean unpack(byte [] data) { + deserialize(data, 0); + return true; + } + + public void setMetadata(UAVMetaObject obj) { meta = obj; } + public UAVMetaObject getMetadata() { return meta; } + public abstract UAVMetaObject getDefaultMetadata(); + + /* + // Unported code from QT + bool save(); + bool save(QFile& file); + bool load(); + bool load(QFile& file); + virtual void setMetadata(const Metadata& mdata) = 0; + virtual Metadata getMetadata() = 0; + virtual Metadata getDefaultMetadata() = 0; + void requestUpdate(); + void updated(); + void lock(); + void lock(int timeoutMs); + void unlock(); + QMutex* getMutex(); + qint32 getNumFields(); + QList getFields(); + UAVObjectField* getField(const QString& name); + QString toString(); + QString toStringBrief(); + QString toStringData(); + void emitTransactionCompleted(bool success); + + signals: + void objectUpdated(UAVObject* obj); + void objectUpdatedAuto(UAVObject* obj); + void objectUpdatedManual(UAVObject* obj); + void objectUnpacked(UAVObject* obj); + void updateRequested(UAVObject* obj); + void transactionCompleted(UAVObject* obj, bool success); + + private slots: + void fieldUpdated(UAVObjectField* field); + + protected: + quint32 objID; + quint32 instID; + bool isSingleInst; + QString name; + QString description; + quint32 numBytes; + QMutex* mutex; + quint8* data; + QList fields; + + void initializeFields(QList& fields, quint8* data, quint32 numBytes); + void setDescription(const QString& description); + */ +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java new file mode 100644 index 000000000..3091595f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -0,0 +1,332 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +public class UAVObjectManager { + + private final int MAX_INSTANCES = 10; + + // Use array list to store objects since rarely added or deleted + private List> objects = new ArrayList>(); + + public UAVObjectManager() + { + //mutex = new QMutex(QMutex::Recursive); + } + + /** + * Register an object with the manager. This function must be called for all newly created instances. + * A new instance can be created directly by instantiating a new object or by calling clone() of + * an existing object. The object will be registered and will be properly initialized so that it can accept + * updates. + */ + Boolean registerObject(UAVDataObject obj) + { + // QMutexLocker locker(mutex); + + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // Check if the object ID is in the list + if( (instList.size() > 0) && (instList.get(0).getObjID() == obj.getObjID() )) { + // Check if this is a single instance object, if yes we can not add a new instance + if(obj.isSingleInstance()) { + return false; + } + // The object type has alredy been added, so now we need to initialize the new instance with the appropriate id + // There is a single metaobject for all object instances of this type, so no need to create a new one + // Get object type metaobject from existing instance + UAVDataObject refObj = (UAVDataObject) instList.get(0); + if (refObj == null) + { + return false; + } + UAVMetaObject mobj = refObj.getMetaObject(); + + // Make sure we aren't requesting to create too many instances + if(obj.getInstID() >= MAX_INSTANCES || instList.size() >= MAX_INSTANCES || obj.getInstID() < 0) { + return false; + } + + // If InstID is zero then we find the next open instId and create it + if (obj.getInstID() == 0) + { + // Assign the next available ID and initialize the object instance the nadd + obj.initialize(instList.size(), mobj); + instList.add(obj); + return true; + } + + // Check if that inst ID already exists + ListIterator instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + // If the instance ID is specified and not at the default value (0) then we need to make sure + // that there are no gaps in the instance list. If gaps are found then then additional instances + // will be created. + for(int instID = instList.size(); instID < obj.getInstID(); instID++) { + UAVDataObject newObj = obj.clone(instID); + newObj.initialize(mobj); + instList.add(newObj); + // emit new instance signal + } + obj.initialize(mobj); + //emit new instance signal + instList.add(obj); + + instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + + // Check if there are any gaps between the requested instance ID and the ones in the list, + // if any then create the missing instances. + for (int instId = instList.size(); instId < obj.getInstID(); ++instId) + { + UAVDataObject cobj = obj.clone(instId); + cobj.initialize(mobj); + instList.add(cobj); + // emit newInstance(cobj); + } + // Finally, initialize the actual object instance + obj.initialize(mobj); + // Add the actual object instance in the list + instList.add(obj); + //emit newInstance(obj); + return true; + } + + } + + // If this point is reached then this is the first time this object type (ID) is added in the list + // create a new list of the instances, add in the object collection and create the object's metaobject + // Create metaobject + String mname = obj.getName(); + mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); + // Initialize object + obj.initialize(0, mobj); + // Add to list + addObject(obj); + addObject(mobj); + return true; + } + + void addObject(UAVObject obj) + { + // Add to list + List ls = new ArrayList(); + ls.add(obj); + objects.add(ls); + //emit newObject(obj); + } + + /** + * Get all objects. A two dimentional QList is returned. Objects are grouped by + * instances of the same object type. + */ + List> getObjects() + { + //QMutexLocker locker(mutex); + return objects; + } + + /** + * Same as getObjects() but will only return DataObjects. + */ + List< List > getDataObjects() + { + return new ArrayList>(); + + /* QMutexLocker locker(mutex); + QList< QList > dObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVDataObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVDataObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + dObjects.append(list); + } + } + }*/ + // Done + } + + /** + * Same as getObjects() but will only return MetaObjects. + */ + List > getMetaObjects() + { + return new ArrayList< List >(); + /* + QMutexLocker locker(mutex); + QList< QList > mObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVMetaObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + mObjects.append(list); + } + } + } + // Done + return mObjects; + */ + } + + /** + * Get a specific object given its name and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(String name, int instId) + { + return getObject(name, 0, instId); + } + + /** + * Get a specific object given its object and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(int objId, int instId) + { + return getObject(null, objId, instId); + } + + /** + * Helper function for the public getObject() functions. + */ + UAVObject getObject(String name, int objId, int instId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + // Look for the requested instance ID + ListIterator iter = instList.listIterator(); + while(iter.hasNext()) { + UAVObject obj = iter.next(); + if(obj.getInstID() == instId) { + return obj; + } + } + } + } + } + + return null; + } + + /** + * Get all the instances of the object specified by name + */ + List getObjectInstances(String name) + { + return getObjectInstances(name, 0); + } + + /** + * Get all the instances of the object specified by its ID + */ + List getObjectInstances(int objId) + { + return getObjectInstances(null, objId); + } + + /** + * Helper function for the public getObjectInstances() + */ + List getObjectInstances(String name, int objId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + return instList; + } + } + } + + return null; + } + + /** + * Get the number of instances for an object given its name + */ + int getNumInstances(String name) + { + return getNumInstances(name, 0); + } + + /** + * Get the number of instances for an object given its ID + */ + int getNumInstances(int objId) + { + return getNumInstances(null, objId); + } + + /** + * Helper function for public getNumInstances + */ + int getNumInstances(String name, int objId) + { + return getObjectInstances(name,objId).size(); + } + + +} From eed5705a6cfcdb4807170c4da95dbacf6d755d87 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 01:23:10 -0600 Subject: [PATCH 040/165] Trying to get eclipse project right --- .gitignore | 8 +- androidgcs/.classpath | 7 ++ androidgcs/.project | 33 ++++++ .../.settings/org.eclipse.jdt.core.prefs | 5 + androidgcs/AndroidManifest.xml | 10 +- androidgcs/bin/OpieMobi.apk | Bin 148198 -> 0 bytes androidgcs/bin/classes.dex | Bin 12640 -> 0 bytes .../ObjBrowserExpandableListAdapter.class | Bin 3092 -> 0 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 951 -> 0 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 358 -> 0 bytes .../org/openpilot/androidgcs/R$color.class | Bin 447 -> 0 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 418 -> 0 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 403 -> 0 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 449 -> 0 bytes .../org/openpilot/androidgcs/R$string.class | Bin 445 -> 0 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 627 -> 0 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 1127 -> 0 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 1440 -> 0 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 1199 -> 0 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 1333 -> 0 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 2255 -> 0 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 5422 -> 0 bytes androidgcs/bin/resources.ap_ | Bin 140460 -> 0 bytes androidgcs/default.properties | 2 +- .../gen/org/openpilot/androidgcs/R.java | 31 ------ androidgcs/res/drawable-hdpi/icon.png | Bin 48558 -> 4147 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 48558 -> 1723 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 48558 -> 2574 bytes androidgcs/res/layout/objectbrowser.xml | 8 -- androidgcs/res/values/strings.xml | 6 +- .../ObjBrowserExpandableListAdapter.java | 99 ------------------ .../openpilot/androidgcs/ObjectBrowser.java | 21 ---- .../org/openpilot/uavtalk/UAVMetaObject.java | 12 +-- 33 files changed, 62 insertions(+), 180 deletions(-) create mode 100644 androidgcs/.classpath create mode 100644 androidgcs/.project create mode 100644 androidgcs/.settings/org.eclipse.jdt.core.prefs delete mode 100644 androidgcs/bin/OpieMobi.apk delete mode 100644 androidgcs/bin/classes.dex delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class delete mode 100644 androidgcs/bin/resources.ap_ delete mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java delete mode 100644 androidgcs/res/layout/objectbrowser.xml delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/.gitignore b/.gitignore index a5af05849..c9478a9c1 100644 --- a/.gitignore +++ b/.gitignore @@ -64,10 +64,16 @@ ground/uavobjgenerator/uavobjgenerator.pro.user ground/uavobjects/uavobjects.pro.user ground/ground.pro.user -# Ignore GNU global tags files GPATH GRTAGS GSYMS GTAGS + +plane +quad + +# Ignore auto generated java files +androidgcs/bin/ +androidgcs/gen/ /.cproject /.project diff --git a/androidgcs/.classpath b/androidgcs/.classpath new file mode 100644 index 000000000..609aa00eb --- /dev/null +++ b/androidgcs/.classpath @@ -0,0 +1,7 @@ + + + + + + + diff --git a/androidgcs/.project b/androidgcs/.project new file mode 100644 index 000000000..c607dd2bd --- /dev/null +++ b/androidgcs/.project @@ -0,0 +1,33 @@ + + + androidgcs + + + + + + com.android.ide.eclipse.adt.ResourceManagerBuilder + + + + + com.android.ide.eclipse.adt.PreCompilerBuilder + + + + + org.eclipse.jdt.core.javabuilder + + + + + com.android.ide.eclipse.adt.ApkBuilder + + + + + + com.android.ide.eclipse.adt.AndroidNature + org.eclipse.jdt.core.javanature + + diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs new file mode 100644 index 000000000..f3fe4d6d6 --- /dev/null +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -0,0 +1,5 @@ +#Tue Mar 01 01:16:25 CST 2011 +eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 +org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 83d19e96c..7a96a6600 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -3,16 +3,10 @@ package="org.openpilot.androidgcs" android:versionCode="1" android:versionName="1.0"> - + - - - - - - + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk deleted file mode 100644 index 87a15c5e83805a3bb48265a78f9bd9154813cd35..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class deleted file mode 100644 index 306bc08c9eca5d510d01792bc7011e1ef8b75cc0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class deleted file mode 100644 index f69a8e17560897ad1adaae18fd15a3f75ac850a4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class deleted file mode 100644 index 43d486e461eb753c8772c3c239c81b3a83a13216..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class deleted file mode 100644 index d473cb81c8c6db44be5035f5848de2cfe8504c66..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class deleted file mode 100644 index 95af7d70364676903cbaee10411198d19f52394b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class deleted file mode 100644 index 7234b135ec1e4b601e8d271c48caf5fa07bd47ba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class deleted file mode 100644 index 5e520fa0eb6d9ad0cf329fa2572250588a3e365e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class deleted file mode 100644 index 5e228155303a29cd063056a485473fdd564000c7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class deleted file mode 100644 index f4a6dd7e4e5820644e459a4aa5652e5f2a69beba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ deleted file mode 100644 index 2452fd26f12793bb5445461ce339266070961506..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u diff --git a/androidgcs/default.properties b/androidgcs/default.properties index e2e8061f2..46769a720 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-8 +target=android-7 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java deleted file mode 100644 index 31e90ffd1..000000000 --- a/androidgcs/gen/org/openpilot/androidgcs/R.java +++ /dev/null @@ -1,31 +0,0 @@ -/* AUTO-GENERATED FILE. DO NOT MODIFY. - * - * This class was automatically generated by the - * aapt tool from the resource data it found. It - * should not be modified by hand. - */ - -package org.openpilot.androidgcs; - -public final class R { - public static final class attr { - } - public static final class color { - public static final int all_black=0x7f050001; - public static final int all_white=0x7f050000; - } - public static final class drawable { - public static final int icon=0x7f020000; - } - public static final class id { - public static final int objects=0x7f060000; - } - public static final class layout { - public static final int main=0x7f030000; - public static final int objectbrowser=0x7f030001; - } - public static final class string { - public static final int app_name=0x7f040001; - public static final int hello=0x7f040000; - } -} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..8074c4c571b8cd19e27f4ee5545df367420686d7 100644 GIT binary patch literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926
r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..1095584ec21f71cd0afc9e0993aa2209671b590c 100644 GIT binary patch literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..a07c69fa5a0f4da5d5efe96eea12a543154dbab6 100644 GIT binary patch literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(hvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml deleted file mode 100644 index 02a3f5dd6..000000000 --- a/androidgcs/res/layout/objectbrowser.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index eba6becf8..0d9f93bc2 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,7 +1,5 @@ - OpenPilot Android GCS - OpieMobi - #FFFFFF - #000000 + Hello World! + OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java deleted file mode 100644 index 190668d80..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java +++ /dev/null @@ -1,99 +0,0 @@ -/** - * - */ -package org.openpilot.androidgcs; - -import android.widget.AbsListView; -import android.widget.TextView; -import android.content.Context; -import android.view.Gravity; -import android.view.View; -import android.view.ViewGroup; -import android.widget.BaseExpandableListAdapter; - -/** - * @author jcotton81 - * - */ -public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { - - // Sample data set. children[i] contains the children (String[]) for - // groups[i]. - private String[] groups = { "Parent1", "Parent2", "Parent3" }; - private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; - - private Context context; - - public ObjBrowserExpandableListAdapter(Context context) { - this.context = context; - } - - public Object getChild(int groupPosition, int childPosition) { - return children[groupPosition][childPosition]; - } - - public long getChildId(int groupPosition, int childPosition) { - return childPosition; - } - - public int getChildrenCount(int groupPosition) { - int i = 0; - try { - i = children[groupPosition].length; - - } catch (Exception e) { - } - - return i; - } - - public TextView getGenericView() { - // Layout parameters for the ExpandableListView - AbsListView.LayoutParams lp = new AbsListView.LayoutParams( - ViewGroup.LayoutParams.FILL_PARENT, 64); - - TextView textView = new TextView(context); - textView.setLayoutParams(lp); - // Center the text vertically - textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); - // Set the text starting position - textView.setPadding(36, 0, 0, 0); - return textView; - } - - public View getChildView(int groupPosition, int childPosition, - boolean isLastChild, View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getChild(groupPosition, childPosition).toString()); - return textView; - } - - public Object getGroup(int groupPosition) { - return groups[groupPosition]; - } - - public int getGroupCount() { - return groups.length; - } - - public long getGroupId(int groupPosition) { - return groupPosition; - } - - public View getGroupView(int groupPosition, boolean isExpanded, - View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getGroup(groupPosition).toString()); - return textView; - } - - public boolean isChildSelectable(int groupPosition, int childPosition) { - return true; - } - - public boolean hasStableIds() { - return true; - } - - -} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java deleted file mode 100644 index 19e9b2812..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ /dev/null @@ -1,21 +0,0 @@ -package org.openpilot.androidgcs; - -import android.app.Activity; -import android.os.Bundle; - -import android.widget.*; - -public class ObjectBrowser extends Activity { - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - - setContentView(R.layout.objectbrowser); - ExpandableListAdapter mAdapter; - ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); - mAdapter = new ObjBrowserExpandableListAdapter(this); - epView.setAdapter(mAdapter); - - } -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index a1e5773b9..e5197b02e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,13 +2,11 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, Boolean isSingleInst, String name) { - super(objID, isSingleInst, name); - // TODO Auto-generated constructor stub - } - - public UAVMetaObject(int objID, String mname, UAVDataObject obj) { - // TODO Auto-generated constructor stub + private UAVDataObject parent; + + public UAVMetaObject(int objID, String mname, UAVDataObject parent) { + super(objID, true, mname); + this.parent = parent; } @Override From 1810fb61a0dd1549be60621471f08111cc89bdc8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 22:27:58 -0600 Subject: [PATCH 041/165] Update the object template to be more consistent with ground code --- .../templates/uavobjecttemplate.java | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 285ad03aa..13eeeb724 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -29,30 +29,31 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectMetaData; -import org.openpilot.uavtalk.UAVObjectFieldDescription; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; + /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVObject{ +public class $(NAME) extends UAVDataObject{ $(FIELDSINIT) public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVObjectMetaData.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObjectMetaData.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObjectMetaData.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObjectMetaData.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObjectMetaData.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObjectMetaData.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObjectMetaData.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -65,7 +66,7 @@ $(FIELDSINIT) return "$(NAME)"; } - public String getObjDescription() { + public String getDescription() { return "$(DESCRIPTION)"; } From f0e4c10cfae12a45b6d30657f01b43a36fd60a54 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 2 Mar 2011 20:23:27 -0600 Subject: [PATCH 042/165] Continuing to work on the java code to be more consistent with GCS code --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 34 +++++++++++--- .../org/openpilot/uavtalk/UAVMetaObject.java | 47 +++++++++++++++---- .../src/org/openpilot/uavtalk/UAVObject.java | 36 ++++++++++---- .../templates/uavobjecttemplate.java | 30 ++++++++---- 5 files changed, 117 insertions(+), 31 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 609aa00eb..b24a2abf5 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -3,5 +3,6 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 12a4263c0..a2e6acf9e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -2,17 +2,20 @@ package org.openpilot.uavtalk; public abstract class UAVDataObject extends UAVObject { + /** + * @brief Constructor for UAVDataObject + * @param objID the object id to be created + * @param isSingleInst + * @param isSet + * @param name + */ public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); } - public void initialize(int instID, UAVMetaObject mobj) { - - } + public abstract void initialize(int instID, UAVMetaObject mobj); - public void initialize(UAVMetaObject mobj) { - - } + public abstract void initialize(UAVMetaObject mobj); Boolean isSettings() { return null; @@ -22,6 +25,23 @@ public abstract class UAVDataObject extends UAVObject { return null; } - public abstract UAVDataObject clone(int instID); + public UAVDataObject clone(int instID) { + try { + return (UAVDataObject) super.clone(); + } catch (CloneNotSupportedException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + return null; + } + +public: + static int OBJID = $(OBJIDHEX); + static String NAME; + static String DESCRIPTION; + static boolean ISSINGLEINST = $(ISSINGLEINST); + static boolean ISSETTINGS = $(ISSETTINGS); + static int NUMBYTES = sizeof(DataFields); + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index e5197b02e..9c2e3b12d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,23 +2,41 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - private UAVDataObject parent; - - public UAVMetaObject(int objID, String mname, UAVDataObject parent) { - super(objID, true, mname); + public UAVMetaObject(int objID, String name, UAVDataObject parent) { + super(objID, true, name); this.parent = parent; + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + } + + UAVObject getParentObject() { + return parent; } @Override public void deserialize(byte[] arr, int offset) { // TODO Auto-generated method stub - + } @Override - public UAVMetaObject getDefaultMetadata() { - // TODO Auto-generated method stub - return null; + public Metadata getMetadata() { + return ownMetadata; + } + + @Override + public Metadata getDefaultMetadata() { + return ownMetadata; } @Override @@ -45,4 +63,17 @@ public class UAVMetaObject extends UAVObject { return null; } + + public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); + UAVObject* getParentObject(); + void setMetadata(const Metadata& mdata); + void setData(const Metadata& mdata); + Metadata getData(); + + + private UAVObject parent; + private Metadata ownMetadata; + private Metadata parentMetadata; + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index c5ffc9d21..1decf3563 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -20,11 +20,27 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY } ; - - - private Boolean isSingleInst; - private int instID; - private UAVMetaObject meta; + + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; + + final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; public UAVObject(int objID, Boolean isSingleInst, String name) { assert(objID == getObjID()); // ID is in implementation code, make sure it matches object @@ -62,9 +78,13 @@ public abstract class UAVObject { return true; } - public void setMetadata(UAVMetaObject obj) { meta = obj; } - public UAVMetaObject getMetadata() { return meta; } - public abstract UAVMetaObject getDefaultMetadata(); + public abstract void setMetadata(Metadata obj); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; /* // Unported code from QT diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 13eeeb724..fa09f782f 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -31,29 +31,34 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVDataObject{ +public class $(NAME) extends UAVDataObject { $(FIELDSINIT) + public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + } + public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -69,6 +74,15 @@ $(FIELDSINIT) public String getDescription() { return "$(DESCRIPTION)"; } +protected: + // Constants + static final int OBJID = $(OBJIDHEX); + static final String NAME; + static final String DESCRIPTION; + static final boolean ISSINGLEINST = $(ISSINGLEINST); + static final boolean ISSETTINGS = $(ISSETTINGS); + static final int NUMBYTES = sizeof(DataFields); + $(GETTERSETTER) } \ No newline at end of file From c3244cf5a231e302c6ccd59cfd0d306bbb584aeb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 00:06:17 -0600 Subject: [PATCH 043/165] Import of UAVObjectField object. This differs a bit from the GCS implementation in that the data is stored within the field instead of being packed back into a continugious memory region. This is because java doesn't allow casting to struct so the memory access isn't a useful feature. --- .../org/openpilot/uavtalk/UAVObjectField.java | 468 ++++++++++++++++++ 1 file changed, 468 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java new file mode 100644 index 000000000..832e7048a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -0,0 +1,468 @@ +package org.openpilot.uavtalk; + +import java.io.Serializable; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.ArrayList; +import java.util.List; + +public class UAVObjectField { + + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + + public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { + List elementNames = new ArrayList(); + // Set element names + for (int n = 0; n < numElements; ++n) + { + elementNames.add(String.valueOf(n)); + } + // Initialize + constructorInitialize(name, units, type, elementNames, options); + } + + public UAVObjectField(String name, String units, FieldType type, List elementNames, List options) { + constructorInitialize(name, units, type, elementNames, options); + } + + public void initialize(byte[] data, int dataOffset, UAVObject obj){ + this.data = data; + this.offset = dataOffset; + this.obj = obj; + clear(); + + } + + public UAVObject getObject() { + return obj; + } + + public FieldType getType() { + return type; + } + + public String getTypeAsString() { + switch (type) + { + case INT8: + return "int8"; + case INT16: + return "int16"; + case INT32: + return "int32"; + case UINT8: + return "uint8"; + case UINT16: + return "uint16"; + case UINT32: + return "uint32"; + case FLOAT32: + return "float32"; + case ENUM: + return "enum"; + case STRING: + return "string"; + default: + return ""; + } + } + + public String getName() { + return name; + } + + public String getUnits() { + return units; + } + + public int getNumElements() { + return numElements; + } + + public List getElementNames() { + return elementNames; + } + + public List getOptions() { + return options; + } + + /** + * This function copies this field from the internal storage of the parent object + * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) + * to the arm/uavtalk standard (little endian) + * @param dataOut + * @return +] + * @throws Exception */ + public int pack(ByteBuffer dataOut) throws Exception { + //QMutexLocker locker(obj->getMutex()); + // Pack each element in output buffer + dataOut.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case INT16: + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case INT32: + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case UINT8: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case UINT16: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case UINT32: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case FLOAT32: + for (int index = 0; index < numElements; ++index) + dataOut.putFloat((Float) getValue(index)); + break; + case ENUM: + List l = (List) data; + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) l.get(index)); + break; + case STRING: + // TODO: Implement strings + throw new Exception("Strings not yet implemented"); + } + // Done + return getNumBytes(); + } + + public int unpack(ByteBuffer dataIn) throws Exception { + // Unpack each element from input buffer + dataIn.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case INT16: + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case INT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case UINT8: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case UINT16: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case UINT32: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case FLOAT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Float) dataIn.getFloat(), index); + } + break; + case ENUM: + List l = (List) data; + for (int index = 0 ; index < numElements; ++index) { + l.set(index, dataIn.get(index)); + } + break; + case STRING: + throw new Exception("Strings not handled"); + } + // Done + return getNumBytes(); + } + + Object getValue() throws Exception { return getValue(0); }; + Object getValue(int index) throws Exception { +// QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + { + return null; + } + + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + return l.get(index); + } + case UINT8: + case UINT16: + case UINT32: + { + // TODO: Correctly deal with unsigned values + List l = (List) data; + return l.get(index); + } + case FLOAT32: + { + List l = (List) data; + return l.get(index); + } + case ENUM: + { + List l = (List) data; + Byte val = l.get(index); + + if(val >= options.size() || val < 0) + throw new Exception("Invalid value for" + name); + + return options.get(val); + } + case STRING: + { + throw new Exception("Shit I should do this"); + } + } + // If this point is reached then we got an invalid type + return null; + } + + public void setValue(Object data) throws Exception { setValue(data,0); } + public void setValue(Object data, int index) throws Exception { + // QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + throw new Exception("Index out of bounds"); + + // Get metadata + UAVObject.Metadata mdata = obj.getMetadata(); + // Update value if the access mode permits + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + { + ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case UINT8: + case UINT16: + case UINT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case FLOAT32: + { + List l = (List) data; + l.set(index, (Float) data); + break; + } + case ENUM: + { + byte val = (byte) options.indexOf((String) data); + if(val < 0) throw new Exception("Enumerated value not found"); + List l = (List) data; + l.set(index, val); + break; + } + case STRING: + { + throw new Exception("Sorry I haven't implemented strings yet"); + } + } + } + } + + public double getDouble() throws Exception { return getDouble(0); }; + public double getDouble(int index) throws Exception { + return Double.valueOf((Double) getValue(index)); + } + + void setDouble(double value) throws Exception { setDouble(value, 0); }; + void setDouble(double value, int index) throws Exception { + setValue(value, index); + } + + int getDataOffset() { + return offset; + } + + int getNumBytes() { + return numBytesPerElement * numElements; + } + + int getNumBytesElement() { + return numBytesPerElement; + } + + boolean isNumeric() { + switch (type) + { + case INT8: + return true; + case INT16: + return true; + case INT32: + return true; + case UINT8: + return true; + case UINT16: + return true; + case UINT32: + return true; + case FLOAT32: + return true; + case ENUM: + return false; + case STRING: + return false; + default: + return false; + } + } + + boolean isText() { + switch (type) + { + case INT8: + return false; + case INT16: + return false; + case INT32: + return false; + case UINT8: + return false; + case UINT16: + return false; + case UINT32: + return false; + case FLOAT32: + return false; + case ENUM: + return true; + case STRING: + return true; + default: + return false; + } + } + + public String toString() { + String sout = new String(); + sout += name + ": [ "; + for (int n = 0; n < numElements; ++n) + { + sout += String.valueOf(n) + " "; + } + + sout += "] " + units + "\n"; + return sout; + } + + void fieldUpdated(UAVObjectField field) { + + } + + public void clear() { + // TODO: This accesses a shared array of the parent + } + + public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + // Copy params + this.name = name; + this.units = units; + this.type = type; + this.options = options; + this.numElements = elementNames.size(); + this.offset = 0; + this.data = null; + this.obj = null; + this.elementNames = elementNames; + // Set field size + switch (type) + { + case INT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case INT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case INT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case UINT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case UINT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case UINT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case FLOAT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case ENUM: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case STRING: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + default: + numBytesPerElement = 0; + } + } + + + private String name; + private String units; + private FieldType type; + private List elementNames; + private List options; + private int numElements; + private int numBytesPerElement; + private int offset; + private Object data; + private UAVObject obj; + +} From cd8fac766cb8a2e1b041209d6ceb9e3c53fef7ec Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 10:22:11 -0600 Subject: [PATCH 044/165] Some changes to the object field to get it to initialze the array to be the right length --- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 75 ++++++++++++++----- 2 files changed, 56 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 1decf3563..aaf32151f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -84,7 +84,7 @@ public abstract class UAVObject { private Boolean isSingleInst; private int instID; - private UAVMetaObject meta; + private Metadata meta; /* // Unported code from QT diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 832e7048a..d09008cbe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -25,10 +25,8 @@ public class UAVObjectField { constructorInitialize(name, units, type, elementNames, options); } - public void initialize(byte[] data, int dataOffset, UAVObject obj){ - this.data = data; - this.offset = dataOffset; - this.obj = obj; + public void initialize(UAVObject obj){ + this.obj = obj; clear(); } @@ -258,10 +256,13 @@ public class UAVObjectField { if ( index >= numElements ) throw new Exception("Index out of bounds"); + System.out.println(data.toString()); + System.out.println(this.data.toString()); + // Get metadata - UAVObject.Metadata mdata = obj.getMetadata(); + //UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) @@ -270,7 +271,7 @@ public class UAVObjectField { case INT16: case INT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } @@ -278,13 +279,13 @@ public class UAVObjectField { case UINT16: case UINT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } case FLOAT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Float) data); break; } @@ -292,7 +293,7 @@ public class UAVObjectField { { byte val = (byte) options.indexOf((String) data); if(val < 0) throw new Exception("Enumerated value not found"); - List l = (List) data; + List l = (List) this.data; l.set(index, val); break; } @@ -395,7 +396,37 @@ public class UAVObjectField { } public void clear() { - // TODO: This accesses a shared array of the parent + switch (type) + { + case INT8: + case INT16: + case INT32: + case UINT8: + case UINT16: + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add(0); + } + break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte)0); + } + break; + case STRING: + // TODO: Add string + break; + default: + numBytesPerElement = 0; + } } public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { @@ -410,47 +441,51 @@ public class UAVObjectField { this.obj = null; this.elementNames = elementNames; // Set field size + System.out.println("Initializing: type " + type + this.numElements); + switch (type) { case INT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case STRING: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; default: numBytesPerElement = 0; } + clear(); + System.out.println("Initialized: " + this.data.toString()); } From ae43ec3eba7fae289043600213d40b077188d11e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 5 Mar 2011 12:29:48 -0600 Subject: [PATCH 045/165] More updates to UAVObject and Field for android app --- .../src/org/openpilot/uavtalk/UAVObject.java | 598 ++++++++++++++---- .../org/openpilot/uavtalk/UAVObjectField.java | 3 +- 2 files changed, 475 insertions(+), 126 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index aaf32151f..f987a03a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,137 +1,487 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.List; +import java.util.ListIterator; + public abstract class UAVObject { - - - /** - * Object update mode - */ - public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ - UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; - /** - * Access mode - */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; - - /** - * Access mode - */ - public enum Acked{ - FALSE, - TRUE - } ; - - final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; - public UAVObject(int objID, Boolean isSingleInst, String name) { - assert(objID == getObjID()); // ID is in implementation code, make sure it matches object - assert(name.equals(getName())); - this.isSingleInst = isSingleInst; - meta = getDefaultMetadata(); - }; - - public void initialize(int instID) { - this.instID = instID; - } - - public int getInstID() { return instID; } - public Boolean isSingleInstance() { return isSingleInst; } - public String getName() { return getObjName(); } // matching QT API to the current autogen code - - public abstract int getObjID(); - public abstract String getDescription(); - public abstract String getObjName(); - - int getNumBytes() { - return serialize().length; - } + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; - // The name of the serializer and deserialize from the autogenerated code - public abstract byte[] serialize(); - public abstract void deserialize(byte[] arr,int offset); - - byte [] pack() { - return serialize(); - } - - Boolean unpack(byte [] data) { - deserialize(data, 0); - return true; - } - - public abstract void setMetadata(Metadata obj); - public abstract Metadata getMetadata(); - public abstract Metadata getDefaultMetadata(); + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; - private Boolean isSingleInst; - private int instID; - private Metadata meta; + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; - /* - // Unported code from QT - bool save(); - bool save(QFile& file); - bool load(); - bool load(QFile& file); - virtual void setMetadata(const Metadata& mdata) = 0; - virtual Metadata getMetadata() = 0; - virtual Metadata getDefaultMetadata() = 0; - void requestUpdate(); - void updated(); - void lock(); - void lock(int timeoutMs); - void unlock(); - QMutex* getMutex(); - qint32 getNumFields(); - QList getFields(); - UAVObjectField* getField(const QString& name); - QString toString(); - QString toStringBrief(); - QString toStringData(); - void emitTransactionCompleted(bool success); + protected final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; - signals: - void objectUpdated(UAVObject* obj); - void objectUpdatedAuto(UAVObject* obj); - void objectUpdatedManual(UAVObject* obj); - void objectUnpacked(UAVObject* obj); - void updateRequested(UAVObject* obj); - void transactionCompleted(UAVObject* obj, bool success); + public UAVObject(int objID, Boolean isSingleInst, String name) { + this.objID = objID; + this.instID = 0; + this.isSingleInst = isSingleInst; + this.name = name; + // this.mutex = new QMutex(QMutex::Recursive); + }; - private slots: - void fieldUpdated(UAVObjectField* field); + public void initialize(int instID) { + //QMutexLocker locker(mutex); + this.instID = instID; + } - protected: - quint32 objID; - quint32 instID; - bool isSingleInst; - QString name; - QString description; - quint32 numBytes; - QMutex* mutex; - quint8* data; - QList fields; + /** + * Initialize objects' data fields + * @param fields List of fields held by the object + * @param data Pointer to that actual object data, this is needed by the fields to access the data + * @param numBytes Number of bytes in the object (total, including all fields) + * @throws Exception When unable to unpack a field + */ + public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception + { + // TODO: QMutexLocker locker(mutex); + this.numBytes = numBytes; + this.data = data; + this.fields = fields; + // Initialize fields + for (int n = 0; n < fields.size(); ++n) + { + fields.get(n).initialize(this); + } + unpack(data); + } - void initializeFields(QList& fields, quint8* data, quint32 numBytes); - void setDescription(const QString& description); - */ + /** + * Get the object ID + */ + public int getObjID() + { + return objID; + } + + /** + * Get the instance ID + */ + public int getInstID() + { + return instID; + } + + /** + * Returns true if this is a single instance object + */ + public boolean isSingleInstance() + { + return isSingleInst; + } + + /** + * Get the name of the object + */ + public String getName() + { + return name; + } + + /** + * Get the description of the object + * @return The description of the object + */ + public String getDescription() + { + return description; + } + + /** + * Set the description of the object + * @param The description of the object + * @return + */ + public void setDescription(String description) + { + this.description = description; + } + + + /** + * Get the total number of bytes of the object's data + */ + public int getNumBytes() + { + return numBytes; + } + + // /** + // * Request that this object is updated with the latest values from the autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ + // + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ + // + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ + // + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } + + /** + * Get the number of fields held by this object + */ + public int getNumFields() + { + //QMutexLocker locker(mutex); + return fields.size(); + } + + /** + * Get the object's fields + */ + public List getFields() + { + //QMutexLocker locker(mutex); + return fields; + } + + /** + * Get a specific field + * @throws Exception + * @returns The field or NULL if not found + */ + public UAVObjectField getField(String name) throws Exception + { + //QMutexLocker locker(mutex); + // Look for field + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + if(field.getName().equals(name)) + return field; + } + throw new Exception("Field not found"); + } + + /** + * Pack the object data into a byte array + * @param dataOut ByteBuffer to receive the data. + * @throws Exception + * @returns The number of bytes copied + * @note The array must already have enough space allocated for the object + */ + public int pack(ByteBuffer dataOut) throws Exception + { + // QMutexLocker locker(mutex); + if(dataOut.remaining() < getNumBytes()) + throw new Exception("Not enough bytes in ByteBuffer to pack object"); + int numBytes = 0; + + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.pack(dataOut); + } + return numBytes; + } + + /** + * Unpack the object data from a byte array + * @param dataIn The ByteBuffer to pull data from + * @throws Exception + * @returns The number of bytes copied + */ + public int unpack(ByteBuffer dataIn) throws Exception + { + // QMutexLocker locker(mutex); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.unpack(dataIn); + } + return numBytes; + // TODO: Callbacks + //emit objectUnpacked(this); // trigger object updated event + //emit objectUpdated(this); + } + + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } + // + // // Write object + // if ( !save(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } + // + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } + // + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } + // + // // Done + // return true; + // } + // + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } + // + // // Load object + // if ( !load(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } + // + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } + // + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); + // + // // Done + // return true; + // } + + /** + * Return a string with the object information + */ + @Override + public String toString() + { + return toStringBrief() + toStringData(); + } + + /** + * Return a string with the object information (only the header) + */ + public String toStringBrief() + { + return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", + getName(), + getObjID(), + getInstID(), + getNumBytes(), + isSingleInstance()); + } + + /** + * Return a string with the object information (only the data) + */ + public String toStringData() + { + String s = new String(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + s += field.toString(); + } + return s; + } + + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } + + /** + * Java specific functions + */ + public UAVObject clone() { + return (UAVObject) clone(); + } + /** + * Abstract functions + */ + public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + public abstract UAVDataObject clone(int instID); + protected abstract void setDefaultFieldValues(); + + /** + * Private data for the object, common to all + */ + protected int objID; + protected int instID; + protected boolean isSingleInst; + protected String name; + protected String description; + protected int numBytes; + // TODO: QMutex* mutex; + protected ByteBuffer data; + protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d09008cbe..c7c774199 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,7 @@ public class UAVObjectField { * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) * to the arm/uavtalk standard (little endian) * @param dataOut - * @return -] + * @return the number of bytes added * @throws Exception */ public int pack(ByteBuffer dataOut) throws Exception { //QMutexLocker locker(obj->getMutex()); From a9b28687eafb2dca1d91a68e036f58a8f49ce251 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:20 -0600 Subject: [PATCH 046/165] More work on the java UAVObject implementation --- .../org/openpilot/uavtalk/UAVDataObject.java | 93 ++- .../org/openpilot/uavtalk/UAVMetaObject.java | 140 +++-- .../src/org/openpilot/uavtalk/UAVObject.java | 581 +++++++++--------- .../org/openpilot/uavtalk/UAVObjectField.java | 35 +- .../openpilot/uavtalk/UAVObjectManager.java | 30 +- 5 files changed, 497 insertions(+), 382 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index a2e6acf9e..f0a2248f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,39 +9,78 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { super(objID, isSingleInst, name); + mobj = null; + this.isSet = isSet; } - - public abstract void initialize(int instID, UAVMetaObject mobj); - - public abstract void initialize(UAVMetaObject mobj); - - Boolean isSettings() { - return null; + /** + * Initialize instance ID and assign a metaobject + */ + public void initialize(int instID, UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + super.initialize(instID); + } + + /** + * Assign a metaobject + */ + public void initialize(UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + } + + /** + * Returns true if this is a data object holding module settings + */ + public boolean isSettings() + { + return isSet; + } + + /** + * Set the object's metadata + */ + public void setMetadata(Metadata mdata) + { + if ( mobj != null ) + { + mobj.setData(mdata); + } + } + + /** + * Get the object's metadata + */ + public Metadata getMetadata() + { + if ( mobj != null) + { + return mobj.getData(); + } + else + { + return getDefaultMetadata(); + } + } + + /** + * Get the metaobject + */ + public UAVMetaObject getMetaObject() + { + return mobj; } - - UAVMetaObject getMetaObject() { - return null; - } + // TODO: Make abstract public UAVDataObject clone(int instID) { - try { - return (UAVDataObject) super.clone(); - } catch (CloneNotSupportedException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - return null; + return (UAVDataObject) super.clone(); } -public: - static int OBJID = $(OBJIDHEX); - static String NAME; - static String DESCRIPTION; - static boolean ISSINGLEINST = $(ISSINGLEINST); - static boolean ISSETTINGS = $(ISSETTINGS); - static int NUMBYTES = sizeof(DataFields); - + private UAVMetaObject mobj; + private boolean isSet; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 9c2e3b12d..70e661d46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -1,76 +1,116 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, String name, UAVDataObject parent) { + public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; - - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.loggingUpdatePeriod = 0; - + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + // Setup fields + List boolEnum = new ArrayList(); + boolEnum.add("False"); + boolEnum.add("True"); + + List updateModeEnum = new ArrayList(); + updateModeEnum.add("Periodic"); + updateModeEnum.add("On Change"); + updateModeEnum.add("Manual"); + updateModeEnum.add("Never"); + + List accessModeEnum = new ArrayList(); + accessModeEnum.add("Read/Write"); + accessModeEnum.add("Read Only"); + + List fields = new ArrayList(); + fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + + // Initialize parent + super.initialize(0); + super.initializeFields(fields, ByteBuffer.allocate(10), 10); + + // Setup metadata of parent + parentMetadata = parent.getDefaultMetadata(); } - UAVObject getParentObject() { + /** + * Get the parent object + */ + public UAVObject getParentObject() + { return parent; } - @Override - public void deserialize(byte[] arr, int offset) { - // TODO Auto-generated method stub - + /** + * Set the metadata of the metaobject, this function will + * do nothing since metaobjects have read-only metadata. + */ + public void setMetadata(Metadata mdata) + { + return; // can not update metaobject's metadata } - @Override - public Metadata getMetadata() { + /** + * Get the metadata of the metaobject + */ + public Metadata getMetadata() + { return ownMetadata; } - @Override - public Metadata getDefaultMetadata() { - return ownMetadata; + /** + * Get the default metadata + */ + public Metadata getDefaultMetadata() + { + return ownMetadata; } - @Override - public String getDescription() { - // TODO Auto-generated method stub - return null; + /** + * Set the metadata held by the metaobject + */ + public void setData(Metadata mdata) + { + //QMutexLocker locker(mutex); + parentMetadata = mdata; + // TODO: Callbacks + // emit objectUpdatedAuto(this); // trigger object updated event + // emit objectUpdated(this); } - @Override - public int getObjID() { - // TODO Auto-generated method stub - return 0; + /** + * Get the metadata held by the metaobject + */ + public Metadata getData() + { +// QMutexLocker locker(mutex); + return parentMetadata; } - @Override - public String getObjName() { - // TODO Auto-generated method stub - return null; - } - @Override - public byte[] serialize() { - // TODO Auto-generated method stub - return null; - } - - - public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); - UAVObject* getParentObject(); - void setMetadata(const Metadata& mdata); - void setData(const Metadata& mdata); - Metadata getData(); - - private UAVObject parent; private Metadata ownMetadata; private Metadata parentMetadata; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index f987a03a9..926440805 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -6,241 +6,274 @@ import java.util.ListIterator; public abstract class UAVObject { - /** * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_PERIODIC, /** + * Automatically update object at periodic + * intervals + */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; + UPDATEMODE_MANUAL, /** + * Manually update object, by calling the updated() + * function + */ + UPDATEMODE_NEVER + /** Object is never updated */ + }; /** * Access mode */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; + public enum AccessMode { + ACCESS_READWRITE, ACCESS_READONLY + }; /** * Access mode */ - public enum Acked{ - FALSE, - TRUE - } ; + public enum Acked { + FALSE, TRUE + }; - protected final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; + public final class Metadata { + public AccessMode flightAccess; + /** + * Defines the access level for the local flight transactions (readonly + * and readwrite) + */ + public AccessMode gcsAccess; + /** + * Defines the access level for the local GCS transactions (readonly and + * readwrite) + */ + public Acked flightTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode flightTelemetryUpdateMode; + /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; + /** + * Update period used by the autopilot (only if telemetry mode is + * PERIODIC) + */ + public Acked gcsTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode gcsTelemetryUpdateMode; + /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; + /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; + /** + * Update period used by the logging module (only if logging mode is + * PERIODIC) + */ + }; public UAVObject(int objID, Boolean isSingleInst, String name) { this.objID = objID; this.instID = 0; this.isSingleInst = isSingleInst; this.name = name; - // this.mutex = new QMutex(QMutex::Recursive); + // this.mutex = new QMutex(QMutex::Recursive); }; public void initialize(int instID) { - //QMutexLocker locker(mutex); + // QMutexLocker locker(mutex); this.instID = instID; } /** * Initialize objects' data fields - * @param fields List of fields held by the object - * @param data Pointer to that actual object data, this is needed by the fields to access the data - * @param numBytes Number of bytes in the object (total, including all fields) - * @throws Exception When unable to unpack a field + * + * @param fields + * List of fields held by the object + * @param data + * Pointer to that actual object data, this is needed by the + * fields to access the data + * @param numBytes + * Number of bytes in the object (total, including all fields) + * @throws Exception + * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception - { - // TODO: QMutexLocker locker(mutex); + public void initializeFields(List fields, ByteBuffer data, + int numBytes) throws Exception { + // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; - this.data = data; +// this.data = data; this.fields = fields; // Initialize fields - for (int n = 0; n < fields.size(); ++n) - { + for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } - unpack(data); +// unpack(data); } /** * Get the object ID */ - public int getObjID() - { + public int getObjID() { return objID; } /** * Get the instance ID */ - public int getInstID() - { + public int getInstID() { return instID; } /** * Returns true if this is a single instance object */ - public boolean isSingleInstance() - { + public boolean isSingleInstance() { return isSingleInst; } /** * Get the name of the object */ - public String getName() - { + public String getName() { return name; } /** * Get the description of the object + * * @return The description of the object */ - public String getDescription() - { + public String getDescription() { return description; } /** * Set the description of the object - * @param The description of the object - * @return + * + * @param The + * description of the object + * @return */ - public void setDescription(String description) - { + public void setDescription(String description) { this.description = description; } - /** * Get the total number of bytes of the object's data */ - public int getNumBytes() - { + public int getNumBytes() { return numBytes; } - // /** - // * Request that this object is updated with the latest values from the autopilot - // */ - // /* void UAVObject::requestUpdate() - // { - // emit updateRequested(this); - // } */ + // /** + // * Request that this object is updated with the latest values from the + // autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ // - // /** - // * Signal that the object has been updated - // */ - // /* void UAVObject::updated() - // { - // emit objectUpdatedManual(this); - // emit objectUpdated(this); - // } */ + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock() - // { - // mutex->lock(); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock(int timeoutMs) - // { - // mutex->tryLock(timeoutMs); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ // - // /** - // * Unlock mutex of this object - // */ - // /* void UAVObject::unlock() - // { - // mutex->unlock(); - // } */ + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ // - // /** - // * Get object's mutex - // */ - // QMutex* UAVObject::getMutex() - // { - // return mutex; - // } + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } /** * Get the number of fields held by this object */ - public int getNumFields() - { - //QMutexLocker locker(mutex); + public int getNumFields() { + // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() - { - //QMutexLocker locker(mutex); + public List getFields() { + // QMutexLocker locker(mutex); return fields; } /** * Get a specific field - * @throws Exception + * + * @throws Exception * @returns The field or NULL if not found */ - public UAVObjectField getField(String name) throws Exception - { - //QMutexLocker locker(mutex); + public UAVObjectField getField(String name) { + // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); - if(field.getName().equals(name)) + if (field.getName().equals(name)) return field; } - throw new Exception("Field not found"); + //throw new Exception("Field not found"); + return null; } /** * Pack the object data into a byte array - * @param dataOut ByteBuffer to receive the data. - * @throws Exception + * + * @param dataOut + * ByteBuffer to receive the data. + * @throws Exception * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception - { + public int pack(ByteBuffer dataOut) throws Exception { // QMutexLocker locker(mutex); - if(dataOut.remaining() < getNumBytes()) + if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); numBytes += field.pack(dataOut); } @@ -249,232 +282,232 @@ public abstract class UAVObject { /** * Unpack the object data from a byte array - * @param dataIn The ByteBuffer to pull data from - * @throws Exception + * + * @param dataIn + * The ByteBuffer to pull data from + * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception - { + public int unpack(ByteBuffer dataIn) throws Exception { + if( dataIn == null ) + return 0; + System.out.println( dataIn.toString() ); // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); + System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; // TODO: Callbacks - //emit objectUnpacked(this); // trigger object updated event - //emit objectUpdated(this); + // emit objectUnpacked(this); // trigger object updated event + // emit objectUpdated(this); } - // /** - // * Save the object data to the file. - // * The file will be created in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save() - // { - // QMutexLocker locker(mutex); + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::WriteOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } // - // // Write object - // if ( !save(file) ) - // { - // return false; - // } + // // Write object + // if ( !save(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Save the object data to the file. - // * The file is expected to be already open for writting. - // * The data will be appended and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Write the object ID - // qToLittleEndian(objID, tmpId); - // if ( file.write((const char*)tmpId, 4) == -1 ) - // { - // return false; - // } + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } // - // // Write the instance ID - // if (!isSingleInst) - // { - // qToLittleEndian(instID, tmpId); - // if ( file.write((const char*)tmpId, 2) == -1 ) - // { - // return false; - // } - // } + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } // - // // Write the data - // pack(buffer); - // if ( file.write((const char*)buffer, numBytes) == -1 ) - // { - // return false; - // } + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } // - // // Done - // return true; - // } + // // Done + // return true; + // } // - // /** - // * Load the object data from a file. - // * The file will be openned in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load() - // { - // QMutexLocker locker(mutex); + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::ReadOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } // - // // Load object - // if ( !load(file) ) - // { - // return false; - // } + // // Load object + // if ( !load(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Load the object data from file. - // * The file is expected to be already open for reading. - // * The data will be read and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Read the object ID - // if ( file.read((char*)tmpId, 4) != 4 ) - // { - // return false; - // } + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != objID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } // - // // Read the instance ID - // if ( file.read((char*)tmpId, 2) != 2 ) - // { - // return false; - // } + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != instID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } // - // // Read and unpack the data - // if ( file.read((char*)buffer, numBytes) != numBytes ) - // { - // return false; - // } - // unpack(buffer); + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); // - // // Done - // return true; - // } + // // Done + // return true; + // } /** * Return a string with the object information */ @Override - public String toString() - { + public String toString() { return toStringBrief() + toStringData(); } /** * Return a string with the object information (only the header) */ - public String toStringBrief() - { - return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", - getName(), - getObjID(), - getInstID(), - getNumBytes(), - isSingleInstance()); + public String toStringBrief() { + return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; + // getName(), getObjID(), getInstID(), getNumBytes(), + // isSingleInstance()); } /** * Return a string with the object information (only the data) */ - public String toStringData() - { + public String toStringData() { String s = new String(); ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); s += field.toString(); } return s; } - // /** - // * Emit the transactionCompleted event (used by the UAVTalk plugin) - // */ - // void UAVObject::emitTransactionCompleted(bool success) - // { - // emit transactionCompleted(this, success); - // } + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } - /** + /** * Java specific functions */ public UAVObject clone() { return (UAVObject) clone(); } + /** * Abstract functions */ public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); - public abstract UAVDataObject clone(int instID); - protected abstract void setDefaultFieldValues(); /** * Private data for the object, common to all - */ + */ protected int objID; protected int instID; protected boolean isSingleInst; @@ -482,6 +515,6 @@ public abstract class UAVObject { protected String description; protected int numBytes; // TODO: QMutex* mutex; - protected ByteBuffer data; +// protected ByteBuffer data; protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c7c774199..b37c992fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -248,34 +248,37 @@ public class UAVObjectField { return null; } - public void setValue(Object data) throws Exception { setValue(data,0); } - public void setValue(Object data, int index) throws Exception { + public void setValue(Object data) { setValue(data,0); } + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) - throw new Exception("Index out of bounds"); + //throw new Exception("Index out of bounds"); System.out.println(data.toString()); System.out.println(this.data.toString()); // Get metadata - //UAVObject.Metadata mdata = obj.getMetadata(); + UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { - ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) { case INT8: + data = new Integer((Byte) data); case INT16: + data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,(Integer) data); break; } case UINT8: + data = new Integer((Byte) data); case UINT16: + data = new Integer((Short) data); case UINT32: { List l = (List) this.data; @@ -291,14 +294,14 @@ public class UAVObjectField { case ENUM: { byte val = (byte) options.indexOf((String) data); - if(val < 0) throw new Exception("Enumerated value not found"); + //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); break; } case STRING: { - throw new Exception("Sorry I haven't implemented strings yet"); + //throw new Exception("Sorry I haven't implemented strings yet"); } } } @@ -309,24 +312,24 @@ public class UAVObjectField { return Double.valueOf((Double) getValue(index)); } - void setDouble(double value) throws Exception { setDouble(value, 0); }; - void setDouble(double value, int index) throws Exception { + public void setDouble(double value) throws Exception { setDouble(value, 0); }; + public void setDouble(double value, int index) throws Exception { setValue(value, index); } - int getDataOffset() { + public int getDataOffset() { return offset; } - int getNumBytes() { + public int getNumBytes() { return numBytesPerElement * numElements; } - int getNumBytesElement() { + public int getNumBytesElement() { return numBytesPerElement; } - boolean isNumeric() { + public boolean isNumeric() { switch (type) { case INT8: @@ -352,7 +355,7 @@ public class UAVObjectField { } } - boolean isText() { + public boolean isText() { switch (type) { case INT8: diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 3091595f0..d75b14b85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -21,8 +21,9 @@ public class UAVObjectManager { * A new instance can be created directly by instantiating a new object or by calling clone() of * an existing object. The object will be registered and will be properly initialized so that it can accept * updates. + * @throws Exception */ - Boolean registerObject(UAVDataObject obj) + public boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -126,7 +127,7 @@ public class UAVObjectManager { return true; } - void addObject(UAVObject obj) + public void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -139,7 +140,7 @@ public class UAVObjectManager { * Get all objects. A two dimentional QList is returned. Objects are grouped by * instances of the same object type. */ - List> getObjects() + public List> getObjects() { //QMutexLocker locker(mutex); return objects; @@ -148,7 +149,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - List< List > getDataObjects() + public List< List > getDataObjects() { return new ArrayList>(); @@ -186,7 +187,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return MetaObjects. */ - List > getMetaObjects() + public List > getMetaObjects() { return new ArrayList< List >(); /* @@ -227,7 +228,7 @@ public class UAVObjectManager { * Get a specific object given its name and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(String name, int instId) + public UAVObject getObject(String name, int instId) { return getObject(name, 0, instId); } @@ -236,7 +237,7 @@ public class UAVObjectManager { * Get a specific object given its object and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(int objId, int instId) + public UAVObject getObject(int objId, int instId) { return getObject(null, objId, instId); } @@ -244,7 +245,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - UAVObject getObject(String name, int objId, int instId) + public UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -271,7 +272,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by name */ - List getObjectInstances(String name) + public List getObjectInstances(String name) { return getObjectInstances(name, 0); } @@ -279,7 +280,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by its ID */ - List getObjectInstances(int objId) + public List getObjectInstances(int objId) { return getObjectInstances(null, objId); } @@ -287,7 +288,7 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - List getObjectInstances(String name, int objId) + public List getObjectInstances(String name, int objId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -307,7 +308,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its name */ - int getNumInstances(String name) + public int getNumInstances(String name) { return getNumInstances(name, 0); } @@ -315,7 +316,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its ID */ - int getNumInstances(int objId) + public int getNumInstances(int objId) { return getNumInstances(null, objId); } @@ -323,10 +324,9 @@ public class UAVObjectManager { /** * Helper function for public getNumInstances */ - int getNumInstances(String name, int objId) + public int getNumInstances(String name, int objId) { return getObjectInstances(name,objId).size(); } - } From 9a4c1586906a80e26a5cba1dde33c2f1cde53222 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:46 -0600 Subject: [PATCH 047/165] Java autogenerated code to be more compatible with gcs code --- .../templates/uavobjecttemplate.java | 127 +++-- .../java/uavobjectgeneratorjava.cpp | 434 ++++++++---------- .../generators/java/uavobjectgeneratorjava.h | 16 +- 3 files changed, 278 insertions(+), 299 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index fa09f782f..af8f48fce 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -28,61 +28,110 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; -import org.openpilot.uavtalk.UAVObjectField; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) -**/ + **/ public class $(NAME) extends UAVDataObject { + public $(NAME)() throws Exception { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + $(FIELDSINIT) - public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - } + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytesElement(); + } + NUMBYTES = numBytes; + - public void setGeneratedMetaData() { + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } - getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; + } - } - - public int getObjID() { - return $(OBJIDHEX); - } - - public String getObjName() { - return "$(NAME)"; - } + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { +$(INITFIELDS) + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + $(NAME) obj = new $(NAME)(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public $(NAME) GetInstance(UAVObjectManager objMngr, int instID) + { + return ($(NAME))(objMngr.getObject($(NAME).OBJID, instID)); + } - public String getDescription() { - return "$(DESCRIPTION)"; - } -protected: // Constants - static final int OBJID = $(OBJIDHEX); - static final String NAME; - static final String DESCRIPTION; - static final boolean ISSINGLEINST = $(ISSINGLEINST); - static final boolean ISSETTINGS = $(ISSETTINGS); - static final int NUMBYTES = sizeof(DataFields); + protected static final int OBJID = $(OBJIDHEX); + protected static final String NAME = "$(NAME)"; + protected static String DESCRIPTION = "$(DESCRIPTION)"; + protected static final boolean ISSINGLEINST = $(ISSINGLEINST) == 1; + protected static final boolean ISSETTINGS = $(ISSETTINGS) == 1; + protected static int NUMBYTES = 0; -$(GETTERSETTER) } \ No newline at end of file diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 6ac45a07a..ce436e6af 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -24,313 +24,245 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include "uavobjectgeneratorjava.h" using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - QDir javaTemplatePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << + "quint8" << "quint16" << "quint32" << "float" << "quint8"; - javaCodePath = QDir ( outputpath + QString(JAVA_GENERATED_DIR)); + fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" + << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; - javaCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjecttemplate.java") ); - QString javaInitCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjectsinittemplate.java") ); + javaCodePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + javaOutputPath = QDir( outputpath + QString("java") ); + javaOutputPath.mkpath(javaOutputPath.absolutePath()); - if (javaCodeTemplate.isEmpty() || javaInitCodeTemplate.isEmpty()) { - std::cerr << "Problem reading java templates" << endl; + javaCodeTemplate = readFile( javaCodePath.absoluteFilePath("uavobjecttemplate.java") ); + QString javaInitTemplate = readFile( javaCodePath.absoluteFilePath("uavobjectsinittemplate.java") ); + + if (javaCodeTemplate.isEmpty() || javaInitTemplate.isEmpty()) { + std::cerr << "Problem reading java code templates" << endl; return false; } - QString javaObjInit,javaObjGetter; - javaCodePath.mkpath(javaCodePath.absolutePath() + "/uavobjects"); + QString objInc; + QString javaObjInit; for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) { ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - if (!javaObjInit.isNull()) - javaObjInit.append(",\n"); - - javaObjInit.append(" new " + info->name + "()"); - javaObjGetter.append(QString(" public static %1 get%1() { return (%1)uavobjects[%2];}\n").arg( info->name).arg(objidx)); + javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + objInc.append("#include \"" + info->namelc + ".h\"\n"); } - javaInitCodeTemplate.replace("$(OBJINIT)",javaObjInit); - javaInitCodeTemplate.replace("$(OBJGETTER)",javaObjGetter); - - replaceCommonTags(javaInitCodeTemplate); - - // Write the java object inialization files - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/UAVObjects.java", javaInitCodeTemplate ); + // Write the gcs object inialization files + javaInitTemplate.replace( QString("$(OBJINC)"), objInc); + javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); if (!res) { - cerr << "Error: Could not write java init output files" << endl; + cout << "Error: Could not write output files" << endl; return false; } return true; // if we come here everything should be fine } -QString UAVObjectGeneratorJava::getFieldTypeStr(int type,bool as_obj) { - - switch(type) { - case FIELDTYPE_INT8: - return (QString(as_obj?"Byte":"byte")); - case FIELDTYPE_INT16: - case FIELDTYPE_INT32: - case FIELDTYPE_UINT8: - case FIELDTYPE_UINT16: - return (QString(as_obj?"Integer":"int")); - case FIELDTYPE_UINT32: - return (QString(as_obj?"Long":"long")); - case FIELDTYPE_FLOAT32: - return (QString(as_obj?"Float":"float")); - case FIELDTYPE_ENUM: - return (QString(as_obj?"Byte":"byte")); - default: - return QString("error: unknown type"); - } -} - -/** - * - * format a value from FieldInfo with a given index (idx) to a java code snippet - * - */ -QString UAVObjectGeneratorJava::formatJavaValue(FieldInfo* info,int idx) { - switch(info->type) { - case FIELDTYPE_ENUM: - return (info->name.toUpper() + QString("_") + info->defaultValues[idx].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")); - case FIELDTYPE_FLOAT32: - return QString("%1f").arg( info->defaultValues[idx].toFloat() ); - default: - return QString("%1").arg( info->defaultValues[idx].toInt() ); - } -} - -QString UAVObjectGeneratorJava::QStringList2JavaArray(QStringList strl) { - QString csv=QString(); - for (int i = 0; i < strl.length(); i++){ - if (i!=0) - csv.append(QString(",")); - csv.append(QString("\"%1\"").arg(strl[i])); - } - return QString("new String[] { %1 }").arg(csv); -} - -QString UAVObjectGeneratorJava::serializeJavaValue(int type,QString name) -{ - QString res; - switch(type) { - case FIELDTYPE_ENUM: // OK - - case FIELDTYPE_INT8: - res=name; - break; - - case FIELDTYPE_UINT8: - res=QString("(byte)(%1&0xFF)").arg(name); - break; - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF)"); - break; - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF) , (byte)(("+name+">>16)&0xFF) , (byte)(("+name+">>24)&0xFF)"); - break; - - case FIELDTYPE_FLOAT32: - res=QString("(byte)((Float.floatToIntBits("+name+")>>0)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>8)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>16)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>24)&0xFF) "); // OK - break; - - default: - res=QString("unresolved type"); - break; - } - - return res; -} - -/** - * this function is used to build the deserializing code - */ -QString UAVObjectGeneratorJava::deSerializeJavaValue(int type,QString name) -{ - switch(type) { - case FIELDTYPE_ENUM: // OK - case FIELDTYPE_INT8: - return (name.append("=arr[pos++];\n")); - - case FIELDTYPE_UINT8: - return (name.append("=arr[pos++]&0xFF;\n")); /*test */ - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) ;\n")); /* test */ - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ;\n")); /*test */ - - case FIELDTYPE_FLOAT32: - return (name.append("=Float.intBitsToFloat(((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ); ")); // OK - - default: - cout << "Warning: unresolved type " << type << " for " << name.toStdString() << endl; - return(QString("unresolved type")); // will throw an arr when compiling then - } -} /** * Generate the java object files */ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { - if (info == NULL) return false; + if (info == NULL) + return false; // Prepare output strings + QString outInclude = javaIncludeTemplate; QString outCode = javaCodeTemplate; // Replace common tags + replaceCommonTags(outInclude, info); replaceCommonTags(outCode, info); - QString type,fieldsinit,serialize_code,serialize_code_inner,deserialize_code,gettersetter; - - QString fielddesc=QString(" public final UAVObjectFieldDescription[] getFieldDescriptions() { return new UAVObjectFieldDescription[] {"); - QString fieldgetter=QString(" public Object getField(int fieldid,int arr_pos) { switch(fieldid) {\n"); - QString fieldsetter=QString(" public void setField(int fieldid,int arr_pos,Object obj) { switch(fieldid) {\n"); - - for (int n = 0; n < info->fields.length(); ++n) { - FieldInfo* act_field_info=info->fields[n]; - - bool is_array = info->fields[n]->numElements > 1; - type = getFieldTypeStr(act_field_info->type,false); // Determine type - - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) - fieldsinit.append(QString(" public final static byte %1 = %2;\n").arg(act_field_info->name.toUpper() + QString("_") + act_field_info->options[enum_n].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")).arg(enum_n) ); - - fieldsinit.append(QString(" private ") + type); - - if ( is_array ) - fieldsinit.append(QString("[]")); - - fieldsinit.append(QString(" %1").arg(act_field_info->name)); - - if (!info->fields[n]->defaultValues.isEmpty()) { // if we have default vals - fieldsinit.append(QString("=")); - if ( is_array ) { - fieldsinit.append(QString("{")); - for (int val_n = 0; val_n < act_field_info->defaultValues.length(); ++val_n) - fieldsinit.append( ((val_n>0)?QString(","):QString() ) + formatJavaValue(act_field_info,val_n) ); - fieldsinit.append(QString("}")); - } - else - fieldsinit.append(formatJavaValue(act_field_info,0)); - } - else { - if ( is_array ) // when it is an array - fieldsinit.append(QString("= new ") + type + QString("[%1]").arg(info->fields[n]->numElements)); - } - - fieldsinit.append(QString(";\n")); - - if (n!=0) - serialize_code_inner.append(QString(",")); - - if ( is_array ) { - for (int el=0;elfields[n]->numElements;el++) { - if (el!=0) - serialize_code_inner.append(QString(",")); - - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - } - } - else { // no array - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - } - - serialize_code_inner.append(QString("//%1\n" ).arg(info->fields[n]->name)); - + // Replace the $(DATAFIELDS) tag + QString type; + QString fields; + for (int n = 0; n < info->fields.length(); ++n) + { // Determine type - type = getFieldTypeStr(act_field_info->type,false); - - QString typespec=type; - - if ( is_array ) { - typespec.append(QString("[]")); - fieldgetter.append(QString("case %1: return (Object)%2[arr_pos];\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2[arr_pos]=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg( getFieldTypeStr(act_field_info->type,true))); + type = fieldTypeStrCPP[info->fields[n]->type]; + // Append field + if ( info->fields[n]->numElements > 1 ) + { + fields.append( QString(" %1 %2[%3];\n").arg(type).arg(info->fields[n]->name) + .arg(info->fields[n]->numElements) ); } - else { // no array - fieldgetter.append(QString("case %1: return (Object)%2;\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg(getFieldTypeStr(act_field_info->type,true))); + else + { + fields.append( QString(" %1 %2;\n").arg(type).arg(info->fields[n]->name) ); } + } + outInclude.replace(QString("$(DATAFIELDS)"), fields); + // Replace the $(FIELDSINIT) tag + QString finit; + for (int n = 0; n < info->fields.length(); ++n) + { + finit.append("\n"); - if (!act_field_info->units.isEmpty()) // when we have unit info - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); + // Setup element names + QString varElemName = info->fields[n]->name + "ElemNames"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varElemName) ); + QStringList elemNames = info->fields[n]->elementNames; + for (int m = 0; m < elemNames.length(); ++m) + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varElemName) + .arg(elemNames[m]) ); - gettersetter.append(QString(" public void set%1( %2 _%1 ) { %1=_%1; }\n").arg(act_field_info->name).arg(typespec)); - - if (n!=0) - fielddesc.append(QString("\t,")); - - fielddesc.append(QString("new UAVObjectFieldDescription(\"%1\",this.getObjID(),(byte)%2,(byte)%3,\"%4\",%5,%6)\n").arg(act_field_info->name).arg(n).arg(act_field_info->type).arg(act_field_info->units).arg(QStringList2JavaArray( act_field_info->options)).arg(QStringList2JavaArray( act_field_info->elementNames)) ); - - if (!act_field_info->units.isEmpty()) - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); - - gettersetter.append(QString(" public ") + typespec); - - gettersetter.append(QString(" get%1() { return %1; }\n").arg(act_field_info->name)); - - if ( act_field_info->options.length()!=0) { - QString enumOptionsGetter=QString(" public final static String[] get%1EnumOptions() { return new String[] {").arg(act_field_info->name); - - // gettersetter.append(QString(" get%1s() { return %1; }\n").arg(act_field_info->name)); - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) { - if (enum_n!=0) - enumOptionsGetter.append(QString(",")); - enumOptionsGetter.append(QString("\"")+act_field_info->options[enum_n] +QString("\"")); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) { + QString varOptionName = info->fields[n]->name + "EnumOptions"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varOptionName) ); + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) + { + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varOptionName) + .arg(options[m]) ); } - - gettersetter.append(enumOptionsGetter+QString("};}\n")); + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.ENUM, %3, %4) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(varElemName) + .arg(varOptionName) ); } + // For all other types + else { + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.%3, %4, null) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(fieldTypeStrCPPClass[info->fields[n]->type]) + .arg(varElemName) ); + } + } + outCode.replace(QString("$(FIELDSINIT)"), finit); - if ( is_array ) { // when it is an array create getter for the element names - QString elementListGetter=QString(" public final static String[] get%1ElementNames() { return new String[] {").arg(act_field_info->name); + // Replace the $(DATAFIELDINFO) tag + QString name; + QString enums; + for (int n = 0; n < info->fields.length(); ++n) + { + enums.append(QString(" // Field %1 information\n").arg(info->fields[n]->name)); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) + { + enums.append(QString(" /* Enumeration options for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through each option + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) { + QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) + .arg(m) ); + + } + enums.append( QString(" } %1Options;\n") + .arg( info->fields[n]->name ) ); + } + // Generate element names (only if field has more than one element) + if (info->fields[n]->numElements > 1 && !info->fields[n]->defaultElementNames) { + enums.append(QString(" /* Array element names for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through the element names QStringList elemNames = info->fields[n]->elementNames; for (int m = 0; m < elemNames.length(); ++m) { - gettersetter.append(QString(" public ") + type); - gettersetter.append(QString(" get%1%2() { return %1[%3]; }\n").arg(act_field_info->name).arg(elemNames[m]).arg(m)); - if (m!=0) - elementListGetter.append(QString(",")); + QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( elemNames[m].toUpper() ) + .arg(m) ); - elementListGetter.append(QString("\"") + elemNames[m]+QString("\"")); } - gettersetter.append(elementListGetter+QString("};}\n")); + enums.append( QString(" } %1Elem;\n") + .arg( info->fields[n]->name ) ); + } + // Generate array information + if (info->fields[n]->numElements > 1) { + enums.append(QString(" /* Number of elements for field %1 */\n").arg(info->fields[n]->name)); + enums.append( QString(" static const quint32 %1_NUMELEM = %2;\n") + .arg( info->fields[n]->name.toUpper() ) + .arg( info->fields[n]->numElements ) ); + } + } + outInclude.replace(QString("$(DATAFIELDINFO)"), enums); + + // Replace the $(INITFIELDS) tag + QString initfields; + for (int n = 0; n < info->fields.length(); ++n) + { + if (!info->fields[n]->defaultValues.isEmpty() ) + { + // For non-array fields + if ( info->fields[n]->numElements == 1) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toFloat() ) ); + } + else + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toInt() ) ); + } + } + else + { + // Initialize all fields in the array + for (int idx = 0; idx < info->fields[n]->numElements; ++idx) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toFloat() ) ); + } + else { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toInt() ) ); + } + } + } } } - serialize_code.append(QString(" public byte[] serialize() { return new byte[]{%1 } ;}; \n ").arg(serialize_code_inner)); + outCode.replace(QString("$(INITFIELDS)"), initfields); - serialize_code.append(QString(" public void deserialize(byte[] arr,int offset) {\nsuper.deserialize(arr,offset);\n int pos=offset;\n%1 };\n").arg(deserialize_code)); - - outCode.replace(QString("$(FIELDSINIT)"), fieldsinit); - - fielddesc.append(QString("};}")); - fieldgetter.append(QString("};\n return null;\n}\n")); - fieldsetter.append(QString("};\n}\n")); - outCode.replace(QString("$(GETTERSETTER)"), gettersetter + serialize_code+ fielddesc + fieldgetter + fieldsetter); - - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/uavobjects/" + info->name + ".java", outCode ); + // Write the java code + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); if (!res) { - cerr << "Error: Could not write java init output file " << info->name.toStdString()<< endl; + cout << "Error: Could not write gcs output files" << endl; return false; - } + } return true; } diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h index 21fc4dc75..8d07484f6 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h @@ -28,7 +28,7 @@ #define UAVOBJECTGENERATORJAVA_H #define JAVA_TEMPLATE_DIR "ground/openpilotgcs/src/libs/juavobjects/templates/" -#define JAVA_GENERATED_DIR "java/src/org/openpilot/uavtalk" +#define JAVA_CODE_DIR "java/src/org/openpilot/uavtalk" #include "../generator_common.h" @@ -38,14 +38,12 @@ public: bool generate(UAVObjectParser* gen,QString templatepath,QString outputpath); private: - QString javaCodeTemplate; - QDir javaCodePath; bool process_object(ObjectInfo* info); - QString formatJavaValue(FieldInfo* info,int idx); - QString QStringList2JavaArray(QStringList strl); - QString serializeJavaValue(int type,QString name); - QString deSerializeJavaValue(int type,QString name); - QString getFieldTypeStr(int type,bool as_obj); -}; + + QString javaCodeTemplate, javaIncludeTemplate; + QStringList fieldTypeStrCPP,fieldTypeStrCPPClass; + QDir javaCodePath; + QDir javaOutputPath; + }; #endif From 2238ca08046a33e0476e04be364914f16d8666a6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:56:56 -0600 Subject: [PATCH 048/165] Remove some debugging lines, also use Number interface instead of explicit Byte, Integer, Short etc in setValue/getValue --- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 118 +++++++++++------- 2 files changed, 77 insertions(+), 46 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 926440805..fe478cf2e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -114,7 +114,7 @@ public abstract class UAVObject { for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } -// unpack(data); + unpack(data); } /** @@ -291,13 +291,12 @@ public abstract class UAVObject { public int unpack(ByteBuffer dataIn) throws Exception { if( dataIn == null ) return 0; - System.out.println( dataIn.toString() ); + // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); while (li.hasNext()) { UAVObjectField field = li.next(); - System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index b37c992fb..a9006e02f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -99,31 +99,43 @@ public class UAVObjectField { switch (type) { case INT8: - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case INT16: - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case INT32: - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case UINT8: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case UINT16: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case UINT32: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case FLOAT32: for (int index = 0; index < numElements; ++index) @@ -142,64 +154,93 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) { case INT8: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case INT16: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case INT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case UINT8: - // TODO: Deal with unsigned + // TOOD: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case UINT16: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case UINT32: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case FLOAT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Float) dataIn.getFloat(), index); + Float val = dataIn.getFloat(); + l.set(index, val); } break; + } case ENUM: + { List l = (List) data; for (int index = 0 ; index < numElements; ++index) { l.set(index, dataIn.get(index)); } break; + } case STRING: - throw new Exception("Strings not handled"); + // TODO: implement strings + //throw new Exception("Strings not handled"); } // Done return getNumBytes(); } - Object getValue() throws Exception { return getValue(0); }; - Object getValue(int index) throws Exception { + Object getValue() { return getValue(0); }; + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) @@ -234,14 +275,14 @@ public class UAVObjectField { List l = (List) data; Byte val = l.get(index); - if(val >= options.size() || val < 0) - throw new Exception("Invalid value for" + name); + //if(val >= options.size() || val < 0) + // throw new Exception("Invalid value for" + name); return options.get(val); } case STRING: { - throw new Exception("Shit I should do this"); + //throw new Exception("Shit I should do this"); } } // If this point is reached then we got an invalid type @@ -252,12 +293,9 @@ public class UAVObjectField { public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ) + if ( index >= numElements ); //throw new Exception("Index out of bounds"); - System.out.println(data.toString()); - System.out.println(this.data.toString()); - // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits @@ -266,23 +304,19 @@ public class UAVObjectField { switch (type) { case INT8: - data = new Integer((Byte) data); case INT16: - data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index,(Integer) data); + l.set(index,((Number) data).intValue()); break; } case UINT8: - data = new Integer((Byte) data); case UINT16: - data = new Integer((Short) data); case UINT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,((Number) data).intValue()); break; } case FLOAT32: @@ -386,7 +420,7 @@ public class UAVObjectField { sout += name + ": [ "; for (int n = 0; n < numElements; ++n) { - sout += String.valueOf(n) + " "; + sout += String.valueOf(n) + "(" + getValue(n) + ") "; } sout += "] " + units + "\n"; @@ -442,9 +476,8 @@ public class UAVObjectField { this.data = null; this.obj = null; this.elementNames = elementNames; - // Set field size - System.out.println("Initializing: type " + type + this.numElements); + // Set field size switch (type) { case INT8: @@ -487,7 +520,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - System.out.println("Initialized: " + this.data.toString()); } From cc7eb0f261ceae8ac1654e6a3fcba582f432addc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 02:26:09 -0600 Subject: [PATCH 049/165] Make object store with the minimal amount of space and deal with unsigned values --- .../src/org/openpilot/uavtalk/UAVObject.java | 4 +- .../org/openpilot/uavtalk/UAVObjectField.java | 203 +++++++++++++----- .../java/uavobjectgeneratorjava.cpp | 4 +- 3 files changed, 148 insertions(+), 63 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fe478cf2e..bf2c87d7e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -462,9 +462,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; - // getName(), getObjID(), getInstID(), getNumBytes(), - // isSingleInstance()); + return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a9006e02f..78ebd7b52 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -27,8 +27,7 @@ public class UAVObjectField { public void initialize(UAVObject obj){ this.obj = obj; - clear(); - + //clear(); } public UAVObject getObject() { @@ -161,19 +160,19 @@ public class UAVObjectField { { case INT8: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + Long val = bound(dataIn.get()); + l.set(index, val.byteValue()); } break; } case INT16: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + Long val = bound(dataIn.getShort()); + l.set(index, val.shortValue()); } break; } @@ -181,18 +180,18 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); + Long val = bound(dataIn.getInt()); l.set(index, val.intValue()); } break; } case UINT8: - // TOOD: Deal with unsigned { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); } break; } @@ -200,17 +199,19 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.getShort(); // this sign extends it + int unsignedval = signedval & 0xffff; // drop sign extension + l.set(index, unsignedval); } break; } case UINT32: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); - l.set(index, val.intValue()); + long signedval = (long) dataIn.getInt(); // this sign extends it + long unsignedval = signedval & 0xffffffffL; // drop sign extension + l.set(index, unsignedval); } break; } @@ -240,36 +241,31 @@ public class UAVObjectField { } Object getValue() { return getValue(0); }; - Object getValue(int index) { + @SuppressWarnings("unchecked") + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) { return null; } - + switch (type) { case INT8: + return ((List) data).get(index).intValue(); case INT16: + return ((List) data).get(index).intValue(); case INT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index).intValue(); case UINT8: + return ((List) data).get(index).intValue(); case UINT16: + return ((List) data).get(index).intValue(); case UINT32: - { - // TODO: Correctly deal with unsigned values - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case FLOAT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case ENUM: { List l = (List) data; @@ -290,10 +286,11 @@ public class UAVObjectField { } public void setValue(Object data) { setValue(data,0); } - public void setValue(Object data, int index) { + @SuppressWarnings("unchecked") + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ); + //if ( index >= numElements ); //throw new Exception("Index out of bounds"); // Get metadata @@ -304,25 +301,45 @@ public class UAVObjectField { switch (type) { case INT8: + { + List l = (List) this.data; + l.set(index, bound(data).byteValue()); + break; + } case INT16: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case INT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); break; } case UINT8: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case UINT16: - case UINT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); + break; + } + case UINT32: + { + List l = (List) this.data; + l.set(index, bound(data)); break; } case FLOAT32: { List l = (List) this.data; - l.set(index, (Float) data); + l.set(index, ((Number) data).floatValue()); break; } case ENUM: @@ -431,37 +448,46 @@ public class UAVObjectField { } - public void clear() { + @SuppressWarnings("unchecked") + public void clear() { switch (type) { case INT8: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; case INT16: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case INT32: - case UINT8: - case UINT16: - case UINT32: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { ((ArrayList) data).add(0); } break; - case FLOAT32: - ((ArrayList) data).clear(); + case UINT8: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((float) 0); + ((ArrayList) data).add((short) 0); } break; - case ENUM: - ((ArrayList) data).clear(); + case UINT16: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((byte)0); + ((ArrayList) data).add(0); } break; - case STRING: - // TODO: Add string + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((long) 0); + } break; - default: - numBytesPerElement = 0; } } @@ -481,11 +507,11 @@ public class UAVObjectField { switch (type) { case INT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: @@ -493,7 +519,7 @@ public class UAVObjectField { numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: @@ -501,11 +527,11 @@ public class UAVObjectField { numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: @@ -520,8 +546,69 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); + + System.out.println(this); } + /** + * For numerical types bounds the data appropriately + * @param val Can be any object, for numerical tries to cast to Number + * @return long value with the right range (for float rounds) + * @note This is mostly needed because java has no unsigned integer + */ + protected Long bound (Object val) { + + switch(type) { + case ENUM: + case STRING: + return 0L; + case FLOAT32: + return ((Number) val).longValue(); + } + + long num = ((Number) val).longValue(); + + switch(type) { + case INT8: + if(num < Byte.MIN_VALUE) + return (long) Byte.MAX_VALUE; + if(num > Byte.MAX_VALUE) + return (long) Byte.MAX_VALUE; + return num; + case INT16: + if(num < Short.MIN_VALUE) + return (long) Short.MIN_VALUE; + if(num > Short.MAX_VALUE) + return (long) Short.MAX_VALUE; + return num; + case INT32: + if(num < Integer.MIN_VALUE) + return (long) Integer.MIN_VALUE; + if(num > Integer.MAX_VALUE) + return (long) Integer.MAX_VALUE; + return num; + case UINT8: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; + case UINT16: + if(num < 0) + return (long) 0; + if(num > 65535) + return (long) 65535; + return num; + case UINT32: + if(num < 0) + return (long) 0; + if(num > 4294967295L) + return 4294967295L; + return num; + } + + return num; + } private String name; private String units; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index ce436e6af..7319b7767 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -29,8 +29,8 @@ using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << - "quint8" << "quint16" << "quint32" << "float" << "quint8"; + fieldTypeStrCPP << "Byte" << "Short" << "Int" << + "Short" << "Int" << "Long" << "Float" << "Byte"; fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; From 75118e0abc0afb404fb1588e65734d8dac6f083f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:10:48 -0600 Subject: [PATCH 050/165] Added unit tests --- .../org/openpilot/uavtalk/FieldTest.java | 121 ++++++++++++++++++ .../org/openpilot/uavtalk/SettingsTest.java | 34 +++++ 2 files changed, 155 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/FieldTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java new file mode 100644 index 000000000..2d161fc25 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java @@ -0,0 +1,121 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + +import org.junit.BeforeClass; +import org.junit.Test; + +import org.openpilot.uavtalk.UAVObjectField; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.uavobjects.*; + +public class FieldTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testPackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + + try { + field.pack(bbuf); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Buffer size incorrect"); + } + + // Expect data to come out as little endian + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + for(int i = 0; i < expected.length && i < bbuf.array().length; i++) { + System.out.println("Expected: " + expected[i] + " (" + i + ")"); + System.out.println("Received: " + bbuf.array()[i] + " (" + i + ")"); + assertEquals(bbuf.array()[i],expected[i]); + } + } + + @Test + public void testUnpackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + obj = new ActuatorCommand(); + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + bbuf.put(expected); + bbuf.position(0); + field.unpack(bbuf); + + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } + + @Test + public void testEnumSetGetValue() { + List options = new ArrayList(); + options.add("Opt1"); + options.add("Opt2"); + options.add("Opt3"); + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.ENUM, 3, options); + field.initialize(obj); + field.setValue("Opt1",0); + field.setValue("Opt2",1); + field.setValue("Opt3",2); + assertEquals(field.getValue(0), "Opt1"); + assertEquals(field.getValue(1), "Opt2"); + assertEquals(field.getValue(2), "Opt3"); + } + + @Test + public void testUint16SetGetValue() { + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java new file mode 100644 index 000000000..5a805ae88 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java @@ -0,0 +1,34 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; + +public class SettingsTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetDefaultMetadata() { + fail("Not yet implemented"); + } + + @Test + public void testSetDefaultFieldValues() { + fail("Not yet implemented"); + } + + @Test + public void testIsSettings() { + fail("Not yet implemented"); + } + + @Test + public void testGetField() { + fail("Not yet implemented"); + } + +} From 22e00c780f02ba922b4ba87658d3785a63e26377 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:11:07 -0600 Subject: [PATCH 051/165] More updates to the java objects. Also checking in the auto generated code for now to make things easier. --- .../uavtalk/uavobjects/AHRSCalibration.java | 243 ++++++++++ .../uavtalk/uavobjects/AHRSSettings.java | 178 +++++++ .../uavtalk/uavobjects/ActuatorCommand.java | 158 ++++++ .../uavtalk/uavobjects/ActuatorDesired.java | 159 ++++++ .../uavtalk/uavobjects/ActuatorSettings.java | 455 ++++++++++++++++++ .../uavtalk/uavobjects/AhrsStatus.java | 201 ++++++++ .../uavtalk/uavobjects/AttitudeActual.java | 163 +++++++ .../uavtalk/uavobjects/AttitudeRaw.java | 158 ++++++ .../uavtalk/uavobjects/AttitudeSettings.java | 159 ++++++ .../uavtalk/uavobjects/BaroAltitude.java | 147 ++++++ .../uavtalk/uavobjects/BatterySettings.java | 163 +++++++ .../uavtalk/uavobjects/FirmwareIAPObj.java | 258 ++++++++++ .../uavobjects/FlightBatteryState.java | 165 +++++++ .../uavtalk/uavobjects/FlightPlanControl.java | 144 ++++++ .../uavobjects/FlightPlanSettings.java | 140 ++++++ .../uavtalk/uavobjects/FlightPlanStatus.java | 187 +++++++ .../uavobjects/FlightTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GPSPosition.java | 184 +++++++ .../uavtalk/uavobjects/GPSSatellites.java | 215 +++++++++ .../openpilot/uavtalk/uavobjects/GPSTime.java | 159 ++++++ .../uavtalk/uavobjects/GuidanceSettings.java | 197 ++++++++ .../uavtalk/uavobjects/HomeLocation.java | 197 ++++++++ .../uavtalk/uavobjects/I2CStats.java | 238 +++++++++ .../uavobjects/ManualControlCommand.java | 199 ++++++++ .../uavobjects/ManualControlSettings.java | 395 +++++++++++++++ .../uavtalk/uavobjects/MixerSettings.java | 357 ++++++++++++++ .../uavtalk/uavobjects/MixerStatus.java | 167 +++++++ .../uavtalk/uavobjects/NedAccel.java | 147 ++++++ .../uavtalk/uavobjects/ObjectPersistence.java | 160 ++++++ .../uavtalk/uavobjects/PositionActual.java | 147 ++++++ .../uavtalk/uavobjects/PositionDesired.java | 147 ++++++ .../uavtalk/uavobjects/RateDesired.java | 147 ++++++ .../uavtalk/uavobjects/SonarAltitude.java | 139 ++++++ .../uavobjects/StabilizationDesired.java | 161 +++++++ .../uavobjects/StabilizationSettings.java | 222 +++++++++ .../uavtalk/uavobjects/SystemAlarms.java | 176 +++++++ .../uavtalk/uavobjects/SystemSettings.java | 157 ++++++ .../uavtalk/uavobjects/SystemStats.java | 151 ++++++ .../uavtalk/uavobjects/TaskInfo.java | 170 +++++++ .../uavtalk/uavobjects/TelemetrySettings.java | 148 ++++++ .../uavobjects/UAVObjectsInitialize.java | 87 ++++ .../uavtalk/uavobjects/VelocityActual.java | 147 ++++++ .../uavtalk/uavobjects/VelocityDesired.java | 147 ++++++ .../uavtalk/uavobjects/WatchdogStatus.java | 143 ++++++ 45 files changed, 8310 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java new file mode 100644 index 000000000..a3096ad39 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -0,0 +1,243 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the calibration settings for the @ref AHRSCommsModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the calibration settings for the @ref AHRSCommsModule + +generated from ahrscalibration.xml + **/ +public class AHRSCalibration extends UAVDataObject { + + public AHRSCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcompfactorElemNames = new ArrayList(); + gyro_tempcompfactorElemNames.add("X"); + gyro_tempcompfactorElemNames.add("Y"); + gyro_tempcompfactorElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List vel_varElemNames = new ArrayList(); + vel_varElemNames.add("0"); + fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); + + List pos_varElemNames = new ArrayList(); + pos_varElemNames.add("0"); + fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("measure_var").setValue(0); + getField("accel_bias").setValue(-73.5,0); + getField("accel_bias").setValue(-73.5,1); + getField("accel_bias").setValue(73.5,2); + getField("accel_scale").setValue(0.0359,0); + getField("accel_scale").setValue(0.0359,1); + getField("accel_scale").setValue(-0.0359,2); + getField("accel_var").setValue(0.0005,0); + getField("accel_var").setValue(0.0005,1); + getField("accel_var").setValue(0.0005,2); + getField("gyro_bias").setValue(23,0); + getField("gyro_bias").setValue(-23,1); + getField("gyro_bias").setValue(23,2); + getField("gyro_scale").setValue(-0.017,0); + getField("gyro_scale").setValue(0.017,1); + getField("gyro_scale").setValue(-0.017,2); + getField("gyro_var").setValue(0.0001,0); + getField("gyro_var").setValue(0.0001,1); + getField("gyro_var").setValue(0.0001,2); + getField("gyro_tempcompfactor").setValue(0,0); + getField("gyro_tempcompfactor").setValue(0,1); + getField("gyro_tempcompfactor").setValue(0,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(-2,0); + getField("mag_scale").setValue(-2,1); + getField("mag_scale").setValue(-2,2); + getField("mag_var").setValue(50,0); + getField("mag_var").setValue(50,1); + getField("mag_var").setValue(50,2); + getField("vel_var").setValue(0.4); + getField("pos_var").setValue(0.4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSCalibration obj = new AHRSCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x30101BB2; + protected static final String NAME = "AHRSCalibration"; + protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java new file mode 100644 index 000000000..a38915c28 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + +generated from ahrssettings.xml + **/ +public class AHRSSettings extends UAVDataObject { + + public AHRSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlgorithmElemNames = new ArrayList(); + AlgorithmElemNames.add("0"); + List AlgorithmEnumOptions = new ArrayList(); + AlgorithmEnumOptions.add("SIMPLE"); + AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); + AlgorithmEnumOptions.add("INSGPS_INDOOR"); + AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); + fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); + + List DownsamplingElemNames = new ArrayList(); + DownsamplingElemNames.add("0"); + fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("TRUE"); + BiasCorrectedRawEnumOptions.add("FALSE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Algorithm").setValue(1); + getField("Downsampling").setValue(20); + getField("UpdatePeriod").setValue(1); + getField("BiasCorrectedRaw").setValue(0); + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSSettings obj = new AHRSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDEFC5548; + protected static final String NAME = "AHRSSettings"; + protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java new file mode 100644 index 000000000..a5d6230ac --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + +generated from actuatorcommand.xml + **/ +public class ActuatorCommand extends UAVDataObject { + + public ActuatorCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + + List MaxUpdateTimeElemNames = new ArrayList(); + MaxUpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + + List NumFailedUpdatesElemNames = new ArrayList(); + NumFailedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorCommand obj = new ActuatorCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorCommand)(objMngr.getObject(ActuatorCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE8E077D8; + protected static final String NAME = "ActuatorCommand"; + protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java new file mode 100644 index 000000000..b81ca29da --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + +generated from actuatordesired.xml + **/ +public class ActuatorDesired extends UAVDataObject { + + public ActuatorDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.FLOAT32, UpdateTimeElemNames, null) ); + + List NumLongUpdatesElemNames = new ArrayList(); + NumLongUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumLongUpdates", "ms", UAVObjectField.FieldType.FLOAT32, NumLongUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorDesired obj = new ActuatorDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorDesired)(objMngr.getObject(ActuatorDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD4516782; + protected static final String NAME = "ActuatorDesired"; + protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java new file mode 100644 index 000000000..ebbfaeb17 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -0,0 +1,455 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from actuatorsettings.xml + **/ +public class ActuatorSettings extends UAVDataObject { + + public ActuatorSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYawElemNames = new ArrayList(); + FixedWingYawElemNames.add("0"); + List FixedWingYawEnumOptions = new ArrayList(); + FixedWingYawEnumOptions.add("Channel1"); + FixedWingYawEnumOptions.add("Channel2"); + FixedWingYawEnumOptions.add("Channel3"); + FixedWingYawEnumOptions.add("Channel4"); + FixedWingYawEnumOptions.add("Channel5"); + FixedWingYawEnumOptions.add("Channel6"); + FixedWingYawEnumOptions.add("Channel7"); + FixedWingYawEnumOptions.add("Channel8"); + FixedWingYawEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + + List ChannelUpdateFreqElemNames = new ArrayList(); + ChannelUpdateFreqElemNames.add("0"); + ChannelUpdateFreqElemNames.add("1"); + ChannelUpdateFreqElemNames.add("2"); + ChannelUpdateFreqElemNames.add("3"); + fields.add( new UAVObjectField("ChannelUpdateFreq", "Hz", UAVObjectField.FieldType.UINT16, ChannelUpdateFreqElemNames, null) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ChannelTypeElemNames = new ArrayList(); + ChannelTypeElemNames.add("0"); + ChannelTypeElemNames.add("1"); + ChannelTypeElemNames.add("2"); + ChannelTypeElemNames.add("3"); + ChannelTypeElemNames.add("4"); + ChannelTypeElemNames.add("5"); + ChannelTypeElemNames.add("6"); + ChannelTypeElemNames.add("7"); + List ChannelTypeEnumOptions = new ArrayList(); + ChannelTypeEnumOptions.add("PWM"); + ChannelTypeEnumOptions.add("MK"); + ChannelTypeEnumOptions.add("ASTEC4"); + fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); + + List ChannelAddrElemNames = new ArrayList(); + ChannelAddrElemNames.add("0"); + ChannelAddrElemNames.add("1"); + ChannelAddrElemNames.add("2"); + ChannelAddrElemNames.add("3"); + ChannelAddrElemNames.add("4"); + ChannelAddrElemNames.add("5"); + ChannelAddrElemNames.add("6"); + ChannelAddrElemNames.add("7"); + fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FixedWingRoll1").setValue(8); + getField("FixedWingRoll2").setValue(8); + getField("FixedWingPitch1").setValue(8); + getField("FixedWingPitch2").setValue(8); + getField("FixedWingYaw").setValue(8); + getField("FixedWingThrottle").setValue(8); + getField("VTOLMotorN").setValue(8); + getField("VTOLMotorNE").setValue(8); + getField("VTOLMotorE").setValue(8); + getField("VTOLMotorSE").setValue(8); + getField("VTOLMotorS").setValue(8); + getField("VTOLMotorSW").setValue(8); + getField("VTOLMotorW").setValue(8); + getField("VTOLMotorNW").setValue(8); + getField("ChannelUpdateFreq").setValue(50,0); + getField("ChannelUpdateFreq").setValue(50,1); + getField("ChannelUpdateFreq").setValue(50,2); + getField("ChannelUpdateFreq").setValue(50,3); + getField("ChannelMax").setValue(1000,0); + getField("ChannelMax").setValue(1000,1); + getField("ChannelMax").setValue(1000,2); + getField("ChannelMax").setValue(1000,3); + getField("ChannelMax").setValue(1000,4); + getField("ChannelMax").setValue(1000,5); + getField("ChannelMax").setValue(1000,6); + getField("ChannelMax").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,0); + getField("ChannelNeutral").setValue(1000,1); + getField("ChannelNeutral").setValue(1000,2); + getField("ChannelNeutral").setValue(1000,3); + getField("ChannelNeutral").setValue(1000,4); + getField("ChannelNeutral").setValue(1000,5); + getField("ChannelNeutral").setValue(1000,6); + getField("ChannelNeutral").setValue(1000,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ChannelType").setValue(0,0); + getField("ChannelType").setValue(0,1); + getField("ChannelType").setValue(0,2); + getField("ChannelType").setValue(0,3); + getField("ChannelType").setValue(0,4); + getField("ChannelType").setValue(0,5); + getField("ChannelType").setValue(0,6); + getField("ChannelType").setValue(0,7); + getField("ChannelAddr").setValue(0,0); + getField("ChannelAddr").setValue(1,1); + getField("ChannelAddr").setValue(2,2); + getField("ChannelAddr").setValue(3,3); + getField("ChannelAddr").setValue(4,4); + getField("ChannelAddr").setValue(5,5); + getField("ChannelAddr").setValue(6,6); + getField("ChannelAddr").setValue(7,7); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorSettings obj = new ActuatorSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorSettings)(objMngr.getObject(ActuatorSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1BF864C2; + protected static final String NAME = "ActuatorSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java new file mode 100644 index 000000000..3ee8304ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -0,0 +1,201 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the @ref AHRSCommsModule, including communication errors + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the @ref AHRSCommsModule, including communication errors + +generated from ahrsstatus.xml + **/ +public class AhrsStatus extends UAVDataObject { + + public AhrsStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SerialNumberElemNames = new ArrayList(); + SerialNumberElemNames.add("0"); + SerialNumberElemNames.add("1"); + SerialNumberElemNames.add("2"); + SerialNumberElemNames.add("3"); + SerialNumberElemNames.add("4"); + SerialNumberElemNames.add("5"); + SerialNumberElemNames.add("6"); + SerialNumberElemNames.add("7"); + fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + + List IdleTimePerCyleElemNames = new ArrayList(); + IdleTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); + + List RunningTimePerCyleElemNames = new ArrayList(); + RunningTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); + + List LinkRunningElemNames = new ArrayList(); + LinkRunningElemNames.add("0"); + List LinkRunningEnumOptions = new ArrayList(); + LinkRunningEnumOptions.add("FALSE"); + LinkRunningEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); + + List AhrsKickstartsElemNames = new ArrayList(); + AhrsKickstartsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); + + List AhrsCrcErrorsElemNames = new ArrayList(); + AhrsCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); + + List AhrsRetriesElemNames = new ArrayList(); + AhrsRetriesElemNames.add("0"); + fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); + + List AhrsInvalidPacketsElemNames = new ArrayList(); + AhrsInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); + + List OpCrcErrorsElemNames = new ArrayList(); + OpCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); + + List OpRetriesElemNames = new ArrayList(); + OpRetriesElemNames.add("0"); + fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); + + List OpInvalidPacketsElemNames = new ArrayList(); + OpInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AhrsStatus obj = new AhrsStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37A5F7A2; + protected static final String NAME = "AhrsStatus"; + protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java new file mode 100644 index 000000000..714c18571 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The updated Attitude estimation from @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The updated Attitude estimation from @ref AHRSCommsModule. + +generated from attitudeactual.xml + **/ +public class AttitudeActual extends UAVDataObject { + + public AttitudeActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 500; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeActual obj = new AttitudeActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeActual)(objMngr.getObject(AttitudeActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFC5B8CF4; + protected static final String NAME = "AttitudeActual"; + protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java new file mode 100644 index 000000000..d28302b6a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + +generated from attituderaw.xml + **/ +public class AttitudeRaw extends UAVDataObject { + + public AttitudeRaw() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrosElemNames = new ArrayList(); + gyrosElemNames.add("X"); + gyrosElemNames.add("Y"); + gyrosElemNames.add("Z"); + fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + + List accelsElemNames = new ArrayList(); + accelsElemNames.add("X"); + accelsElemNames.add("Y"); + accelsElemNames.add("Z"); + fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeRaw obj = new AttitudeRaw(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37747DE6; + protected static final String NAME = "AttitudeRaw"; + protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java new file mode 100644 index 000000000..482fc12ce --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref Attitude module used on CopterControl + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref Attitude module used on CopterControl + +generated from attitudesettings.xml + **/ +public class AttitudeSettings extends UAVDataObject { + + public AttitudeSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroGainElemNames = new ArrayList(); + GyroGainElemNames.add("0"); + fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); + + List AccelKpElemNames = new ArrayList(); + AccelKpElemNames.add("0"); + fields.add( new UAVObjectField("AccelKp", "channel", UAVObjectField.FieldType.FLOAT32, AccelKpElemNames, null) ); + + List AccelKiElemNames = new ArrayList(); + AccelKiElemNames.add("0"); + fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AccelBias").setValue(0,0); + getField("AccelBias").setValue(0,1); + getField("AccelBias").setValue(0,2); + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.01); + getField("AccelKi").setValue(0.0001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSettings obj = new AttitudeSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSettings)(objMngr.getObject(AttitudeSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x327BF29A; + protected static final String NAME = "AttitudeSettings"; + protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java new file mode 100644 index 000000000..a2c2c7e3d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the barometric sensor with pressure, temperature and altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the barometric sensor with pressure, temperature and altitude estimate. + +generated from baroaltitude.xml + **/ +public class BaroAltitude extends UAVDataObject { + + public BaroAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List TemperatureElemNames = new ArrayList(); + TemperatureElemNames.add("0"); + fields.add( new UAVObjectField("Temperature", "C", UAVObjectField.FieldType.FLOAT32, TemperatureElemNames, null) ); + + List PressureElemNames = new ArrayList(); + PressureElemNames.add("0"); + fields.add( new UAVObjectField("Pressure", "kPa", UAVObjectField.FieldType.FLOAT32, PressureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAltitude obj = new BaroAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAltitude)(objMngr.getObject(BaroAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xED4424F6; + protected static final String NAME = "BaroAltitude"; + protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java new file mode 100644 index 000000000..19e477b62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery configuration information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery configuration information. + +generated from batterysettings.xml + **/ +public class BatterySettings extends UAVDataObject { + + public BatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BatteryVoltageElemNames = new ArrayList(); + BatteryVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + + List BatteryCapacityElemNames = new ArrayList(); + BatteryCapacityElemNames.add("0"); + fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); + + List BatteryTypeElemNames = new ArrayList(); + BatteryTypeElemNames.add("0"); + List BatteryTypeEnumOptions = new ArrayList(); + BatteryTypeEnumOptions.add("LiPo"); + BatteryTypeEnumOptions.add("A123"); + BatteryTypeEnumOptions.add("LiCo"); + BatteryTypeEnumOptions.add("LiFeSO4"); + BatteryTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); + + List CalibrationsElemNames = new ArrayList(); + CalibrationsElemNames.add("Voltage"); + CalibrationsElemNames.add("Current"); + fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("BatteryVoltage").setValue(11.1); + getField("BatteryCapacity").setValue(2200); + getField("BatteryType").setValue(0); + getField("Calibrations").setValue(1,0); + getField("Calibrations").setValue(1,1); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BatterySettings obj = new BatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA5FF1D9A; + protected static final String NAME = "BatterySettings"; + protected static String DESCRIPTION = "Battery configuration information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java new file mode 100644 index 000000000..493d6cd64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -0,0 +1,258 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Firmware IAP + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Firmware IAP + +generated from firmwareiapobj.xml + **/ +public class FirmwareIAPObj extends UAVDataObject { + + public FirmwareIAPObj() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + DescriptionElemNames.add("40"); + DescriptionElemNames.add("41"); + DescriptionElemNames.add("42"); + DescriptionElemNames.add("43"); + DescriptionElemNames.add("44"); + DescriptionElemNames.add("45"); + DescriptionElemNames.add("46"); + DescriptionElemNames.add("47"); + DescriptionElemNames.add("48"); + DescriptionElemNames.add("49"); + DescriptionElemNames.add("50"); + DescriptionElemNames.add("51"); + DescriptionElemNames.add("52"); + DescriptionElemNames.add("53"); + DescriptionElemNames.add("54"); + DescriptionElemNames.add("55"); + DescriptionElemNames.add("56"); + DescriptionElemNames.add("57"); + DescriptionElemNames.add("58"); + DescriptionElemNames.add("59"); + DescriptionElemNames.add("60"); + DescriptionElemNames.add("61"); + DescriptionElemNames.add("62"); + DescriptionElemNames.add("63"); + DescriptionElemNames.add("64"); + DescriptionElemNames.add("65"); + DescriptionElemNames.add("66"); + DescriptionElemNames.add("67"); + DescriptionElemNames.add("68"); + DescriptionElemNames.add("69"); + DescriptionElemNames.add("70"); + DescriptionElemNames.add("71"); + DescriptionElemNames.add("72"); + DescriptionElemNames.add("73"); + DescriptionElemNames.add("74"); + DescriptionElemNames.add("75"); + DescriptionElemNames.add("76"); + DescriptionElemNames.add("77"); + DescriptionElemNames.add("78"); + DescriptionElemNames.add("79"); + DescriptionElemNames.add("80"); + DescriptionElemNames.add("81"); + DescriptionElemNames.add("82"); + DescriptionElemNames.add("83"); + DescriptionElemNames.add("84"); + DescriptionElemNames.add("85"); + DescriptionElemNames.add("86"); + DescriptionElemNames.add("87"); + DescriptionElemNames.add("88"); + DescriptionElemNames.add("89"); + DescriptionElemNames.add("90"); + DescriptionElemNames.add("91"); + DescriptionElemNames.add("92"); + DescriptionElemNames.add("93"); + DescriptionElemNames.add("94"); + DescriptionElemNames.add("95"); + DescriptionElemNames.add("96"); + DescriptionElemNames.add("97"); + DescriptionElemNames.add("98"); + DescriptionElemNames.add("99"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List ArmResetElemNames = new ArrayList(); + ArmResetElemNames.add("0"); + fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); + + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FirmwareIAPObj obj = new FirmwareIAPObj(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FirmwareIAPObj GetInstance(UAVObjectManager objMngr, int instID) + { + return (FirmwareIAPObj)(objMngr.getObject(FirmwareIAPObj.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1A8ECC2; + protected static final String NAME = "FirmwareIAPObj"; + protected static String DESCRIPTION = "Firmware IAP"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java new file mode 100644 index 000000000..d9fba1de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery status information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery status information. + +generated from flightbatterystate.xml + **/ +public class FlightBatteryState extends UAVDataObject { + + public FlightBatteryState() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List VoltageElemNames = new ArrayList(); + VoltageElemNames.add("0"); + fields.add( new UAVObjectField("Voltage", "V", UAVObjectField.FieldType.FLOAT32, VoltageElemNames, null) ); + + List CurrentElemNames = new ArrayList(); + CurrentElemNames.add("0"); + fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + + List PeakCurrentElemNames = new ArrayList(); + PeakCurrentElemNames.add("0"); + fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); + + List AvgCurrentElemNames = new ArrayList(); + AvgCurrentElemNames.add("0"); + fields.add( new UAVObjectField("AvgCurrent", "A", UAVObjectField.FieldType.FLOAT32, AvgCurrentElemNames, null) ); + + List ConsumedEnergyElemNames = new ArrayList(); + ConsumedEnergyElemNames.add("0"); + fields.add( new UAVObjectField("ConsumedEnergy", "mAh", UAVObjectField.FieldType.FLOAT32, ConsumedEnergyElemNames, null) ); + + List EstimatedFlightTimeElemNames = new ArrayList(); + EstimatedFlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("EstimatedFlightTime", "sec", UAVObjectField.FieldType.FLOAT32, EstimatedFlightTimeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Voltage").setValue(0); + getField("Current").setValue(0); + getField("PeakCurrent").setValue(0); + getField("AvgCurrent").setValue(0); + getField("ConsumedEnergy").setValue(0); + getField("EstimatedFlightTime").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatteryState obj = new FlightBatteryState(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatteryState GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatteryState)(objMngr.getObject(FlightBatteryState.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x791A50E; + protected static final String NAME = "FlightBatteryState"; + protected static String DESCRIPTION = "Battery status information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java new file mode 100644 index 000000000..2e453eda5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Control the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Control the flight plan script + +generated from flightplancontrol.xml + **/ +public class FlightPlanControl extends UAVDataObject { + + public FlightPlanControl() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + List CommandEnumOptions = new ArrayList(); + CommandEnumOptions.add("Start"); + CommandEnumOptions.add("Stop"); + CommandEnumOptions.add("Kill"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.ENUM, CommandElemNames, CommandEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Command").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanControl obj = new FlightPlanControl(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanControl GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanControl)(objMngr.getObject(FlightPlanControl.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x6B4FE6DA; + protected static final String NAME = "FlightPlanControl"; + protected static String DESCRIPTION = "Control the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java new file mode 100644 index 000000000..383e4aff0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -0,0 +1,140 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the flight plan module, control the execution of the script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the flight plan module, control the execution of the script + +generated from flightplansettings.xml + **/ +public class FlightPlanSettings extends UAVDataObject { + + public FlightPlanSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List TestElemNames = new ArrayList(); + TestElemNames.add("0"); + fields.add( new UAVObjectField("Test", "", UAVObjectField.FieldType.FLOAT32, TestElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Test").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanSettings obj = new FlightPlanSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanSettings)(objMngr.getObject(FlightPlanSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x85368422; + protected static final String NAME = "FlightPlanSettings"; + protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java new file mode 100644 index 000000000..00920553c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status of the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status of the flight plan script + +generated from flightplanstatus.xml + **/ +public class FlightPlanStatus extends UAVDataObject { + + public FlightPlanStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Stopped"); + StatusEnumOptions.add("Running"); + StatusEnumOptions.add("Error"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List ErrorTypeElemNames = new ArrayList(); + ErrorTypeElemNames.add("0"); + List ErrorTypeEnumOptions = new ArrayList(); + ErrorTypeEnumOptions.add("None"); + ErrorTypeEnumOptions.add("VMInitError"); + ErrorTypeEnumOptions.add("Exception"); + ErrorTypeEnumOptions.add("IOError"); + ErrorTypeEnumOptions.add("DivByZero"); + ErrorTypeEnumOptions.add("AssertError"); + ErrorTypeEnumOptions.add("AttributeError"); + ErrorTypeEnumOptions.add("ImportError"); + ErrorTypeEnumOptions.add("IndexError"); + ErrorTypeEnumOptions.add("KeyError"); + ErrorTypeEnumOptions.add("MemoryError"); + ErrorTypeEnumOptions.add("NameError"); + ErrorTypeEnumOptions.add("SyntaxError"); + ErrorTypeEnumOptions.add("SystemError"); + ErrorTypeEnumOptions.add("TypeError"); + ErrorTypeEnumOptions.add("ValueError"); + ErrorTypeEnumOptions.add("StopIteration"); + ErrorTypeEnumOptions.add("Warning"); + ErrorTypeEnumOptions.add("UnknownError"); + fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); + + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List Debug1ElemNames = new ArrayList(); + Debug1ElemNames.add("0"); + fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); + + List Debug2ElemNames = new ArrayList(); + Debug2ElemNames.add("0"); + fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Status").setValue(0); + getField("ErrorType").setValue(0); + getField("Debug1").setValue(0); + getField("Debug2").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanStatus obj = new FlightPlanStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanStatus)(objMngr.getObject(FlightPlanStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9FC14812; + protected static final String NAME = "FlightPlanStatus"; + protected static String DESCRIPTION = "Status of the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java new file mode 100644 index 000000000..b58fe6d46 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains the telemetry statistics from the OpenPilot flight computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains the telemetry statistics from the OpenPilot flight computer. + +generated from flighttelemetrystats.xml + **/ +public class FlightTelemetryStats extends UAVDataObject { + + public FlightTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightTelemetryStats obj = new FlightTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightTelemetryStats)(objMngr.getObject(FlightTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x660C265E; + protected static final String NAME = "FlightTelemetryStats"; + protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java new file mode 100644 index 000000000..0f304d45d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The telemetry statistics from the ground computer + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The telemetry statistics from the ground computer + +generated from gcstelemetrystats.xml + **/ +public class GCSTelemetryStats extends UAVDataObject { + + public GCSTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.gcsTelemetryUpdatePeriod = 5000; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSTelemetryStats obj = new GCSTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSTelemetryStats)(objMngr.getObject(GCSTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x771E1046; + protected static final String NAME = "GCSTelemetryStats"; + protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java new file mode 100644 index 000000000..889091e0e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + +generated from gpsposition.xml + **/ +public class GPSPosition extends UAVDataObject { + + public GPSPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "meters", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List GeoidSeparationElemNames = new ArrayList(); + GeoidSeparationElemNames.add("0"); + fields.add( new UAVObjectField("GeoidSeparation", "meters", UAVObjectField.FieldType.FLOAT32, GeoidSeparationElemNames, null) ); + + List HeadingElemNames = new ArrayList(); + HeadingElemNames.add("0"); + fields.add( new UAVObjectField("Heading", "degrees", UAVObjectField.FieldType.FLOAT32, HeadingElemNames, null) ); + + List GroundspeedElemNames = new ArrayList(); + GroundspeedElemNames.add("0"); + fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + + List PDOPElemNames = new ArrayList(); + PDOPElemNames.add("0"); + fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); + + List HDOPElemNames = new ArrayList(); + HDOPElemNames.add("0"); + fields.add( new UAVObjectField("HDOP", "", UAVObjectField.FieldType.FLOAT32, HDOPElemNames, null) ); + + List VDOPElemNames = new ArrayList(); + VDOPElemNames.add("0"); + fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSPosition obj = new GPSPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSPosition)(objMngr.getObject(GPSPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xB5495042; + protected static final String NAME = "GPSPosition"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java new file mode 100644 index 000000000..fa1100207 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -0,0 +1,215 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains information about the GPS satellites in view from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains information about the GPS satellites in view from @ref GPSModule. + +generated from gpssatellites.xml + **/ +public class GPSSatellites extends UAVDataObject { + + public GPSSatellites() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + + List ElevationElemNames = new ArrayList(); + ElevationElemNames.add("0"); + ElevationElemNames.add("1"); + ElevationElemNames.add("2"); + ElevationElemNames.add("3"); + ElevationElemNames.add("4"); + ElevationElemNames.add("5"); + ElevationElemNames.add("6"); + ElevationElemNames.add("7"); + ElevationElemNames.add("8"); + ElevationElemNames.add("9"); + ElevationElemNames.add("10"); + ElevationElemNames.add("11"); + ElevationElemNames.add("12"); + ElevationElemNames.add("13"); + ElevationElemNames.add("14"); + ElevationElemNames.add("15"); + fields.add( new UAVObjectField("Elevation", "degrees", UAVObjectField.FieldType.FLOAT32, ElevationElemNames, null) ); + + List AzimuthElemNames = new ArrayList(); + AzimuthElemNames.add("0"); + AzimuthElemNames.add("1"); + AzimuthElemNames.add("2"); + AzimuthElemNames.add("3"); + AzimuthElemNames.add("4"); + AzimuthElemNames.add("5"); + AzimuthElemNames.add("6"); + AzimuthElemNames.add("7"); + AzimuthElemNames.add("8"); + AzimuthElemNames.add("9"); + AzimuthElemNames.add("10"); + AzimuthElemNames.add("11"); + AzimuthElemNames.add("12"); + AzimuthElemNames.add("13"); + AzimuthElemNames.add("14"); + AzimuthElemNames.add("15"); + fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + + List SNRElemNames = new ArrayList(); + SNRElemNames.add("0"); + SNRElemNames.add("1"); + SNRElemNames.add("2"); + SNRElemNames.add("3"); + SNRElemNames.add("4"); + SNRElemNames.add("5"); + SNRElemNames.add("6"); + SNRElemNames.add("7"); + SNRElemNames.add("8"); + SNRElemNames.add("9"); + SNRElemNames.add("10"); + SNRElemNames.add("11"); + SNRElemNames.add("12"); + SNRElemNames.add("13"); + SNRElemNames.add("14"); + SNRElemNames.add("15"); + fields.add( new UAVObjectField("SNR", "", UAVObjectField.FieldType.INT8, SNRElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSatellites obj = new GPSSatellites(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSatellites GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSatellites)(objMngr.getObject(GPSSatellites.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD62FA3AE; + protected static final String NAME = "GPSSatellites"; + protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java new file mode 100644 index 000000000..5ff55cc2e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + +generated from gpstime.xml + **/ +public class GPSTime extends UAVDataObject { + + public GPSTime() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MonthElemNames = new ArrayList(); + MonthElemNames.add("0"); + fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); + + List DayElemNames = new ArrayList(); + DayElemNames.add("0"); + fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); + + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + + List HourElemNames = new ArrayList(); + HourElemNames.add("0"); + fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); + + List MinuteElemNames = new ArrayList(); + MinuteElemNames.add("0"); + fields.add( new UAVObjectField("Minute", "", UAVObjectField.FieldType.INT8, MinuteElemNames, null) ); + + List SecondElemNames = new ArrayList(); + SecondElemNames.add("0"); + fields.add( new UAVObjectField("Second", "", UAVObjectField.FieldType.INT8, SecondElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSTime obj = new GPSTime(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSTime GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSTime)(objMngr.getObject(GPSTime.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x56FFF0A2; + protected static final String NAME = "GPSTime"; + protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java new file mode 100644 index 000000000..2cde12f64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref GuidanceModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref GuidanceModule + +generated from guidancesettings.xml + **/ +public class GuidanceSettings extends UAVDataObject { + + public GuidanceSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List HorizontalPElemNames = new ArrayList(); + HorizontalPElemNames.add("Kp"); + HorizontalPElemNames.add("Max"); + fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPElemNames = new ArrayList(); + VerticalPElemNames.add("Kp"); + VerticalPElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("GuidanceMode").setValue(0); + getField("HorizontalP").setValue(0.2,0); + getField("HorizontalP").setValue(150,1); + getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalVelPID").setValue(0.002,1); + getField("HorizontalVelPID").setValue(0,2); + getField("HorizontalVelPID").setValue(1000,3); + getField("VerticalP").setValue(0.1,0); + getField("VerticalP").setValue(200,1); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("ThrottleControl").setValue(0); + getField("MaxRollPitch").setValue(10); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GuidanceSettings obj = new GuidanceSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x74740AA2; + protected static final String NAME = "GuidanceSettings"; + protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java new file mode 100644 index 000000000..2adebce70 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + +generated from homelocation.xml + **/ +public class HomeLocation extends UAVDataObject { + + public HomeLocation() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List ECEFElemNames = new ArrayList(); + ECEFElemNames.add("0"); + ECEFElemNames.add("1"); + ECEFElemNames.add("2"); + fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); + + List RNEElemNames = new ArrayList(); + RNEElemNames.add("0"); + RNEElemNames.add("1"); + RNEElemNames.add("2"); + RNEElemNames.add("3"); + RNEElemNames.add("4"); + RNEElemNames.add("5"); + RNEElemNames.add("6"); + RNEElemNames.add("7"); + RNEElemNames.add("8"); + fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); + + List BeElemNames = new ArrayList(); + BeElemNames.add("0"); + BeElemNames.add("1"); + BeElemNames.add("2"); + fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Set").setValue(0); + getField("Latitude").setValue(0); + getField("Longitude").setValue(0); + getField("Altitude").setValue(0); + getField("ECEF").setValue(0,0); + getField("ECEF").setValue(0,1); + getField("ECEF").setValue(0,2); + getField("RNE").setValue(0,0); + getField("RNE").setValue(0,1); + getField("RNE").setValue(0,2); + getField("RNE").setValue(0,3); + getField("RNE").setValue(0,4); + getField("RNE").setValue(0,5); + getField("RNE").setValue(0,6); + getField("RNE").setValue(0,7); + getField("RNE").setValue(0,8); + getField("Be").setValue(0,0); + getField("Be").setValue(0,1); + getField("Be").setValue(0,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HomeLocation obj = new HomeLocation(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HomeLocation GetInstance(UAVObjectManager objMngr, int instID) + { + return (HomeLocation)(objMngr.getObject(HomeLocation.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD6008ED2; + protected static final String NAME = "HomeLocation"; + protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java new file mode 100644 index 000000000..fc68e2902 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -0,0 +1,238 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Tracks statistics on the I2C bus. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Tracks statistics on the I2C bus. + +generated from i2cstats.xml + **/ +public class I2CStats extends UAVDataObject { + + public I2CStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List event_errorsElemNames = new ArrayList(); + event_errorsElemNames.add("0"); + fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); + + List fsm_errorsElemNames = new ArrayList(); + fsm_errorsElemNames.add("0"); + fields.add( new UAVObjectField("fsm_errors", "", UAVObjectField.FieldType.UINT8, fsm_errorsElemNames, null) ); + + List irq_errorsElemNames = new ArrayList(); + irq_errorsElemNames.add("0"); + fields.add( new UAVObjectField("irq_errors", "", UAVObjectField.FieldType.UINT8, irq_errorsElemNames, null) ); + + List nacksElemNames = new ArrayList(); + nacksElemNames.add("0"); + fields.add( new UAVObjectField("nacks", "", UAVObjectField.FieldType.UINT8, nacksElemNames, null) ); + + List timeoutsElemNames = new ArrayList(); + timeoutsElemNames.add("0"); + fields.add( new UAVObjectField("timeouts", "", UAVObjectField.FieldType.UINT8, timeoutsElemNames, null) ); + + List last_error_typeElemNames = new ArrayList(); + last_error_typeElemNames.add("0"); + List last_error_typeEnumOptions = new ArrayList(); + last_error_typeEnumOptions.add("EVENT"); + last_error_typeEnumOptions.add("FSM"); + last_error_typeEnumOptions.add("INTERRUPT"); + fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); + + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + + List event_logElemNames = new ArrayList(); + event_logElemNames.add("0"); + event_logElemNames.add("1"); + event_logElemNames.add("2"); + event_logElemNames.add("3"); + event_logElemNames.add("4"); + List event_logEnumOptions = new ArrayList(); + event_logEnumOptions.add("I2C_EVENT_BUS_ERROR"); + event_logEnumOptions.add("I2C_EVENT_START"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_NACK"); + event_logEnumOptions.add("I2C_EVENT_STOPPED"); + event_logEnumOptions.add("I2C_EVENT_AUTO"); + fields.add( new UAVObjectField("event_log", "", UAVObjectField.FieldType.ENUM, event_logElemNames, event_logEnumOptions) ); + + List state_logElemNames = new ArrayList(); + state_logElemNames.add("0"); + state_logElemNames.add("1"); + state_logElemNames.add("2"); + state_logElemNames.add("3"); + state_logElemNames.add("4"); + List state_logEnumOptions = new ArrayList(); + state_logEnumOptions.add("I2C_STATE_FSM_FAULT"); + state_logEnumOptions.add("I2C_STATE_BUS_ERROR"); + state_logEnumOptions.add("I2C_STATE_STOPPED"); + state_logEnumOptions.add("I2C_STATE_STOPPING"); + state_logEnumOptions.add("I2C_STATE_STARTING"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_POST_LAST"); + state_logEnumOptions.add("R_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_LAST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_POST_LAST"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_NACK"); + fields.add( new UAVObjectField("state_log", "", UAVObjectField.FieldType.ENUM, state_logElemNames, state_logEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + I2CStats obj = new I2CStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public I2CStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (I2CStats)(objMngr.getObject(I2CStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x23CE9E9C; + protected static final String NAME = "I2CStats"; + protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java new file mode 100644 index 000000000..636f30946 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -0,0 +1,199 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + +generated from manualcontrolcommand.xml + **/ +public class ManualControlCommand extends UAVDataObject { + + public ManualControlCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("False"); + ArmedEnumOptions.add("True"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlCommand obj = new ManualControlCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlCommand)(objMngr.getObject(ManualControlCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x926794; + protected static final String NAME = "ManualControlCommand"; + protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java new file mode 100644 index 000000000..c14aef758 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -0,0 +1,395 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to indicate how to decode receiver input by @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to indicate how to decode receiver input by @ref ManualControlModule. + +generated from manualcontrolsettings.xml + **/ +public class ManualControlSettings extends UAVDataObject { + + public ManualControlSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List InputModeElemNames = new ArrayList(); + InputModeElemNames.add("0"); + List InputModeEnumOptions = new ArrayList(); + InputModeEnumOptions.add("PWM"); + InputModeEnumOptions.add("PPM"); + InputModeEnumOptions.add("Spektrum"); + fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + List RollEnumOptions = new ArrayList(); + RollEnumOptions.add("Channel1"); + RollEnumOptions.add("Channel2"); + RollEnumOptions.add("Channel3"); + RollEnumOptions.add("Channel4"); + RollEnumOptions.add("Channel5"); + RollEnumOptions.add("Channel6"); + RollEnumOptions.add("Channel7"); + RollEnumOptions.add("Channel8"); + RollEnumOptions.add("None"); + fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + List PitchEnumOptions = new ArrayList(); + PitchEnumOptions.add("Channel1"); + PitchEnumOptions.add("Channel2"); + PitchEnumOptions.add("Channel3"); + PitchEnumOptions.add("Channel4"); + PitchEnumOptions.add("Channel5"); + PitchEnumOptions.add("Channel6"); + PitchEnumOptions.add("Channel7"); + PitchEnumOptions.add("Channel8"); + PitchEnumOptions.add("None"); + fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + List YawEnumOptions = new ArrayList(); + YawEnumOptions.add("Channel1"); + YawEnumOptions.add("Channel2"); + YawEnumOptions.add("Channel3"); + YawEnumOptions.add("Channel4"); + YawEnumOptions.add("Channel5"); + YawEnumOptions.add("Channel6"); + YawEnumOptions.add("Channel7"); + YawEnumOptions.add("Channel8"); + YawEnumOptions.add("None"); + fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + List ThrottleEnumOptions = new ArrayList(); + ThrottleEnumOptions.add("Channel1"); + ThrottleEnumOptions.add("Channel2"); + ThrottleEnumOptions.add("Channel3"); + ThrottleEnumOptions.add("Channel4"); + ThrottleEnumOptions.add("Channel5"); + ThrottleEnumOptions.add("Channel6"); + ThrottleEnumOptions.add("Channel7"); + ThrottleEnumOptions.add("Channel8"); + ThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Channel1"); + FlightModeEnumOptions.add("Channel2"); + FlightModeEnumOptions.add("Channel3"); + FlightModeEnumOptions.add("Channel4"); + FlightModeEnumOptions.add("Channel5"); + FlightModeEnumOptions.add("Channel6"); + FlightModeEnumOptions.add("Channel7"); + FlightModeEnumOptions.add("Channel8"); + FlightModeEnumOptions.add("None"); + fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + List Accessory1EnumOptions = new ArrayList(); + Accessory1EnumOptions.add("Channel1"); + Accessory1EnumOptions.add("Channel2"); + Accessory1EnumOptions.add("Channel3"); + Accessory1EnumOptions.add("Channel4"); + Accessory1EnumOptions.add("Channel5"); + Accessory1EnumOptions.add("Channel6"); + Accessory1EnumOptions.add("Channel7"); + Accessory1EnumOptions.add("Channel8"); + Accessory1EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + List Accessory2EnumOptions = new ArrayList(); + Accessory2EnumOptions.add("Channel1"); + Accessory2EnumOptions.add("Channel2"); + Accessory2EnumOptions.add("Channel3"); + Accessory2EnumOptions.add("Channel4"); + Accessory2EnumOptions.add("Channel5"); + Accessory2EnumOptions.add("Channel6"); + Accessory2EnumOptions.add("Channel7"); + Accessory2EnumOptions.add("Channel8"); + Accessory2EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + List Accessory3EnumOptions = new ArrayList(); + Accessory3EnumOptions.add("Channel1"); + Accessory3EnumOptions.add("Channel2"); + Accessory3EnumOptions.add("Channel3"); + Accessory3EnumOptions.add("Channel4"); + Accessory3EnumOptions.add("Channel5"); + Accessory3EnumOptions.add("Channel6"); + Accessory3EnumOptions.add("Channel7"); + Accessory3EnumOptions.add("Channel8"); + Accessory3EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + + List ArmingElemNames = new ArrayList(); + ArmingElemNames.add("0"); + List ArmingEnumOptions = new ArrayList(); + ArmingEnumOptions.add("Always Disarmed"); + ArmingEnumOptions.add("Always Armed"); + ArmingEnumOptions.add("Roll Left"); + ArmingEnumOptions.add("Roll Right"); + ArmingEnumOptions.add("Pitch Forward"); + ArmingEnumOptions.add("Pitch Aft"); + ArmingEnumOptions.add("Yaw Left"); + ArmingEnumOptions.add("Yaw Right"); + fields.add( new UAVObjectField("Arming", "", UAVObjectField.FieldType.ENUM, ArmingElemNames, ArmingEnumOptions) ); + + List Stabilization1SettingsElemNames = new ArrayList(); + Stabilization1SettingsElemNames.add("Roll"); + Stabilization1SettingsElemNames.add("Pitch"); + Stabilization1SettingsElemNames.add("Yaw"); + List Stabilization1SettingsEnumOptions = new ArrayList(); + Stabilization1SettingsEnumOptions.add("None"); + Stabilization1SettingsEnumOptions.add("Rate"); + Stabilization1SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); + + List Stabilization2SettingsElemNames = new ArrayList(); + Stabilization2SettingsElemNames.add("Roll"); + Stabilization2SettingsElemNames.add("Pitch"); + Stabilization2SettingsElemNames.add("Yaw"); + List Stabilization2SettingsEnumOptions = new ArrayList(); + Stabilization2SettingsEnumOptions.add("None"); + Stabilization2SettingsEnumOptions.add("Rate"); + Stabilization2SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); + + List Stabilization3SettingsElemNames = new ArrayList(); + Stabilization3SettingsElemNames.add("Roll"); + Stabilization3SettingsElemNames.add("Pitch"); + Stabilization3SettingsElemNames.add("Yaw"); + List Stabilization3SettingsEnumOptions = new ArrayList(); + Stabilization3SettingsEnumOptions.add("None"); + Stabilization3SettingsEnumOptions.add("Rate"); + Stabilization3SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); + + List FlightModePositionElemNames = new ArrayList(); + FlightModePositionElemNames.add("0"); + FlightModePositionElemNames.add("1"); + FlightModePositionElemNames.add("2"); + List FlightModePositionEnumOptions = new ArrayList(); + FlightModePositionEnumOptions.add("Manual"); + FlightModePositionEnumOptions.add("Stabilized1"); + FlightModePositionEnumOptions.add("Stabilized2"); + FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("VelocityControl"); + FlightModePositionEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("InputMode").setValue(0); + getField("Roll").setValue(0); + getField("Pitch").setValue(1); + getField("Yaw").setValue(2); + getField("Throttle").setValue(3); + getField("FlightMode").setValue(4); + getField("Accessory1").setValue(8); + getField("Accessory2").setValue(8); + getField("Accessory3").setValue(8); + getField("Arming").setValue(0); + getField("Stabilization1Settings").setValue(2,0); + getField("Stabilization1Settings").setValue(2,1); + getField("Stabilization1Settings").setValue(2,2); + getField("Stabilization2Settings").setValue(2,0); + getField("Stabilization2Settings").setValue(2,1); + getField("Stabilization2Settings").setValue(2,2); + getField("Stabilization3Settings").setValue(2,0); + getField("Stabilization3Settings").setValue(2,1); + getField("Stabilization3Settings").setValue(2,2); + getField("FlightModePosition").setValue(0,0); + getField("FlightModePosition").setValue(1,1); + getField("FlightModePosition").setValue(2,2); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ArmedTimeout").setValue(30000); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlSettings obj = new ManualControlSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlSettings)(objMngr.getObject(ManualControlSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2B82102; + protected static final String NAME = "ManualControlSettings"; + protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java new file mode 100644 index 000000000..554e366f3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -0,0 +1,357 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from mixersettings.xml + **/ +public class MixerSettings extends UAVDataObject { + + public MixerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAccelElemNames = new ArrayList(); + MaxAccelElemNames.add("0"); + fields.add( new UAVObjectField("MaxAccel", "units/sec", UAVObjectField.FieldType.FLOAT32, MaxAccelElemNames, null) ); + + List FeedForwardElemNames = new ArrayList(); + FeedForwardElemNames.add("0"); + fields.add( new UAVObjectField("FeedForward", "", UAVObjectField.FieldType.FLOAT32, FeedForwardElemNames, null) ); + + List AccelTimeElemNames = new ArrayList(); + AccelTimeElemNames.add("0"); + fields.add( new UAVObjectField("AccelTime", "ms", UAVObjectField.FieldType.FLOAT32, AccelTimeElemNames, null) ); + + List DecelTimeElemNames = new ArrayList(); + DecelTimeElemNames.add("0"); + fields.add( new UAVObjectField("DecelTime", "ms", UAVObjectField.FieldType.FLOAT32, DecelTimeElemNames, null) ); + + List ThrottleCurve1ElemNames = new ArrayList(); + ThrottleCurve1ElemNames.add("0"); + ThrottleCurve1ElemNames.add("25"); + ThrottleCurve1ElemNames.add("50"); + ThrottleCurve1ElemNames.add("75"); + ThrottleCurve1ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve1", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve1ElemNames, null) ); + + List ThrottleCurve2ElemNames = new ArrayList(); + ThrottleCurve2ElemNames.add("0"); + ThrottleCurve2ElemNames.add("25"); + ThrottleCurve2ElemNames.add("50"); + ThrottleCurve2ElemNames.add("75"); + ThrottleCurve2ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + + List Mixer1TypeElemNames = new ArrayList(); + Mixer1TypeElemNames.add("0"); + List Mixer1TypeEnumOptions = new ArrayList(); + Mixer1TypeEnumOptions.add("Disabled"); + Mixer1TypeEnumOptions.add("Motor"); + Mixer1TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); + + List Mixer1VectorElemNames = new ArrayList(); + Mixer1VectorElemNames.add("ThrottleCurve1"); + Mixer1VectorElemNames.add("ThrottleCurve2"); + Mixer1VectorElemNames.add("Roll"); + Mixer1VectorElemNames.add("Pitch"); + Mixer1VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer1Vector", "", UAVObjectField.FieldType.INT8, Mixer1VectorElemNames, null) ); + + List Mixer2TypeElemNames = new ArrayList(); + Mixer2TypeElemNames.add("0"); + List Mixer2TypeEnumOptions = new ArrayList(); + Mixer2TypeEnumOptions.add("Disabled"); + Mixer2TypeEnumOptions.add("Motor"); + Mixer2TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); + + List Mixer2VectorElemNames = new ArrayList(); + Mixer2VectorElemNames.add("ThrottleCurve1"); + Mixer2VectorElemNames.add("ThrottleCurve2"); + Mixer2VectorElemNames.add("Roll"); + Mixer2VectorElemNames.add("Pitch"); + Mixer2VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer2Vector", "", UAVObjectField.FieldType.INT8, Mixer2VectorElemNames, null) ); + + List Mixer3TypeElemNames = new ArrayList(); + Mixer3TypeElemNames.add("0"); + List Mixer3TypeEnumOptions = new ArrayList(); + Mixer3TypeEnumOptions.add("Disabled"); + Mixer3TypeEnumOptions.add("Motor"); + Mixer3TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); + + List Mixer3VectorElemNames = new ArrayList(); + Mixer3VectorElemNames.add("ThrottleCurve1"); + Mixer3VectorElemNames.add("ThrottleCurve2"); + Mixer3VectorElemNames.add("Roll"); + Mixer3VectorElemNames.add("Pitch"); + Mixer3VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer3Vector", "", UAVObjectField.FieldType.INT8, Mixer3VectorElemNames, null) ); + + List Mixer4TypeElemNames = new ArrayList(); + Mixer4TypeElemNames.add("0"); + List Mixer4TypeEnumOptions = new ArrayList(); + Mixer4TypeEnumOptions.add("Disabled"); + Mixer4TypeEnumOptions.add("Motor"); + Mixer4TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); + + List Mixer4VectorElemNames = new ArrayList(); + Mixer4VectorElemNames.add("ThrottleCurve1"); + Mixer4VectorElemNames.add("ThrottleCurve2"); + Mixer4VectorElemNames.add("Roll"); + Mixer4VectorElemNames.add("Pitch"); + Mixer4VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer4Vector", "", UAVObjectField.FieldType.INT8, Mixer4VectorElemNames, null) ); + + List Mixer5TypeElemNames = new ArrayList(); + Mixer5TypeElemNames.add("0"); + List Mixer5TypeEnumOptions = new ArrayList(); + Mixer5TypeEnumOptions.add("Disabled"); + Mixer5TypeEnumOptions.add("Motor"); + Mixer5TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); + + List Mixer5VectorElemNames = new ArrayList(); + Mixer5VectorElemNames.add("ThrottleCurve1"); + Mixer5VectorElemNames.add("ThrottleCurve2"); + Mixer5VectorElemNames.add("Roll"); + Mixer5VectorElemNames.add("Pitch"); + Mixer5VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer5Vector", "", UAVObjectField.FieldType.INT8, Mixer5VectorElemNames, null) ); + + List Mixer6TypeElemNames = new ArrayList(); + Mixer6TypeElemNames.add("0"); + List Mixer6TypeEnumOptions = new ArrayList(); + Mixer6TypeEnumOptions.add("Disabled"); + Mixer6TypeEnumOptions.add("Motor"); + Mixer6TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); + + List Mixer6VectorElemNames = new ArrayList(); + Mixer6VectorElemNames.add("ThrottleCurve1"); + Mixer6VectorElemNames.add("ThrottleCurve2"); + Mixer6VectorElemNames.add("Roll"); + Mixer6VectorElemNames.add("Pitch"); + Mixer6VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer6Vector", "", UAVObjectField.FieldType.INT8, Mixer6VectorElemNames, null) ); + + List Mixer7TypeElemNames = new ArrayList(); + Mixer7TypeElemNames.add("0"); + List Mixer7TypeEnumOptions = new ArrayList(); + Mixer7TypeEnumOptions.add("Disabled"); + Mixer7TypeEnumOptions.add("Motor"); + Mixer7TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); + + List Mixer7VectorElemNames = new ArrayList(); + Mixer7VectorElemNames.add("ThrottleCurve1"); + Mixer7VectorElemNames.add("ThrottleCurve2"); + Mixer7VectorElemNames.add("Roll"); + Mixer7VectorElemNames.add("Pitch"); + Mixer7VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer7Vector", "", UAVObjectField.FieldType.INT8, Mixer7VectorElemNames, null) ); + + List Mixer8TypeElemNames = new ArrayList(); + Mixer8TypeElemNames.add("0"); + List Mixer8TypeEnumOptions = new ArrayList(); + Mixer8TypeEnumOptions.add("Disabled"); + Mixer8TypeEnumOptions.add("Motor"); + Mixer8TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); + + List Mixer8VectorElemNames = new ArrayList(); + Mixer8VectorElemNames.add("ThrottleCurve1"); + Mixer8VectorElemNames.add("ThrottleCurve2"); + Mixer8VectorElemNames.add("Roll"); + Mixer8VectorElemNames.add("Pitch"); + Mixer8VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAccel").setValue(1000); + getField("FeedForward").setValue(0); + getField("AccelTime").setValue(0); + getField("DecelTime").setValue(0); + getField("ThrottleCurve1").setValue(0,0); + getField("ThrottleCurve1").setValue(0.25,1); + getField("ThrottleCurve1").setValue(0.5,2); + getField("ThrottleCurve1").setValue(0.75,3); + getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve2").setValue(0,0); + getField("ThrottleCurve2").setValue(0.25,1); + getField("ThrottleCurve2").setValue(0.5,2); + getField("ThrottleCurve2").setValue(0.75,3); + getField("ThrottleCurve2").setValue(1,4); + getField("Mixer1Type").setValue(0); + getField("Mixer1Vector").setValue(0,0); + getField("Mixer1Vector").setValue(0,1); + getField("Mixer1Vector").setValue(0,2); + getField("Mixer1Vector").setValue(0,3); + getField("Mixer1Vector").setValue(0,4); + getField("Mixer2Type").setValue(0); + getField("Mixer2Vector").setValue(0,0); + getField("Mixer2Vector").setValue(0,1); + getField("Mixer2Vector").setValue(0,2); + getField("Mixer2Vector").setValue(0,3); + getField("Mixer2Vector").setValue(0,4); + getField("Mixer3Type").setValue(0); + getField("Mixer3Vector").setValue(0,0); + getField("Mixer3Vector").setValue(0,1); + getField("Mixer3Vector").setValue(0,2); + getField("Mixer3Vector").setValue(0,3); + getField("Mixer3Vector").setValue(0,4); + getField("Mixer4Type").setValue(0); + getField("Mixer4Vector").setValue(0,0); + getField("Mixer4Vector").setValue(0,1); + getField("Mixer4Vector").setValue(0,2); + getField("Mixer4Vector").setValue(0,3); + getField("Mixer4Vector").setValue(0,4); + getField("Mixer5Type").setValue(0); + getField("Mixer5Vector").setValue(0,0); + getField("Mixer5Vector").setValue(0,1); + getField("Mixer5Vector").setValue(0,2); + getField("Mixer5Vector").setValue(0,3); + getField("Mixer5Vector").setValue(0,4); + getField("Mixer6Type").setValue(0); + getField("Mixer6Vector").setValue(0,0); + getField("Mixer6Vector").setValue(0,1); + getField("Mixer6Vector").setValue(0,2); + getField("Mixer6Vector").setValue(0,3); + getField("Mixer6Vector").setValue(0,4); + getField("Mixer7Type").setValue(0); + getField("Mixer7Vector").setValue(0,0); + getField("Mixer7Vector").setValue(0,1); + getField("Mixer7Vector").setValue(0,2); + getField("Mixer7Vector").setValue(0,3); + getField("Mixer7Vector").setValue(0,4); + getField("Mixer8Type").setValue(0); + getField("Mixer8Vector").setValue(0,0); + getField("Mixer8Vector").setValue(0,1); + getField("Mixer8Vector").setValue(0,2); + getField("Mixer8Vector").setValue(0,3); + getField("Mixer8Vector").setValue(0,4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerSettings obj = new MixerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerSettings)(objMngr.getObject(MixerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4FAE374E; + protected static final String NAME = "MixerSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java new file mode 100644 index 000000000..fbd405b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -0,0 +1,167 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from mixerstatus.xml + **/ +public class MixerStatus extends UAVDataObject { + + public MixerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List Mixer1ElemNames = new ArrayList(); + Mixer1ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer1", "", UAVObjectField.FieldType.FLOAT32, Mixer1ElemNames, null) ); + + List Mixer2ElemNames = new ArrayList(); + Mixer2ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer2", "", UAVObjectField.FieldType.FLOAT32, Mixer2ElemNames, null) ); + + List Mixer3ElemNames = new ArrayList(); + Mixer3ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer3", "", UAVObjectField.FieldType.FLOAT32, Mixer3ElemNames, null) ); + + List Mixer4ElemNames = new ArrayList(); + Mixer4ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer4", "", UAVObjectField.FieldType.FLOAT32, Mixer4ElemNames, null) ); + + List Mixer5ElemNames = new ArrayList(); + Mixer5ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer5", "", UAVObjectField.FieldType.FLOAT32, Mixer5ElemNames, null) ); + + List Mixer6ElemNames = new ArrayList(); + Mixer6ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer6", "", UAVObjectField.FieldType.FLOAT32, Mixer6ElemNames, null) ); + + List Mixer7ElemNames = new ArrayList(); + Mixer7ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer7", "", UAVObjectField.FieldType.FLOAT32, Mixer7ElemNames, null) ); + + List Mixer8ElemNames = new ArrayList(); + Mixer8ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerStatus obj = new MixerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerStatus)(objMngr.getObject(MixerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF6A33F10; + protected static final String NAME = "MixerStatus"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java new file mode 100644 index 000000000..f16ddd199 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The projection of acceleration in the NED reference frame used by @ref Guidance. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The projection of acceleration in the NED reference frame used by @ref Guidance. + +generated from nedaccel.xml + **/ +public class NedAccel extends UAVDataObject { + + public NedAccel() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10001; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NedAccel obj = new NedAccel(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NedAccel GetInstance(UAVObjectManager objMngr, int instID) + { + return (NedAccel)(objMngr.getObject(NedAccel.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8E852CE8; + protected static final String NAME = "NedAccel"; + protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java new file mode 100644 index 000000000..2a09c2b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -0,0 +1,160 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Someone who knows please enter this + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Someone who knows please enter this + +generated from objectpersistence.xml + **/ +public class ObjectPersistence extends UAVDataObject { + + public ObjectPersistence() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List OperationElemNames = new ArrayList(); + OperationElemNames.add("0"); + List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("Load"); + OperationEnumOptions.add("Save"); + OperationEnumOptions.add("Delete"); + fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); + + List SelectionElemNames = new ArrayList(); + SelectionElemNames.add("0"); + List SelectionEnumOptions = new ArrayList(); + SelectionEnumOptions.add("SingleObject"); + SelectionEnumOptions.add("AllSettings"); + SelectionEnumOptions.add("AllMetaObjects"); + SelectionEnumOptions.add("AllObjects"); + fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); + + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ObjectPersistence obj = new ObjectPersistence(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ObjectPersistence GetInstance(UAVObjectManager objMngr, int instID) + { + return (ObjectPersistence)(objMngr.getObject(ObjectPersistence.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x22216832; + protected static final String NAME = "ObjectPersistence"; + protected static String DESCRIPTION = "Someone who knows please enter this"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java new file mode 100644 index 000000000..444009f90 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from positionactual.xml + **/ +public class PositionActual extends UAVDataObject { + + public PositionActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionActual obj = new PositionActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionActual)(objMngr.getObject(PositionActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE0739636; + protected static final String NAME = "PositionActual"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java new file mode 100644 index 000000000..5cf51df71 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + +generated from positiondesired.xml + **/ +public class PositionDesired extends UAVDataObject { + + public PositionDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionDesired obj = new PositionDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2FC4E5BA; + protected static final String NAME = "PositionDesired"; + protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java new file mode 100644 index 000000000..7164c0957 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from ratedesired.xml + **/ +public class RateDesired extends UAVDataObject { + + public RateDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg/s", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg/s", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RateDesired obj = new RateDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RateDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (RateDesired)(objMngr.getObject(RateDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA41B51C; + protected static final String NAME = "RateDesired"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java new file mode 100644 index 000000000..4e9f0b8b8 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the ultrasound sonar sensor with altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the ultrasound sonar sensor with altitude estimate. + +generated from sonaraltitude.xml + **/ +public class SonarAltitude extends UAVDataObject { + + public SonarAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SonarAltitude obj = new SonarAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SonarAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (SonarAltitude)(objMngr.getObject(SonarAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FDD844C; + protected static final String NAME = "SonarAltitude"; + protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java new file mode 100644 index 000000000..8cba8a54c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -0,0 +1,161 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + +generated from stabilizationdesired.xml + **/ +public class StabilizationDesired extends UAVDataObject { + + public StabilizationDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("None"); + StabilizationModeEnumOptions.add("Rate"); + StabilizationModeEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationDesired obj = new StabilizationDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationDesired)(objMngr.getObject(StabilizationDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x41AA9DC2; + protected static final String NAME = "StabilizationDesired"; + protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java new file mode 100644 index 000000000..74c480e1c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -0,0 +1,222 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + +generated from stabilizationsettings.xml + **/ +public class StabilizationSettings extends UAVDataObject { + + public StabilizationSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List ManualRateElemNames = new ArrayList(); + ManualRateElemNames.add("Roll"); + ManualRateElemNames.add("Pitch"); + ManualRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("ManualRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, ManualRateElemNames, null) ); + + List MaximumRateElemNames = new ArrayList(); + MaximumRateElemNames.add("Roll"); + MaximumRateElemNames.add("Pitch"); + MaximumRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); + + List RollRatePIElemNames = new ArrayList(); + RollRatePIElemNames.add("Kp"); + RollRatePIElemNames.add("Ki"); + RollRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + + List PitchRatePIElemNames = new ArrayList(); + PitchRatePIElemNames.add("Kp"); + PitchRatePIElemNames.add("Ki"); + PitchRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + + List YawRatePIElemNames = new ArrayList(); + YawRatePIElemNames.add("Kp"); + YawRatePIElemNames.add("Ki"); + YawRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + + List RollPIElemNames = new ArrayList(); + RollPIElemNames.add("Kp"); + RollPIElemNames.add("Ki"); + RollPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollPI", "", UAVObjectField.FieldType.FLOAT32, RollPIElemNames, null) ); + + List PitchPIElemNames = new ArrayList(); + PitchPIElemNames.add("Kp"); + PitchPIElemNames.add("Ki"); + PitchPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchPI", "", UAVObjectField.FieldType.FLOAT32, PitchPIElemNames, null) ); + + List YawPIElemNames = new ArrayList(); + YawPIElemNames.add("Kp"); + YawPIElemNames.add("Ki"); + YawPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("RollMax").setValue(35); + getField("PitchMax").setValue(35); + getField("YawMax").setValue(35); + getField("ManualRate").setValue(150,0); + getField("ManualRate").setValue(150,1); + getField("ManualRate").setValue(150,2); + getField("MaximumRate").setValue(300,0); + getField("MaximumRate").setValue(300,1); + getField("MaximumRate").setValue(300,2); + getField("RollRatePI").setValue(0.0015,0); + getField("RollRatePI").setValue(0,1); + getField("RollRatePI").setValue(0.3,2); + getField("PitchRatePI").setValue(0.0015,0); + getField("PitchRatePI").setValue(0,1); + getField("PitchRatePI").setValue(0.3,2); + getField("YawRatePI").setValue(0.003,0); + getField("YawRatePI").setValue(0,1); + getField("YawRatePI").setValue(0.3,2); + getField("RollPI").setValue(2,0); + getField("RollPI").setValue(0,1); + getField("RollPI").setValue(50,2); + getField("PitchPI").setValue(2,0); + getField("PitchPI").setValue(0,1); + getField("PitchPI").setValue(50,2); + getField("YawPI").setValue(2,0); + getField("YawPI").setValue(0,1); + getField("YawPI").setValue(50,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationSettings obj = new StabilizationSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationSettings)(objMngr.getObject(StabilizationSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2147404; + protected static final String NAME = "StabilizationSettings"; + protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java new file mode 100644 index 000000000..9136627f4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -0,0 +1,176 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + +generated from systemalarms.xml + **/ +public class SystemAlarms extends UAVDataObject { + + public SystemAlarms() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlarmElemNames = new ArrayList(); + AlarmElemNames.add("OutOfMemory"); + AlarmElemNames.add("StackOverflow"); + AlarmElemNames.add("CPUOverload"); + AlarmElemNames.add("EventSystem"); + AlarmElemNames.add("SDCard"); + AlarmElemNames.add("Telemetry"); + AlarmElemNames.add("ManualControl"); + AlarmElemNames.add("Actuator"); + AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Stabilization"); + AlarmElemNames.add("Guidance"); + AlarmElemNames.add("AHRSComms"); + AlarmElemNames.add("Battery"); + AlarmElemNames.add("FlightTime"); + AlarmElemNames.add("I2C"); + AlarmElemNames.add("GPS"); + List AlarmEnumOptions = new ArrayList(); + AlarmEnumOptions.add("Uninitialised"); + AlarmEnumOptions.add("OK"); + AlarmEnumOptions.add("Warning"); + AlarmEnumOptions.add("Error"); + AlarmEnumOptions.add("Critical"); + fields.add( new UAVObjectField("Alarm", "", UAVObjectField.FieldType.ENUM, AlarmElemNames, AlarmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 4000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Alarm").setValue(0,0); + getField("Alarm").setValue(0,1); + getField("Alarm").setValue(0,2); + getField("Alarm").setValue(0,3); + getField("Alarm").setValue(0,4); + getField("Alarm").setValue(0,5); + getField("Alarm").setValue(0,6); + getField("Alarm").setValue(0,7); + getField("Alarm").setValue(0,8); + getField("Alarm").setValue(0,9); + getField("Alarm").setValue(0,10); + getField("Alarm").setValue(0,11); + getField("Alarm").setValue(0,12); + getField("Alarm").setValue(0,13); + getField("Alarm").setValue(0,14); + getField("Alarm").setValue(0,15); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemAlarms obj = new SystemAlarms(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemAlarms GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemAlarms)(objMngr.getObject(SystemAlarms.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x89C3DCB2; + protected static final String NAME = "SystemAlarms"; + protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java new file mode 100644 index 000000000..d01b55b24 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -0,0 +1,157 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + +generated from systemsettings.xml + **/ +public class SystemSettings extends UAVDataObject { + + public SystemSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirframeTypeElemNames = new ArrayList(); + AirframeTypeElemNames.add("0"); + List AirframeTypeEnumOptions = new ArrayList(); + AirframeTypeEnumOptions.add("FixedWing"); + AirframeTypeEnumOptions.add("FixedWingElevon"); + AirframeTypeEnumOptions.add("FixedWingVtail"); + AirframeTypeEnumOptions.add("VTOL"); + AirframeTypeEnumOptions.add("HeliCP"); + AirframeTypeEnumOptions.add("QuadX"); + AirframeTypeEnumOptions.add("QuadP"); + AirframeTypeEnumOptions.add("Hexa"); + AirframeTypeEnumOptions.add("Octo"); + AirframeTypeEnumOptions.add("Custom"); + AirframeTypeEnumOptions.add("HexaX"); + AirframeTypeEnumOptions.add("OctoV"); + AirframeTypeEnumOptions.add("OctoCoaxP"); + AirframeTypeEnumOptions.add("OctoCoaxX"); + AirframeTypeEnumOptions.add("HexaCoax"); + AirframeTypeEnumOptions.add("Tri"); + fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirframeType").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemSettings obj = new SystemSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemSettings)(objMngr.getObject(SystemSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3875CEE; + protected static final String NAME = "SystemSettings"; + protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java new file mode 100644 index 000000000..7c34360e9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * CPU and memory usage from OpenPilot computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +CPU and memory usage from OpenPilot computer. + +generated from systemstats.xml + **/ +public class SystemStats extends UAVDataObject { + + public SystemStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FlightTimeElemNames = new ArrayList(); + FlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + + List HeapRemainingElemNames = new ArrayList(); + HeapRemainingElemNames.add("0"); + fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List CPUTempElemNames = new ArrayList(); + CPUTempElemNames.add("0"); + fields.add( new UAVObjectField("CPUTemp", "C", UAVObjectField.FieldType.INT8, CPUTempElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemStats obj = new SystemStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemStats)(objMngr.getObject(SystemStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAA26FFFA; + protected static final String NAME = "SystemStats"; + protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java new file mode 100644 index 000000000..3ad065b5c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -0,0 +1,170 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Task information + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Task information + +generated from taskinfo.xml + **/ +public class TaskInfo extends UAVDataObject { + + public TaskInfo() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StackRemainingElemNames = new ArrayList(); + StackRemainingElemNames.add("System"); + StackRemainingElemNames.add("Actuator"); + StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("TelemetryTx"); + StackRemainingElemNames.add("TelemetryTxPri"); + StackRemainingElemNames.add("TelemetryRx"); + StackRemainingElemNames.add("GPS"); + StackRemainingElemNames.add("ManualControl"); + StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("AHRSComms"); + StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("Guidance"); + StackRemainingElemNames.add("FlightPlan"); + fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); + + List RunningElemNames = new ArrayList(); + RunningElemNames.add("System"); + RunningElemNames.add("Actuator"); + RunningElemNames.add("Attitude"); + RunningElemNames.add("TelemetryTx"); + RunningElemNames.add("TelemetryTxPri"); + RunningElemNames.add("TelemetryRx"); + RunningElemNames.add("GPS"); + RunningElemNames.add("ManualControl"); + RunningElemNames.add("Altitude"); + RunningElemNames.add("AHRSComms"); + RunningElemNames.add("Stabilization"); + RunningElemNames.add("Guidance"); + RunningElemNames.add("FlightPlan"); + List RunningEnumOptions = new ArrayList(); + RunningEnumOptions.add("False"); + RunningEnumOptions.add("True"); + fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TaskInfo obj = new TaskInfo(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TaskInfo GetInstance(UAVObjectManager objMngr, int instID) + { + return (TaskInfo)(objMngr.getObject(TaskInfo.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x50F599F0; + protected static final String NAME = "TaskInfo"; + protected static String DESCRIPTION = "Task information"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java new file mode 100644 index 000000000..6995a02b0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select baud rate of telemetry. Warning - this must match your modem. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select baud rate of telemetry. Warning - this must match your modem. + +generated from telemetrysettings.xml + **/ +public class TelemetrySettings extends UAVDataObject { + + public TelemetrySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SpeedElemNames = new ArrayList(); + SpeedElemNames.add("0"); + List SpeedEnumOptions = new ArrayList(); + SpeedEnumOptions.add("2400"); + SpeedEnumOptions.add("4800"); + SpeedEnumOptions.add("9600"); + SpeedEnumOptions.add("19200"); + SpeedEnumOptions.add("38400"); + SpeedEnumOptions.add("57600"); + SpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Speed").setValue(5); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TelemetrySettings obj = new TelemetrySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA608C526; + protected static final String NAME = "TelemetrySettings"; + protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java new file mode 100644 index 000000000..4eca6ea82 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -0,0 +1,87 @@ +/** + ****************************************************************************** + * + * + * @file uavobjectsinittemplate.java + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief the template for the uavobjects init part + * $(GENERATEDWARNING) + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.UAVObjectManager; + +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { + objMngr.registerObject( new ActuatorCommand() ); + objMngr.registerObject( new ActuatorDesired() ); + objMngr.registerObject( new ActuatorSettings() ); + objMngr.registerObject( new AHRSCalibration() ); + objMngr.registerObject( new AHRSSettings() ); + objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AttitudeActual() ); + objMngr.registerObject( new AttitudeRaw() ); + objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new BaroAltitude() ); + objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatteryState() ); + objMngr.registerObject( new FlightPlanControl() ); + objMngr.registerObject( new FlightPlanSettings() ); + objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSTelemetryStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GuidanceSettings() ); + objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new ManualControlCommand() ); + objMngr.registerObject( new ManualControlSettings() ); + objMngr.registerObject( new MixerSettings() ); + objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PositionActual() ); + objMngr.registerObject( new PositionDesired() ); + objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new SonarAltitude() ); + objMngr.registerObject( new StabilizationDesired() ); + objMngr.registerObject( new StabilizationSettings() ); + objMngr.registerObject( new SystemAlarms() ); + objMngr.registerObject( new SystemSettings() ); + objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TelemetrySettings() ); + objMngr.registerObject( new VelocityActual() ); + objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new WatchdogStatus() ); + + } catch (Exception e) { + e.printStackTrace(); + } + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java new file mode 100644 index 000000000..649e6c122 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + +generated from velocityactual.xml + **/ +public class VelocityActual extends UAVDataObject { + + public VelocityActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityActual obj = new VelocityActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityActual)(objMngr.getObject(VelocityActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x48009C88; + protected static final String NAME = "VelocityActual"; + protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java new file mode 100644 index 000000000..27f290898 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + +generated from velocitydesired.xml + **/ +public class VelocityDesired extends UAVDataObject { + + public VelocityDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityDesired obj = new VelocityDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityDesired)(objMngr.getObject(VelocityDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x122F5E3A; + protected static final String NAME = "VelocityDesired"; + protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java new file mode 100644 index 000000000..3adcad96b --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * For monitoring the flags in the watchdog and especially the bootup flags + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +For monitoring the flags in the watchdog and especially the bootup flags + +generated from watchdogstatus.xml + **/ +public class WatchdogStatus extends UAVDataObject { + + public WatchdogStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BootupFlagsElemNames = new ArrayList(); + BootupFlagsElemNames.add("0"); + fields.add( new UAVObjectField("BootupFlags", "", UAVObjectField.FieldType.UINT16, BootupFlagsElemNames, null) ); + + List ActiveFlagsElemNames = new ArrayList(); + ActiveFlagsElemNames.add("0"); + fields.add( new UAVObjectField("ActiveFlags", "", UAVObjectField.FieldType.UINT16, ActiveFlagsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WatchdogStatus obj = new WatchdogStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WatchdogStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (WatchdogStatus)(objMngr.getObject(WatchdogStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD646E910; + protected static final String NAME = "WatchdogStatus"; + protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From f33862509216ebd4383db53b0f3b42b9ac0fc851 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:12:32 -0600 Subject: [PATCH 052/165] Removed various debugging outputs and exceptions for now (will add back in a more principled manner later). Also updated the auto generated code. --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 30 +++++++---- .../templates/uavobjectsinittemplate.java | 52 ++++--------------- .../templates/uavobjecttemplate.java | 6 +-- .../java/uavobjectgeneratorjava.cpp | 4 +- 7 files changed, 37 insertions(+), 63 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index b24a2abf5..6f3f456df 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,6 +1,7 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index f0a2248f5..de04f81c5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,7 +9,7 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); mobj = null; this.isSet = isSet; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index bf2c87d7e..cc6718ebd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -105,10 +105,9 @@ public abstract class UAVObject { * When unable to unpack a field */ public void initializeFields(List fields, ByteBuffer data, - int numBytes) throws Exception { + int numBytes) { // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; -// this.data = data; this.fields = fields; // Initialize fields for (int n = 0; n < fields.size(); ++n) { @@ -288,7 +287,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ebd7b52..a5fc6b7da 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,8 @@ public class UAVObjectField { * to the arm/uavtalk standard (little endian) * @param dataOut * @return the number of bytes added - * @throws Exception */ - public int pack(ByteBuffer dataOut) throws Exception { + **/ + public int pack(ByteBuffer dataOut) { //QMutexLocker locker(obj->getMutex()); // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); @@ -147,7 +147,7 @@ public class UAVObjectField { break; case STRING: // TODO: Implement strings - throw new Exception("Strings not yet implemented"); + throw new Error("Strings not yet implemented"); } // Done return getNumBytes(); @@ -358,13 +358,13 @@ public class UAVObjectField { } } - public double getDouble() throws Exception { return getDouble(0); }; - public double getDouble(int index) throws Exception { + public double getDouble() { return getDouble(0); }; + public double getDouble(int index) { return Double.valueOf((Double) getValue(index)); } - public void setDouble(double value) throws Exception { setDouble(value, 0); }; - public void setDouble(double value, int index) throws Exception { + public void setDouble(double value) { setDouble(value, 0); }; + public void setDouble(double value, int index) { setValue(value, index); } @@ -436,9 +436,7 @@ public class UAVObjectField { String sout = new String(); sout += name + ": [ "; for (int n = 0; n < numElements; ++n) - { sout += String.valueOf(n) + "(" + getValue(n) + ") "; - } sout += "] " + units + "\n"; return sout; @@ -488,6 +486,18 @@ public class UAVObjectField { ((ArrayList) data).add((long) 0); } break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -546,8 +556,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - - System.out.println(this); } /** diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java index 5185ab237..7f9edb791 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java @@ -26,50 +26,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -package org.openpilot.uavtalk; +package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.uavobjects.*; -import org.openpilot.uavtalk.UAVObject; -import java.util.HashMap; +import org.openpilot.uavtalk.UAVObjectManager; -public class UAVObjects { - - private static UAVObject[] uavobjects=null; - private static HashMap id2obj; - - public static void init() { - if (uavobjects==null) { - uavobjects=new UAVObject[] { -$(OBJINIT) - }; - id2obj=new HashMap(); - for (int i=0;i< uavobjects.length;i++) - id2obj.put(uavobjects[i].getObjID(),i); +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { +$(OBJINIT) + } catch (Exception e) { + e.printStackTrace(); + } } - } - - public static UAVObject[] getUAVObjectArray() { - return uavobjects; - } - - public static boolean hasObjectWithID(int id) { - return id2obj.containsKey(id); - } - - public static UAVObject getObjectByID(int id) { - if (!hasObjectWithID(id)) - return null; - return uavobjects[(Integer)id2obj.get(id)]; - } - - public static UAVObject getObjectByName(String name) { - return uavobjects[0]; - } - - public static void printAll() { - for (UAVObject obj : uavobjects) - System.out.println(obj.getObjName()); - } - -$(OBJGETTER) } \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index af8f48fce..64e2461f5 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -36,7 +36,6 @@ import java.util.ListIterator; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; import org.openpilot.uavtalk.UAVObjectField; /** @@ -46,7 +45,7 @@ generated from $(XMLFILE) **/ public class $(NAME) extends UAVDataObject { - public $(NAME)() throws Exception { + public $(NAME)() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); @@ -57,10 +56,9 @@ $(FIELDSINIT) int numBytes = 0; ListIterator li = fields.listIterator(); while(li.hasNext()) { - numBytes += li.next().getNumBytesElement(); + numBytes += li.next().getNumBytes(); } NUMBYTES = numBytes; - // Initialize object initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 7319b7767..b8d4b33d5 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -54,14 +54,14 @@ bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepa ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + javaObjInit.append("\t\t\tobjMngr.registerObject( new " + info->name + "() );\n"); objInc.append("#include \"" + info->namelc + ".h\"\n"); } // Write the gcs object inialization files javaInitTemplate.replace( QString("$(OBJINC)"), objInc); javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/UAVObjectsInitialize.java", javaInitTemplate ); if (!res) { cout << "Error: Could not write output files" << endl; return false; From 6dd509ded3547b146d52c12066f28b31525c139b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:33:56 -0600 Subject: [PATCH 053/165] Make the initial values for enums be the string. Make setValue accept numerical or string constants for enums. Only returns a string though. --- .../src/org/openpilot/uavtalk/UAVObjectField.java | 10 ++++++++-- .../generators/java/uavobjectgeneratorjava.cpp | 8 ++++---- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a5fc6b7da..bb525a5e0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -343,8 +343,14 @@ public class UAVObjectField { break; } case ENUM: - { - byte val = (byte) options.indexOf((String) data); + { + byte val; + try { + // Test if numeric constant passed in + val = ((Number) data).byteValue(); + } catch (Exception e) { + val = (byte) options.indexOf((String) data); + } //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index b8d4b33d5..e942b238f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -210,9 +210,9 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%2\");\n") .arg( info->fields[n]->name ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + .arg( info->fields[n]->defaultValues[0] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { @@ -233,10 +233,10 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) for (int idx = 0; idx < info->fields[n]->numElements; ++idx) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%3\",%2);\n") .arg( info->fields[n]->name ) .arg( idx ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + .arg( info->fields[n]->defaultValues[idx] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") From 1f202089d197dc54571d1b1d3b341c5c4859591f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:36:49 -0600 Subject: [PATCH 054/165] Some cosmetic changes, also initialize the Metadata properly --- .../src/org/openpilot/uavtalk/UAVMetaObject.java | 13 ++++++++++++- androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObjectField.java | 6 +----- 3 files changed, 14 insertions(+), 7 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 70e661d46..98e4bd626 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -3,12 +3,15 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.ArrayList; import java.util.List; +import java.util.ListIterator; public class UAVMetaObject extends UAVObject { public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; + + ownMetadata = new Metadata(); ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; @@ -48,9 +51,17 @@ public class UAVMetaObject extends UAVObject { fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + + // Initialize object + // Initialize parent super.initialize(0); - super.initializeFields(fields, ByteBuffer.allocate(10), 10); + initializeFields(fields, ByteBuffer.allocate(numBytes), numBytes); // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index cc6718ebd..a990def2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -461,7 +461,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index bb525a5e0..0b72c33c8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -440,11 +440,7 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": [ "; - for (int n = 0; n < numElements; ++n) - sout += String.valueOf(n) + "(" + getValue(n) + ") "; - - sout += "] " + units + "\n"; + sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; return sout; } From 689afeabb5bbfbe466f0f096762adc8d673500c7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:11 -0600 Subject: [PATCH 055/165] Initial implementation of UAVTalk protocol and a test platform for it and the UAVObjectManager --- .../openpilot/uavtalk/UAVObjectManager.java | 22 + .../src/org/openpilot/uavtalk/UAVTalk.java | 808 ++++++++++++++++++ .../org/openpilot/uavtalk/ObjMngrTest.java | 22 + .../tests/org/openpilot/uavtalk/TalkTest.java | 74 ++ 4 files changed, 926 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVTalk.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TalkTest.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index d75b14b85..2e531fc85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -118,6 +118,7 @@ public class UAVObjectManager { // Create metaobject String mname = obj.getName(); mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); // Initialize object obj.initialize(0, mobj); @@ -224,6 +225,17 @@ public class UAVObjectManager { */ } + + /** + * Returns a specific object by name only, returns instance ID zero + * @param name The object name + * @return The object or null if not found + */ + public UAVObject getObject(String name) + { + return getObject(name, 0, 0); + } + /** * Get a specific object given its name and instance ID * @returns The object is found or NULL if not @@ -233,6 +245,16 @@ public class UAVObjectManager { return getObject(name, 0, instId); } + /** + * Get a specific object with given object ID and instance ID zero + * @param objId the object id + * @returns The object is found or NULL if not + */ + public UAVObject getObject(int objId) + { + return getObject(null, objId, 0); + } + /** * Get a specific object given its object and instance ID * @returns The object is found or NULL if not diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java new file mode 100644 index 000000000..07b061bc9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -0,0 +1,808 @@ +package org.openpilot.uavtalk; + +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; +import java.io.IOException; +import java.io.InputStream; +import java.io.OutputStream; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; + +public class UAVTalk { + + /** + * Constants + */ + private static final int SYNC_VAL = 0x3C; + + private static final short crc_table[] = { + 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, + 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, + 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, + 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, + 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, + 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, + 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, + 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, + 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, + 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, + 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, + 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, + 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, + 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 + }; + + enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + + static final int TYPE_MASK = 0xFC; + static final int TYPE_VER = 0x20; + static final int TYPE_OBJ = (TYPE_VER | 0x00); + static final int TYPE_OBJ_REQ = (TYPE_VER | 0x01); + static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); + static final int TYPE_ACK = (TYPE_VER | 0x03); + + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + + static final int CHECKSUM_LENGTH = 1; + + static final int MAX_PAYLOAD_LENGTH = 256; + + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + + static final int ALL_INSTANCES = 0xFFFF; + static final int TX_BUFFER_SIZE = 2*1024; + + /** + * Private data + */ + InputStream inStream; + OutputStream outStream; + UAVObjectManager objMngr; + + UAVObject respObj; + boolean respAllInstances; + // Variables used by the receive state machine + ByteBuffer rxTmpBuffer /* 4 */; + ByteBuffer rxBuffer; + int rxType; + int rxObjId; + int rxInstId; + int rxLength; + int rxPacketLength; + + int rxCSPacket, rxCS; + int rxCount; + int packetSize; + RxStateType rxState; + ComStats stats = new ComStats(); + + /** + * Comm stats + */ + public class ComStats { + public int txBytes = 0; + public int rxBytes = 0; + public int txObjectBytes = 0; + public int rxObjectBytes = 0; + public int rxObjects = 0; + public int txObjects = 0; + public int txErrors = 0; + public int rxErrors = 0; + } + + /** + * Constructor + */ + public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) + { + this.objMngr = objMngr; + this.inStream = inStream; + this.outStream = outStream; + + rxState = RxStateType.STATE_SYNC; + rxPacketLength = 0; + + //mutex = new QMutex(QMutex::Recursive); + + respObj = null; + resetStats(); + rxTmpBuffer = ByteBuffer.allocate(4); + rxTmpBuffer.order(ByteOrder.LITTLE_ENDIAN); + rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); + rxBuffer.order(ByteOrder.LITTLE_ENDIAN); + + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + } + + /** + * Reset the statistics counters + */ + public void resetStats() + { + //QMutexLocker locker(mutex); + stats = new ComStats(); + } + + /** + * Get the statistics counters + */ + public ComStats getStats() + { + //QMutexLocker locker(mutex); + return stats; + } + + /** + * Called each time there are data in the input buffer + */ + public void processInputStream() + { + int val; + + while (true) + { + try { + //inStream.wait(); + val = inStream.read(); + } /*catch (InterruptedException e) { + // TODO Auto-generated catch block + System.out.println("Connection was aborted\n"); + e.printStackTrace(); + break; + }*/ catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + break; + } + //System.out.println("Received byte " + val + " in state + " + rxState); + processInputByte(val); + } + } + + /** + * Request an update for the specified object, on success the object data would have been + * updated by the GCS. + * \param[in] obj Object to update + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) + { + //QMutexLocker locker(mutex); + return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); + } + + /** + * Send the specified object through the telemetry link. + * \param[in] obj Object to send + * \param[in] acked Selects if an ack is required + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + { + //QMutexLocker locker(mutex); + if (acked) + { + return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); + } + else + { + return objectTransaction(obj, TYPE_OBJ, allInstances); + } + } + + /** + * Cancel a pending transaction + */ + public void cancelTransaction() + { + //QMutexLocker locker(mutex); + respObj = null; + } + + /** + * Execute the requested transaction on an object. + * \param[in] obj Object + * \param[in] type Transaction type + * TYPE_OBJ: send object, + * TYPE_OBJ_REQ: request object update + * TYPE_OBJ_ACK: send object with an ack + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) + { + // Send object depending on if a response is needed + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) + { + if ( transmitObject(obj, type, allInstances) ) + { + respObj = obj; + respAllInstances = allInstances; + return true; + } + else + { + return false; + } + } + else if (type == TYPE_OBJ) + { + return transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + return false; + } + } + + /** + * Process an byte from the telemetry stream. + * \param[in] rxbyte Received byte + * \return Success (true), Failure (false) + */ + public boolean processInputByte(int rxbyte) + { + assert(objMngr != null); + + // Update stats + stats.rxBytes++; + + rxPacketLength++; // update packet byte count + + // Receive state machine + switch (rxState) + { + case STATE_SYNC: + + if (rxbyte != SYNC_VAL) + break; + + // Initialize and update CRC + rxCS = updateCRC(0, rxbyte); + + rxPacketLength = 1; + + rxState = RxStateType.STATE_TYPE; + break; + + case STATE_TYPE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if ((rxbyte & TYPE_MASK) != TYPE_VER) + { + rxState = RxStateType.STATE_SYNC; + break; + } + + rxType = rxbyte; + + packetSize = 0; + + rxState = RxStateType.STATE_SIZE; + rxCount = 0; + break; + + case STATE_SIZE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if (rxCount == 0) + { + packetSize += rxbyte; + rxCount++; + break; + } + + packetSize += (rxbyte << 8) & 0xff00; + + if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) + { // incorrect packet size + rxState = RxStateType.STATE_SYNC; + break; + } + + rxCount = 0; + rxState = RxStateType.STATE_OBJID; + rxTmpBuffer.position(0); + break; + + case STATE_OBJID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 4) + break; + + // Search for object, if not found reset state machine + rxObjId = rxTmpBuffer.getInt(0); + { + UAVObject rxObj = objMngr.getObject(rxObjId); + if (rxObj == null) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Determine data length + if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK) + rxLength = 0; + else + rxLength = rxObj.getNumBytes(); + + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check if this is a single instance object (i.e. if the instance ID field is coming next) + if (rxObj.isSingleInstance()) + { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } + else + { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } + } + + break; + + case STATE_INSTID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 2) + break; + + rxInstId = rxTmpBuffer.getShort(0); + + rxCount = 0; + + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + + break; + + case STATE_DATA: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + //System.out.println(rxCount + "/" + rxLength); + rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < rxLength) + break; + + rxState = RxStateType.STATE_CS; + rxCount = 0; + break; + + case STATE_CS: + + // The CRC byte + rxCSPacket = rxbyte; + + if (rxCS != rxCSPacket) + { // packet error - faulty CRC + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + if (rxPacketLength != (packetSize + 1)) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + //mutex->lock(); + rxBuffer.position(0); + receiveObject(rxType, rxObjId, rxInstId, rxBuffer); + stats.rxObjectBytes += rxLength; + stats.rxObjects++; + //mutex->unlock(); + + rxState = RxStateType.STATE_SYNC; + break; + + default: + rxState = RxStateType.STATE_SYNC; + stats.rxErrors++; + } + + // Done + return true; + } + + /** + * Receive an object. This function process objects received through the telemetry stream. + * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) + * \param[in] obj Handle of the received object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] data Data buffer + * \param[in] length Buffer length + * \return Success (true), Failure (false) + */ + public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + UAVObject obj = null; + boolean error = false; + boolean allInstances = (instId == ALL_INSTANCES? true : false); + + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + // Process message type + switch (type) { + case TYPE_OBJ: + // All instances, not allowed for OBJ messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Check if an ack is pending + if ( obj != null ) + { + updateAck(obj); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_ACK: + // All instances, not allowed for OBJ_ACK messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Transmit ACK + if ( obj != null ) + { + transmitObject(obj, TYPE_ACK, false); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_REQ: + // Get object, if all instances are requested get instance 0 of the object + if (allInstances) + { + obj = objMngr.getObject(objId); + } + else + { + obj = objMngr.getObject(objId, instId); + } + // If object was found transmit it + if (obj != null) + { + transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + error = true; + } + break; + case TYPE_ACK: + // All instances, not allowed for ACK messages + if (!allInstances) + { + // Get object + obj = objMngr.getObject(objId, instId); + // Check if an ack is pending + if (obj != null) + { + updateAck(obj); + } + else + { + error = true; + } + } + break; + default: + error = true; + } + // Done + return !error; + } + + /** + * Update the data of an object from a byte array (unpack). + * If the object instance could not be found in the list, then a + * new one is created. + */ + public UAVObject updateObject(int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + // Get object + UAVObject obj = objMngr.getObject(objId, instId); + // If the instance does not exist create it + if (obj == null) + { + // Get the object type + UAVObject tobj = objMngr.getObject(objId); + if (tobj == null) + { + return null; + } + // Make sure this is a data object + UAVDataObject dobj = null; + try { + dobj = (UAVDataObject) tobj; + } catch (Exception e) { + // Failed to cast to a data object + return null; + } + + // Create a new instance, unpack and register + UAVDataObject instobj = dobj.clone(instId); + try { + if ( !objMngr.registerObject(instobj) ) + { + return null; + } + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + instobj.unpack(data); + return instobj; + } + else + { + // Unpack data into object instance + // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + obj.unpack(data); + return obj; + } + } + + /** + * Check if a transaction is pending and if yes complete it. + */ + public void updateAck(UAVObject obj) + { + if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) + { + respObj = null; + // TODO: Signals +// emit transactionCompleted(obj); + } + } + + /** + * Send an object through the telemetry link. + * \param[in] obj Object to send + * \param[in] type Transaction type + * \param[in] allInstances True is all instances of the object are to be sent + * \return Success (true), Failure (false) + */ + public boolean transmitObject(UAVObject obj, int type, boolean allInstances) + { + // If all instances are requested on a single instance object it is an error + if (allInstances && obj.isSingleInstance()) + { + allInstances = false; + } + + // Process message type + if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) + { + if (allInstances) + { + // Get number of instances + int numInst = objMngr.getNumInstances(obj.getObjID()); + // Send all instances + for (int instId = 0; instId < numInst; ++instId) + { + UAVObject inst = objMngr.getObject(obj.getObjID(), instId); + transmitSingleObject(inst, type, false); + } + return true; + } + else + { + return transmitSingleObject(obj, type, false); + } + } + else if (type == TYPE_OBJ_REQ) + { + return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); + } + else if (type == TYPE_ACK) + { + if (!allInstances) + { + return transmitSingleObject(obj, TYPE_ACK, false); + } + else + { + return false; + } + } + else + { + return false; + } + } + + + /** + * Send an object through the telemetry link. + * \param[in] obj Object handle to send + * \param[in] type Transaction type + * \return Success (true), Failure (false) + */ + public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + { + int length; + int dataOffset; + int objId; + int instId; + int allInstId = ALL_INSTANCES; + + assert(objMngr != null && outStream != null); + + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); + bbuf.order(ByteOrder.LITTLE_ENDIAN); + + // Determine data length + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) + { + length = 0; + } + else + { + length = obj.getNumBytes(); + } + + // Setup type and object id fields + bbuf.put((byte) (SYNC_VAL & 0xff)); + bbuf.put((byte) (type & 0xff)); + bbuf.putShort((short) (length + + 2 /* SYNC, Type */ + + 2 /* Size */ + + 4 /* ObjID */ + + (obj.isSingleInstance() ? 0 : 2) )); + bbuf.putInt(obj.getObjID()); + + // Setup instance ID if one is required + if ( !obj.isSingleInstance() ) + { + // Check if all instances are requested + if (allInstances) + bbuf.putShort((short) (allInstId & 0xffff)); + else + bbuf.putShort((short) (obj.getInstID() & 0xffff)); + } + + // Check length + if (length >= MAX_PAYLOAD_LENGTH) + return false; + + // Copy data (if any) + if (length > 0) + try { + if ( obj.pack(bbuf) == 0) + return false; + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + + // Calculate checksum + bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + + try { + outStream.write(bbuf.array()); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + +// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE +// // Send buffer, check that the transmit backlog does not grow above limit +// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) +// { +// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); +// } +// else +// { +// ++stats.txErrors; +// return false; +// } + + // Update stats + ++stats.txObjects; + stats.txBytes += bbuf.position(); + stats.txObjectBytes += length; + + // Done + return true; + } + + /** + * Update the crc value with new data. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ + * using the configuration: + * Width = 8 + * Poly = 0x07 + * XorIn = 0x00 + * ReflectIn = False + * XorOut = 0x00 + * ReflectOut = False + * Algorithm = table-driven + * + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param length Number of bytes in the \a data buffer. + * \return The updated crc value. + */ + int updateCRC(int crc, int data) + { + return crc_table[crc ^ (data & 0xff)]; + } + int updateCRC(int crc, byte [] data) + { + for (int i = 0; i < data.length; i++) + crc = updateCRC(crc, (int) data[i]); + return crc; + } + + + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java new file mode 100644 index 000000000..0131d1246 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java @@ -0,0 +1,22 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjMngrTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetObjects() { + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); +// System.out.println(objMngr.getObject("ActuatorSettings", 0)); + } + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java new file mode 100644 index 000000000..6dc23530e --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -0,0 +1,74 @@ +package org.openpilot.uavtalk; +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TalkTest { + + static UAVObjectManager objMngr; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 8000; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + @Test + public void testProcessInputStream() { + Socket connection = null; + UAVTalk talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + talk.processInputStream(); + } + + @Test + public void testSendObjectRequest() { + fail("Not yet implemented"); + } + + @Test + public void testSendObject() { + fail("Not yet implemented"); + } + + @Test + public void testReceiveObject() { + fail("Not yet implemented"); + } + + @Test + public void testUpdateObject() { + fail("Not yet implemented"); + } + +} From c7961b9f384c9f8e98cfe99399e49a4ffc4b3dea Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:39 -0600 Subject: [PATCH 056/165] Updates to various objects --- .../uavtalk/uavobjects/AHRSCalibration.java | 2 +- .../uavtalk/uavobjects/AHRSSettings.java | 4 +- .../uavtalk/uavobjects/ActuatorSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/BatterySettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 4 +- .../uavtalk/uavobjects/HomeLocation.java | 2 +- .../uavobjects/ManualControlSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/MixerSettings.java | 16 +++---- .../uavtalk/uavobjects/SystemAlarms.java | 32 +++++++------- .../uavtalk/uavobjects/SystemSettings.java | 2 +- .../uavtalk/uavobjects/TelemetrySettings.java | 2 +- 13 files changed, 80 insertions(+), 80 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index a3096ad39..922582398 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -171,7 +171,7 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue(0); + getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index a38915c28..c49c04778 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -132,10 +132,10 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Algorithm").setValue(1); + getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); getField("YawBias").setValue(0); getField("PitchBias").setValue(0); getField("RollBias").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index ebbfaeb17..542b433d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -358,20 +358,20 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue(8); - getField("FixedWingRoll2").setValue(8); - getField("FixedWingPitch1").setValue(8); - getField("FixedWingPitch2").setValue(8); - getField("FixedWingYaw").setValue(8); - getField("FixedWingThrottle").setValue(8); - getField("VTOLMotorN").setValue(8); - getField("VTOLMotorNE").setValue(8); - getField("VTOLMotorE").setValue(8); - getField("VTOLMotorSE").setValue(8); - getField("VTOLMotorS").setValue(8); - getField("VTOLMotorSW").setValue(8); - getField("VTOLMotorW").setValue(8); - getField("VTOLMotorNW").setValue(8); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -400,14 +400,14 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); - getField("ChannelType").setValue(0,0); - getField("ChannelType").setValue(0,1); - getField("ChannelType").setValue(0,2); - getField("ChannelType").setValue(0,3); - getField("ChannelType").setValue(0,4); - getField("ChannelType").setValue(0,5); - getField("ChannelType").setValue(0,6); - getField("ChannelType").setValue(0,7); + getField("ChannelType").setValue("PWM",0); + getField("ChannelType").setValue("PWM",1); + getField("ChannelType").setValue("PWM",2); + getField("ChannelType").setValue("PWM",3); + getField("ChannelType").setValue("PWM",4); + getField("ChannelType").setValue("PWM",5); + getField("ChannelType").setValue("PWM",6); + getField("ChannelType").setValue("PWM",7); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java index 19e477b62..6af673930 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -121,7 +121,7 @@ public class BatterySettings extends UAVDataObject { { getField("BatteryVoltage").setValue(11.1); getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue(0); + getField("BatteryType").setValue("LiPo"); getField("Calibrations").setValue(1,0); getField("Calibrations").setValue(1,1); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index 2e453eda5..fdc5bfcb0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -104,7 +104,7 @@ public class FlightPlanControl extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Command").setValue(0); + getField("Command").setValue("Start"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 00920553c..2303514c0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -144,8 +144,8 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Status").setValue(0); - getField("ErrorType").setValue(0); + getField("Status").setValue("Stopped"); + getField("ErrorType").setValue("None"); getField("Debug1").setValue(0); getField("Debug2").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2cde12f64..2fe8bb437 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -142,7 +142,7 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue(0); + getField("GuidanceMode").setValue("DUAL_LOOP"); getField("HorizontalP").setValue(0.2,0); getField("HorizontalP").setValue(150,1); getField("HorizontalVelPID").setValue(0.1,0); @@ -155,7 +155,7 @@ public class GuidanceSettings extends UAVDataObject { getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue(0); + getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 2adebce70..5941c069c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -139,7 +139,7 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue(0); + getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c14aef758..83697999a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -309,28 +309,28 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue(0); - getField("Roll").setValue(0); - getField("Pitch").setValue(1); - getField("Yaw").setValue(2); - getField("Throttle").setValue(3); - getField("FlightMode").setValue(4); - getField("Accessory1").setValue(8); - getField("Accessory2").setValue(8); - getField("Accessory3").setValue(8); - getField("Arming").setValue(0); - getField("Stabilization1Settings").setValue(2,0); - getField("Stabilization1Settings").setValue(2,1); - getField("Stabilization1Settings").setValue(2,2); - getField("Stabilization2Settings").setValue(2,0); - getField("Stabilization2Settings").setValue(2,1); - getField("Stabilization2Settings").setValue(2,2); - getField("Stabilization3Settings").setValue(2,0); - getField("Stabilization3Settings").setValue(2,1); - getField("Stabilization3Settings").setValue(2,2); - getField("FlightModePosition").setValue(0,0); - getField("FlightModePosition").setValue(1,1); - getField("FlightModePosition").setValue(2,2); + getField("InputMode").setValue("PWM"); + getField("Roll").setValue("Channel1"); + getField("Pitch").setValue("Channel2"); + getField("Yaw").setValue("Channel3"); + getField("Throttle").setValue("Channel4"); + getField("FlightMode").setValue("Channel5"); + getField("Accessory1").setValue("None"); + getField("Accessory2").setValue("None"); + getField("Accessory3").setValue("None"); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Attitude",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Attitude",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Attitude",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Manual",1); + getField("FlightModePosition").setValue("Manual",2); getField("ChannelMax").setValue(2000,0); getField("ChannelMax").setValue(2000,1); getField("ChannelMax").setValue(2000,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 554e366f3..9aa87d49e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -270,49 +270,49 @@ public class MixerSettings extends UAVDataObject { getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); - getField("Mixer1Type").setValue(0); + getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); getField("Mixer1Vector").setValue(0,2); getField("Mixer1Vector").setValue(0,3); getField("Mixer1Vector").setValue(0,4); - getField("Mixer2Type").setValue(0); + getField("Mixer2Type").setValue("Disabled"); getField("Mixer2Vector").setValue(0,0); getField("Mixer2Vector").setValue(0,1); getField("Mixer2Vector").setValue(0,2); getField("Mixer2Vector").setValue(0,3); getField("Mixer2Vector").setValue(0,4); - getField("Mixer3Type").setValue(0); + getField("Mixer3Type").setValue("Disabled"); getField("Mixer3Vector").setValue(0,0); getField("Mixer3Vector").setValue(0,1); getField("Mixer3Vector").setValue(0,2); getField("Mixer3Vector").setValue(0,3); getField("Mixer3Vector").setValue(0,4); - getField("Mixer4Type").setValue(0); + getField("Mixer4Type").setValue("Disabled"); getField("Mixer4Vector").setValue(0,0); getField("Mixer4Vector").setValue(0,1); getField("Mixer4Vector").setValue(0,2); getField("Mixer4Vector").setValue(0,3); getField("Mixer4Vector").setValue(0,4); - getField("Mixer5Type").setValue(0); + getField("Mixer5Type").setValue("Disabled"); getField("Mixer5Vector").setValue(0,0); getField("Mixer5Vector").setValue(0,1); getField("Mixer5Vector").setValue(0,2); getField("Mixer5Vector").setValue(0,3); getField("Mixer5Vector").setValue(0,4); - getField("Mixer6Type").setValue(0); + getField("Mixer6Type").setValue("Disabled"); getField("Mixer6Vector").setValue(0,0); getField("Mixer6Vector").setValue(0,1); getField("Mixer6Vector").setValue(0,2); getField("Mixer6Vector").setValue(0,3); getField("Mixer6Vector").setValue(0,4); - getField("Mixer7Type").setValue(0); + getField("Mixer7Type").setValue("Disabled"); getField("Mixer7Vector").setValue(0,0); getField("Mixer7Vector").setValue(0,1); getField("Mixer7Vector").setValue(0,2); getField("Mixer7Vector").setValue(0,3); getField("Mixer7Vector").setValue(0,4); - getField("Mixer8Type").setValue(0); + getField("Mixer8Type").setValue("Disabled"); getField("Mixer8Vector").setValue(0,0); getField("Mixer8Vector").setValue(0,1); getField("Mixer8Vector").setValue(0,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 9136627f4..e9313472c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -121,22 +121,22 @@ public class SystemAlarms extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Alarm").setValue(0,0); - getField("Alarm").setValue(0,1); - getField("Alarm").setValue(0,2); - getField("Alarm").setValue(0,3); - getField("Alarm").setValue(0,4); - getField("Alarm").setValue(0,5); - getField("Alarm").setValue(0,6); - getField("Alarm").setValue(0,7); - getField("Alarm").setValue(0,8); - getField("Alarm").setValue(0,9); - getField("Alarm").setValue(0,10); - getField("Alarm").setValue(0,11); - getField("Alarm").setValue(0,12); - getField("Alarm").setValue(0,13); - getField("Alarm").setValue(0,14); - getField("Alarm").setValue(0,15); + getField("Alarm").setValue("Uninitialised",0); + getField("Alarm").setValue("Uninitialised",1); + getField("Alarm").setValue("Uninitialised",2); + getField("Alarm").setValue("Uninitialised",3); + getField("Alarm").setValue("Uninitialised",4); + getField("Alarm").setValue("Uninitialised",5); + getField("Alarm").setValue("Uninitialised",6); + getField("Alarm").setValue("Uninitialised",7); + getField("Alarm").setValue("Uninitialised",8); + getField("Alarm").setValue("Uninitialised",9); + getField("Alarm").setValue("Uninitialised",10); + getField("Alarm").setValue("Uninitialised",11); + getField("Alarm").setValue("Uninitialised",12); + getField("Alarm").setValue("Uninitialised",13); + getField("Alarm").setValue("Uninitialised",14); + getField("Alarm").setValue("Uninitialised",15); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index d01b55b24..99bceb6ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -117,7 +117,7 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("AirframeType").setValue(0); + getField("AirframeType").setValue("FixedWing"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java index 6995a02b0..675f9b592 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -108,7 +108,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue(5); + getField("Speed").setValue("57600"); } From 7d13f4869d60195b2ec69c3962479c4a9a3fa4f4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:54:43 -0600 Subject: [PATCH 057/165] Made a lot of critical functions synchronized to block race conditions (essentialy implements a mutex locker for that object). Also added callbacks to UAVObjects for unpacked and updated. More to come. Finally test case that checks that we get FlightStatus through UAVTalk (i.e. that the aircraft is talking). --- .../src/org/openpilot/uavtalk/UAVObject.java | 49 +++++++++++++++++-- .../org/openpilot/uavtalk/UAVObjectField.java | 18 +++---- .../openpilot/uavtalk/UAVObjectManager.java | 14 +++--- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 ++++++- .../tests/org/openpilot/uavtalk/TalkTest.java | 33 +++++++++++-- 5 files changed, 107 insertions(+), 25 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index a990def2c..6ede86094 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -3,9 +3,50 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.List; import java.util.ListIterator; +import java.util.Observer; +import java.util.Observable; public abstract class UAVObject { + public class CallbackListener extends Observable { + private UAVObject parent; + + public CallbackListener(UAVObject parent) { + this.parent = parent; + } + + public void event () { + setChanged(); + notifyObservers(parent); + } + } + + private CallbackListener updatedListeners = new CallbackListener(this); + public void addUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.addObserver(o); + } + } + void updated() { + synchronized(updatedListeners) { + updatedListeners.event(); + } + } + + private CallbackListener unpackedListeners = new CallbackListener(this); + public void addUnpackedObserver(Observer o) { + synchronized(unpackedListeners) { + unpackedListeners.addObserver(o); + } + } + void unpacked() { + synchronized(unpackedListeners) { + System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); + unpackedListeners.event(); + } + } + + /** * Object update mode */ @@ -298,10 +339,12 @@ public abstract class UAVObject { UAVObjectField field = li.next(); numBytes += field.unpack(dataIn); } + + // Trigger all the listeners for the unpack event + unpacked(); + updated(); + return numBytes; - // TODO: Callbacks - // emit objectUnpacked(this); // trigger object updated event - // emit objectUpdated(this); } // /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 0b72c33c8..21444a04b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -91,8 +91,7 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public int pack(ByteBuffer dataOut) { - //QMutexLocker locker(obj->getMutex()); + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -153,7 +152,7 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -240,10 +239,9 @@ public class UAVObjectField { return getNumBytes(); } - Object getValue() { return getValue(0); }; + public Object getValue() { return getValue(0); }; @SuppressWarnings("unchecked") - Object getValue(int index) { -// QMutexLocker locker(obj->getMutex()); + public synchronized Object getValue(int index) { // Check that index is not out of bounds if ( index >= numElements ) { @@ -287,8 +285,7 @@ public class UAVObjectField { public void setValue(Object data) { setValue(data,0); } @SuppressWarnings("unchecked") - public void setValue(Object data, int index) { - // QMutexLocker locker(obj->getMutex()); + public synchronized void setValue(Object data, int index) { // Check that index is not out of bounds //if ( index >= numElements ); //throw new Exception("Index out of bounds"); @@ -361,6 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } + obj.updated(); } } @@ -449,7 +447,7 @@ public class UAVObjectField { } @SuppressWarnings("unchecked") - public void clear() { + public synchronized void clear() { switch (type) { case INT8: @@ -503,7 +501,7 @@ public class UAVObjectField { } } - public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + public synchronized void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { // Copy params this.name = name; this.units = units; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 2e531fc85..74ddb95fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -23,7 +23,7 @@ public class UAVObjectManager { * updates. * @throws Exception */ - public boolean registerObject(UAVDataObject obj) throws Exception + public synchronized boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -128,7 +128,7 @@ public class UAVObjectManager { return true; } - public void addObject(UAVObject obj) + public synchronized void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -143,15 +143,15 @@ public class UAVObjectManager { */ public List> getObjects() { - //QMutexLocker locker(mutex); return objects; } /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public List< List > getDataObjects() { + assert(false); // TOOD This return new ArrayList>(); /* QMutexLocker locker(mutex); @@ -190,6 +190,7 @@ public class UAVObjectManager { */ public List > getMetaObjects() { + assert(false); // TODO return new ArrayList< List >(); /* QMutexLocker locker(mutex); @@ -267,7 +268,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - public UAVObject getObject(String name, int objId, int instId) + public synchronized UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -310,9 +311,8 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - public List getObjectInstances(String name, int objId) + public synchronized List getObjectInstances(String name, int objId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 07b061bc9..7ea9c7c60 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -10,6 +10,22 @@ import java.nio.ByteOrder; public class UAVTalk { + private Thread inputProcessingThread = null; + /** + * A reference to the thread for processing the incoming stream + * @return + */ + public Thread getInputProcessThread() { + if(inputProcessingThread == null) + + inputProcessingThread = new Thread() { + public void run() { + processInputStream(); + } + }; + return inputProcessingThread; + } + /** * Constants */ @@ -684,7 +700,7 @@ public class UAVTalk { * \param[in] type Transaction type * \return Success (true), Failure (false) */ - public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; int dataOffset; diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 6dc23530e..252927122 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -9,6 +9,8 @@ import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; import org.junit.BeforeClass; import org.junit.Test; @@ -20,8 +22,9 @@ public class TalkTest { static UAVObjectManager objMngr; static final String IP_ADDRDESS = new String("127.0.0.1"); - static final int PORT_NUM = 8000; - + static final int PORT_NUM = 7777; + boolean succeed = false; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -29,7 +32,7 @@ public class TalkTest { } @Test - public void testProcessInputStream() { + public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; try{ @@ -48,7 +51,29 @@ public class TalkTest { fail("Couldn't construct UAVTalk object"); } - talk.processInputStream(); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + succeed = false; + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + + obj.addUpdatedObserver( new Observer() { + public void update(Observable observable, Object data) { + // TODO Auto-generated method stub + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + try { + Thread.sleep(1000); + } catch (InterruptedException e1) { + } + + if(!succeed) + fail("Never received a FlightTelemetryStats update"); + } @Test From b81450a4aa8a22e1d357c4182d27f805968ffb2e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:56:14 -0600 Subject: [PATCH 058/165] Test case for the callbacks --- .../org/openpilot/uavtalk/DataObjectTest.java | 95 +++++++++++++++++++ 1 file changed, 95 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java new file mode 100644 index 000000000..0f8106cc5 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java @@ -0,0 +1,95 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.ActuatorCommand; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.database.Observable; + +public class DataObjectTest { + + boolean succeed = false; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testUpdatedObserver() { + + succeed = false; + + UAVObject obj = new ActuatorCommand(); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + obj.updated(); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + @Test + public void testUpdatedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + objMngr.getObject("FlightTelemetryStats").updated(); + + if(!succeed) + fail("No callback"); + System.out.println("Done"); + + } + + @Test + public void testUnpackedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUnpackedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + ByteBuffer bbuf = ByteBuffer.allocate(obj.getNumBytes()); + objMngr.getObject("FlightTelemetryStats").unpack(bbuf); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + +} From 157e5619273a2681284322b16c3025e4135245ac Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:26:50 -0600 Subject: [PATCH 059/165] Add isMetadata() instead of testing whether dynamic cast fails --- androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java | 1 + androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 5 +++++ androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 1 + 3 files changed, 7 insertions(+) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index de04f81c5..5694cc9d8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,6 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } + public boolean isMetadata() { return true; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 98e4bd626..7aab176ef 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -66,6 +66,11 @@ public class UAVMetaObject extends UAVObject { // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); } + + @Override + public boolean isMetadata() { + return true; + }; /** * Get the parent object diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6ede86094..6d35df822 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -46,6 +46,7 @@ public abstract class UAVObject { } } + public abstract boolean isMetadata(); /** * Object update mode From 943dd82a7587b26aa391dd869f92a0ec1e4f835c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:27:21 -0600 Subject: [PATCH 060/165] Initial start of the telemetry system which interfaces between UAVTalk and the ObjectManager/Objects --- .../src/org/openpilot/uavtalk/Telemetry.java | 25 ++ .../openpilot/uavtalk/TelemetryManager.java | 5 + .../openpilot/uavtalk/TelemetryMonitor.java | 263 ++++++++++++++++++ 3 files changed, 293 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/Telemetry.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java new file mode 100644 index 000000000..88bc33de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -0,0 +1,25 @@ +package org.openpilot.uavtalk; + +public class Telemetry { + + private TelemetryStats stats; + public class TelemetryStats { + public int txBytes; + public int rxBytes; + public int txObjectBytes; + public int rxObjectBytes; + public int rxObjects; + public int txObjects; + public int txErrors; + public int rxErrors; + public int txRetries; + } ; + + public TelemetryStats getStats() { + return stats; + } + + public void resetStats() { + stats = new TelemetryStats(); + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java new file mode 100644 index 000000000..7540a1423 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java @@ -0,0 +1,5 @@ +package org.openpilot.uavtalk; + +public class TelemetryManager { + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java new file mode 100644 index 000000000..40fc220cc --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -0,0 +1,263 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; +import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; + +import android.util.Log; + +public class TelemetryMonitor { + + private static final String TAG = "TelemetryMonitor"; + + static final int STATS_UPDATE_PERIOD_MS = 4000; + static final int STATS_CONNECT_PERIOD_MS = 1000; + static final int CONNECTION_TIMEOUT_MS = 8000; + + private UAVObjectManager objMngr; + private Telemetry tel; + private UAVObject objPending; + private UAVObject gcsStatsObj; + private UAVObject flightStatsObj; + private Timer periodicTask; + private int currentPeriod; + private List queue; + + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) + { + this.objMngr = objMngr; + this.tel = tel; + this.objPending = null; + queue = new ArrayList(); + + // Get stats objects + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + flightStatsObj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + flightStatsUpdated((UAVObject) data); + } + }); + + // Start update timer + setPeriod(STATS_CONNECT_PERIOD_MS); + } + + /** + * Initiate object retrieval, initialize queue with objects to be retrieved. + */ + public void startRetrievingObjects() + { + // Clear object queue + queue.clear(); + // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue + List< List > objs = objMngr.getObjects(); + + ListIterator> objListIterator = objs.listIterator(); + while( objListIterator.hasNext() ) + { + List instList = objListIterator.next(); + UAVObject obj = instList.get(0); + UAVObject.Metadata mdata = obj.getMetadata(); + if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + if ( obj.isMetadata() ) + { + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } + } + } + } + // Start retrieving + Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + retrieveNextObject(); + } + + /** + * Cancel the object retrieval + */ + public void stopRetrievingObjects() + { + //qxtLog->debug("Object retrieval has been cancelled"); + queue.clear(); + } + + /** + * Retrieve the next object in the queue + */ + public void retrieveNextObject() + { + // If queue is empty return + if ( queue.isEmpty() ) + { + //qxtLog->debug("Object retrieval completed"); + //emit connected(); + return; + } + // Get next object from the queue + UAVObject obj = queue.remove(0); + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; + // Connect to object + //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + // Request update + obj.requestUpdate(); + objPending = obj; + } + + /** + * Called by the retrieved object when a transaction is completed. + */ + public void transactionCompleted(UAVObject obj, boolean success) + { + //QMutexLocker locker(mutex); + // Disconnect from sending object + //obj->disconnect(this); + objPending = null; + + // Process next object if telemetry is still available + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + retrieveNextObject(); + } + else + { + stopRetrievingObjects(); + } + } + + /** + * Called each time the flight stats object is updated by the autopilot + */ + public synchronized void flightStatsUpdated(UAVObject obj) + { + // Force update if not yet connected + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + processStatsUpdates(); + } + } + + /** + * Called periodically to update the statistics and connection status. + */ + public synchronized void processStatsUpdates() + { + // Get telemetry stats + Telemetry.TelemetryStats telStats = tel.getStats(); + tel.resetStats(); + + // Update stats object + gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); + gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); + UAVObjectField field = gcsStatsObj.getField("RxFailures"); + field.setDouble(field.getDouble() + telStats.rxErrors); + field = gcsStatsObj.getField("TxFailures"); + field.setDouble(field.getDouble() + telStats.txErrors); + field = gcsStatsObj.getField("TxRetries"); + field.setDouble(field.getDouble() + telStats.txRetries); + + // Check for a connection timeout + boolean connectionTimeout; + if ( telStats.rxObjects > 0 ) + { + //connectionTimer.start(); + } + if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + { + connectionTimeout = true; + } + else + { + connectionTimeout = false; + } + + // Update connection state + int oldStatus = gcsStats.Status; + if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + { + // Request connection + gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + { + // Check for connection acknowledge + if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + { + gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + } + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + { + // Check if the connection is still active and the the autopilot is still connected + if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + { + gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + } + } + + // Set data + gcsStatsObj->setData(gcsStats); + + // Force telemetry update if not yet connected + if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || + flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + { + gcsStatsObj->updated(); + } + + // Act on new connections or disconnections + if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_UPDATE_PERIOD_MS); + statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot established"); + startRetrievingObjects(); + } + if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_CONNECT_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot lost"); + Log.d(TAG,"Trying to connect to the autopilot"); + emit disconnected(); + } + } + + private void setPeriod(int ms) { + if(periodicTask == null) + periodicTask = new Timer(); + + periodicTask.cancel(); + currentPeriod = ms; + periodicTask.scheduleAtFixedRate(new TimerTask() { + @Override + public void run() { + processStatsUpdates(); + } + }, currentPeriod, currentPeriod); + } + +} From 63f750c51e05d4e0b1c9f06db3ff32c0d3fb16fb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 9 Mar 2011 02:44:25 -0600 Subject: [PATCH 061/165] A few more synchronized statements and deep cloning of objects --- .../src/org/openpilot/uavtalk/UAVObject.java | 30 ++-- .../org/openpilot/uavtalk/UAVObjectField.java | 13 +- .../openpilot/uavtalk/UAVObjectManager.java | 130 +++++++++--------- 3 files changed, 97 insertions(+), 76 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6d35df822..adfece03e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,6 +1,7 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; +import java.util.ArrayList; import java.util.List; import java.util.ListIterator; import java.util.Observer; @@ -128,8 +129,7 @@ public abstract class UAVObject { // this.mutex = new QMutex(QMutex::Recursive); }; - public void initialize(int instID) { - // QMutexLocker locker(mutex); + public synchronized void initialize(int instID) { this.instID = instID; } @@ -146,9 +146,8 @@ public abstract class UAVObject { * @throws Exception * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, + public synchronized void initializeFields(List fields, ByteBuffer data, int numBytes) { - // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; this.fields = fields; // Initialize fields @@ -267,15 +266,13 @@ public abstract class UAVObject { * Get the number of fields held by this object */ public int getNumFields() { - // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() { - // QMutexLocker locker(mutex); + public synchronized List getFields() { return fields; } @@ -286,7 +283,6 @@ public abstract class UAVObject { * @returns The field or NULL if not found */ public UAVObjectField getField(String name) { - // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); while (li.hasNext()) { @@ -307,8 +303,7 @@ public abstract class UAVObject { * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception { - // QMutexLocker locker(mutex); + public synchronized int pack(ByteBuffer dataOut) throws Exception { if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; @@ -329,7 +324,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; @@ -532,8 +527,17 @@ public abstract class UAVObject { /** * Java specific functions */ - public UAVObject clone() { - return (UAVObject) clone(); + public synchronized UAVObject clone() { + UAVObject newObj = clone(); + List newFields = new ArrayList(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField nf = li.next().clone(); + nf.initialize(newObj); + newFields.add(nf); + } + newObj.initializeFields(newFields, ByteBuffer.allocate(numBytes), numBytes); + return newObj; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 21444a04b..2fd7f7846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -617,6 +617,17 @@ public class UAVObjectField { return num; } + + @Override + public UAVObjectField clone() + { + UAVObjectField newField = new UAVObjectField(new String(name), new String(units), type, + new ArrayList(elementNames), + new ArrayList(options)); + newField.initialize(obj); + newField.data = data; + return newField; + } private String name; private String units; @@ -626,7 +637,7 @@ public class UAVObjectField { private int numElements; private int numBytesPerElement; private int offset; - private Object data; private UAVObject obj; + protected Object data; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 74ddb95fb..63f535eac 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -3,9 +3,29 @@ package org.openpilot.uavtalk; import java.util.ArrayList; import java.util.List; import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; public class UAVObjectManager { + public class CallbackListener extends Observable { + public void event (UAVObject obj) { + setChanged(); + notifyObservers(obj); + } + } + private CallbackListener newInstance = new CallbackListener(); + public void addNewInstanceObserver(Observer o) { + synchronized(newInstance) { + newInstance.addObserver(o); + } + } + private CallbackListener newObject = new CallbackListener(); + public void addNewObjectObserver(Observer o) { + synchronized(newObject) { + newObject.addObserver(o); + } + } private final int MAX_INSTANCES = 10; // Use array list to store objects since rarely added or deleted @@ -79,11 +99,12 @@ public class UAVObjectManager { UAVDataObject newObj = obj.clone(instID); newObj.initialize(mobj); instList.add(newObj); - // emit new instance signal + newInstance.event(newObj); } obj.initialize(mobj); //emit new instance signal instList.add(obj); + newInstance.event(obj); instIter = instList.listIterator(); while(instIter.hasNext()) { @@ -101,13 +122,13 @@ public class UAVObjectManager { UAVDataObject cobj = obj.clone(instId); cobj.initialize(mobj); instList.add(cobj); - // emit newInstance(cobj); + newInstance.event(cobj); } // Finally, initialize the actual object instance obj.initialize(mobj); // Add the actual object instance in the list instList.add(obj); - //emit newInstance(obj); + newInstance.event(obj); return true; } @@ -149,81 +170,67 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public synchronized List< List > getDataObjects() { - assert(false); // TOOD This - return new ArrayList>(); - - /* QMutexLocker locker(mutex); - QList< QList > dObjects; + List< List > dObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVDataObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVDataObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - dObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVDataObject) instIt.next()); } - }*/ + dObjects.add(newInstList); + } // Done + return dObjects; } /** * Same as getObjects() but will only return MetaObjects. */ - public List > getMetaObjects() + public synchronized List > getMetaObjects() { - assert(false); // TODO - return new ArrayList< List >(); - /* - QMutexLocker locker(mutex); - QList< QList > mObjects; + List< List > mObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVMetaObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - mObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(!instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVMetaObject) instIt.next()); } + mObjects.add(newInstList); } // Done return mObjects; - */ } @@ -270,7 +277,6 @@ public class UAVObjectManager { */ public synchronized UAVObject getObject(String name, int objId, int instId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { From 6bc97f1a3dedbba1e5c1d4e5bc28c6c2a21e3ca7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:05:36 -0600 Subject: [PATCH 062/165] Most of the work on Telemetry.java as well as lots of signals for various object events --- .../src/org/openpilot/uavtalk/Telemetry.java | 623 +++++++++++++++++- .../openpilot/uavtalk/TelemetryMonitor.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 51 +- .../openpilot/uavtalk/UAVObjectManager.java | 3 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 7 +- 5 files changed, 673 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 88bc33de5..79e821fe3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,8 +1,18 @@ package org.openpilot.uavtalk; +import java.util.LinkedList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Queue; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.UAVObject.Acked; + public class Telemetry { - private TelemetryStats stats; public class TelemetryStats { public int txBytes; public int rxBytes; @@ -15,11 +25,612 @@ public class Telemetry { public int txRetries; } ; - public TelemetryStats getStats() { - return stats; - } + class ObjectTimeInfo { + UAVObject obj; + int updatePeriodMs; /** Update period in ms or 0 if no periodic updates are needed */ + int timeToNextUpdateMs; /** Time delay to the next update */ + }; + + class ObjectQueueInfo { + UAVObject obj; + int event; + boolean allInstances; + }; + + class ObjectTransactionInfo { + UAVObject obj; + boolean allInstances; + boolean objRequest; + int retriesRemaining; + Acked acked; + } ; - public void resetStats() { - stats = new TelemetryStats(); + /** + * Events generated by objects. Not enum because used in mask. + */ + private static final int EV_UNPACKED = 0x01; /** Object data updated by unpacking */ + private static final int EV_UPDATED = 0x02; /** Object data updated by changing the data structure */ + private static final int EV_UPDATED_MANUAL = 0x04; /** Object update event manually generated */ + private static final int EV_UPDATE_REQ = 0x08; /** Request to update object data */ + + /** + * Constructor + */ + public Telemetry(UAVTalk utalk, UAVObjectManager objMngr) + { + this.utalk = utalk; + this.objMngr = objMngr; + + // Process all objects in the list + List< List > objs = objMngr.getObjects(); + ListIterator> li = objs.listIterator(); + while(li.hasNext()) + registerObject(li.next().get(0)); // we only need to register one instance per object type + + // Listen to new object creations + objMngr.addNewInstanceObserver(new Observer() { + public void update(Observable observable, Object data) { + newInstance((UAVObject) data); + } + }); + objMngr.addNewObjectObserver(new Observer() { + public void update(Observable observable, Object data) { + newObject((UAVObject) data); + } + }); + + // Listen to transaction completions + utalk.addObserver(new Observer() { + public void update(Observable observable, Object data) { + transactionCompleted((UAVObject) data); + } + }); + + // Get GCS stats object + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + + // Setup transaction timer + transPending = false; + transTimer = new Timer(); + transTimerTask = new TimerTask() { + @Override + public void run() { + transactionTimeout(); + } + }; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + + updateTimer = new Timer(); + updateTimerTask = new TimerTask() { + @Override + public void run() { + processPeriodicUpdates(); + } + }; + updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; } + + /** + * Register a new object for periodic updates (if enabled) + */ + private void registerObject(UAVObject obj) + { + // Setup object for periodic updates + addObject(obj); + + // Setup object for telemetry updates + updateObject(obj); + } + + /** + * Add an object in the list used for periodic updates + */ + private void addObject(UAVObject obj) + { + // Check if object type is already in the list + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if( n.obj.getObjID() == obj.getObjID() ) + { + // Object type (not instance!) is already in the list, do nothing + return; + } + } + + // If this point is reached, then the object type is new, let's add it + ObjectTimeInfo timeInfo = new ObjectTimeInfo(); + timeInfo.obj = obj; + timeInfo.timeToNextUpdateMs = 0; + timeInfo.updatePeriodMs = 0; + objList.add(timeInfo); + } + + /** + * Update the object's timers + */ + private void setUpdatePeriod(UAVObject obj, int periodMs) + { + // Find object type (not instance!) and update its period + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if ( n.obj.getObjID() == obj.getObjID() ) + { + n.updatePeriodMs = periodMs; + n.timeToNextUpdateMs = (int) (periodMs * (new java.util.Random()).nextDouble()); // avoid bunching of updates + } + } + } + + /** + * Connect to all instances of an object depending on the event mask specified + */ + private void connectToObjectInstances(UAVObject obj, int eventMask) + { + List objs = objMngr.getObjectInstances(obj.getObjID()); + ListIterator li = objs.listIterator(); + while(li.hasNext()) + { + obj = li.next(); + //TODO: Disconnect all + // obj.disconnect(this); + + // Connect only the selected events + if ( (eventMask&EV_UNPACKED) != 0) + { + obj.addUnpackedObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUnpacked( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED) != 0) + { + obj.addUpdatedAutoObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedAuto( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED_MANUAL) != 0) + { + obj.addUpdatedManualObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedManual( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATE_REQ) != 0) + { + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + updateRequested( (UAVObject) data); + } + }); + } + } + } + + /** + * Update an object based on its metadata properties + */ + private void updateObject(UAVObject obj) + { + // Get metadata + UAVObject.Metadata metadata = obj.getMetadata(); + + // Setup object depending on update mode + int eventMask; + if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + { + // Set update period + setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Disconnect from object + connectToObjectInstances(obj, 0); + } + } + + /** + * Called when a transaction is successfully completed (uavtalk event) + */ + private void transactionCompleted(UAVObject obj) + { + // Check if there is a pending transaction and the objects match + if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) + { + // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + // Complete transaction + transTimer.cancel(); + transPending = false; + // Send signal + obj.transactionCompleted(true); + // Process new object updates from queue + processObjectQueue(); + } else + { + // qDebug() << "Error: received a transaction completed when did not expect it."; + } + } + + /** + * Called when a transaction is not completed within the timeout period (timer event) + */ + private void transactionTimeout() + { +// qDebug() << "Telemetry: transaction timeout."; + transTimer.cancel(); + // Proceed only if there is a pending transaction + if ( transPending ) + { + // Check if more retries are pending + if (transInfo.retriesRemaining > 0) + { + --transInfo.retriesRemaining; + processObjectTransaction(); + ++txRetries; + } + else + { + // Terminate transaction + utalk.cancelTransaction(); + transPending = false; + // Send signal + transInfo.obj.transactionCompleted(false); + // Process new object updates from queue + processObjectQueue(); + ++txErrors; + } + } + } + + /** + * Start an object transaction with UAVTalk, all information is stored in transInfo + */ + private void processObjectTransaction() + { + if (transPending) + { + // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + // Initiate transaction + if (transInfo.objRequest) + { + utalk.sendObjectRequest(transInfo.obj, transInfo.allInstances); + } + else + { + utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + } + // Start timer if a response is expected + if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + { + transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + } + else + { + transTimer.cancel(); + transPending = false; + } + } else + { + // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + } + } + + /** + * Process the event received from an object + */ + private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + { + // Push event into queue +// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + ObjectQueueInfo objInfo = new ObjectQueueInfo(); + objInfo.obj = obj; + objInfo.event = event; + objInfo.allInstances = allInstances; + if (priority) + { + if ( objPriorityQueue.size() < MAX_QUEUE_SIZE ) + { + objPriorityQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + } + } + else + { + if ( objQueue.size() < MAX_QUEUE_SIZE ) + { + objQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + } + } + + // If there is no transaction in progress then process event + if (!transPending) + { + // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else + { + // qDebug() << "Transaction pending, DO NOT process object queue..."; + } + } + + /** + * Process events from the object queue + */ + private void processObjectQueue() + { + // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + + // Don nothing if a transaction is already in progress (should not happen) + if (transPending) + { +// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + return; + } + + // Get object information from queue (first the priority and then the regular queue) + ObjectQueueInfo objInfo; + if ( !objPriorityQueue.isEmpty() ) + { + objInfo = objPriorityQueue.remove(); + } + else if ( !objQueue.isEmpty() ) + { + objInfo = objQueue.remove(); + } + else + { + return; + } + + // Check if a connection has been established, only process GCSTelemetryStats updates + // (used to establish the connection) + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) + { + objQueue.clear(); + if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) + { + objInfo.obj.transactionCompleted(false); + return; + } + } + + // Setup transaction (skip if unpack event) + if ( objInfo.event != EV_UNPACKED ) + { + UAVObject.Metadata metadata = objInfo.obj.getMetadata(); + transInfo.obj = objInfo.obj; + transInfo.allInstances = objInfo.allInstances; + transInfo.retriesRemaining = MAX_RETRIES; + transInfo.acked = metadata.gcsTelemetryAcked; + if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) + { + transInfo.objRequest = false; + } + else if ( objInfo.event == EV_UPDATE_REQ ) + { + transInfo.objRequest = true; + } + // Start transaction + transPending = true; + processObjectTransaction(); + } else + { +// qDebug() << QString("Process object queue: this is an unpack event for %1").arg(objInfo.obj->getName()); + } + + // If this is a metaobject then make necessary telemetry updates + if (objInfo.obj.isMetadata()) + { + UAVMetaObject metaobj = (UAVMetaObject) objInfo.obj; + updateObject( metaobj.getParentObject() ); + } + + // The fact we received an unpacked event does not mean that + // we do not have additional objects still in the queue, + // so we have to reschedule queue processing to make sure they are not + // stuck: + if ( objInfo.event == EV_UNPACKED ) + processObjectQueue(); + + } + + /** + * Check is any objects are pending for periodic updates + * TODO: Clean-up + */ + private synchronized void processPeriodicUpdates() + { + // Stop timer + updateTimer.cancel(); + + // Iterate through each object and update its timer, if zero then transmit object. + // Also calculate smallest delay to next update (will be used for setting timeToNextUpdateMs) + int minDelay = MAX_UPDATE_PERIOD_MS; + ObjectTimeInfo objinfo; + int elapsedMs = 0; + long startTime; + int offset; + ListIterator li = objList.listIterator(); + while(li.hasNext()) + { + objinfo = li.next(); + // If object is configured for periodic updates + if (objinfo.updatePeriodMs > 0) + { + objinfo.timeToNextUpdateMs -= timeToNextUpdateMs; + // Check if time for the next update + if (objinfo.timeToNextUpdateMs <= 0) + { + // Reset timer + offset = (-objinfo.timeToNextUpdateMs) % objinfo.updatePeriodMs; + objinfo.timeToNextUpdateMs = objinfo.updatePeriodMs - offset; + // Send object + startTime = System.currentTimeMillis(); + processObjectUpdates(objinfo.obj, EV_UPDATED_MANUAL, true, false); + elapsedMs = (int) (System.currentTimeMillis() - startTime); + // Update timeToNextUpdateMs with the elapsed delay of sending the object; + timeToNextUpdateMs += elapsedMs; + } + // Update minimum delay + if (objinfo.timeToNextUpdateMs < minDelay) + { + minDelay = objinfo.timeToNextUpdateMs; + } + } + } + + // Check if delay for the next update is too short + if (minDelay < MIN_UPDATE_PERIOD_MS) + { + minDelay = MIN_UPDATE_PERIOD_MS; + } + + // Done + timeToNextUpdateMs = minDelay; + + // Restart timer + //updateTimer->start(timeToNextUpdateMs); + updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + } + + public TelemetryStats getStats() + { + // Get UAVTalk stats + UAVTalk.ComStats utalkStats = utalk.getStats(); + + // Update stats + TelemetryStats stats = new TelemetryStats(); + stats.txBytes = utalkStats.txBytes; + stats.rxBytes = utalkStats.rxBytes; + stats.txObjectBytes = utalkStats.txObjectBytes; + stats.rxObjectBytes = utalkStats.rxObjectBytes; + stats.rxObjects = utalkStats.rxObjects; + stats.txObjects = utalkStats.txObjects; + stats.txErrors = utalkStats.txErrors + txErrors; + stats.rxErrors = utalkStats.rxErrors; + stats.txRetries = txRetries; + + // Done + return stats; + } + + public synchronized void resetStats() + { + utalk.resetStats(); + txErrors = 0; + txRetries = 0; + } + + private synchronized void objectUpdatedAuto(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED, false, true); + } + + private synchronized void objectUpdatedManual(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED_MANUAL, false, true); + } + + private synchronized void objectUnpacked(UAVObject obj) + { + processObjectUpdates(obj, EV_UNPACKED, false, true); + } + + private synchronized void updateRequested(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATE_REQ, false, true); + } + + private void newObject(UAVObject obj) + { + registerObject(obj); + } + + private synchronized void newInstance(UAVObject obj) + { + registerObject(obj); + } + + /** + * Private variables + */ + private TelemetryStats stats; + private UAVObjectManager objMngr; + private UAVTalk utalk; + private UAVObject gcsStatsObj; + private List objList; + private Queue objQueue = new LinkedList(); + private Queue objPriorityQueue = new LinkedList(); + private ObjectTransactionInfo transInfo; + private boolean transPending; + + private Timer updateTimer; + private TimerTask updateTimerTask; + private Timer transTimer; + private TimerTask transTimerTask; + + private int timeToNextUpdateMs; + private int txErrors; + private int txRetries; + + /** + * Private constants + */ + private static final int REQ_TIMEOUT_MS = 250; + private static final int MAX_RETRIES = 2; + private static final int MAX_UPDATE_PERIOD_MS = 1000; + private static final int MIN_UPDATE_PERIOD_MS = 1; + private static final int MAX_QUEUE_SIZE = 20; + + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 40fc220cc..39d332457 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -123,7 +123,7 @@ public class TelemetryMonitor { // Connect to object //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); // Request update - obj.requestUpdate(); + tel.requestUpdate(obj); objPending = obj; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index adfece03e..9e4f69a39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -8,7 +8,7 @@ import java.util.Observer; import java.util.Observable; public abstract class UAVObject { - + public class CallbackListener extends Observable { private UAVObject parent; @@ -20,6 +20,31 @@ public abstract class UAVObject { setChanged(); notifyObservers(parent); } + public void event (Object data) { + setChanged(); + notifyObservers(data); + } + } + + public class TransactionResult { + public UAVObject obj; + public boolean success; + public TransactionResult(UAVObject obj, boolean success) { + this.obj = obj; + this.success = success; + } + } + + private CallbackListener transactionCompletedListeners = new CallbackListener(this); + public void addTransactionCompleted(Observer o) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.addObserver(o); + } + } + void transactionCompleted(boolean status) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.event(new TransactionResult(this,status)); + } } private CallbackListener updatedListeners = new CallbackListener(this); @@ -47,6 +72,30 @@ public abstract class UAVObject { } } + private CallbackListener updatedAutoListeners = new CallbackListener(this); + public void addUpdatedAutoObserver(Observer o) { + synchronized(updatedAutoListeners) { + updatedAutoListeners.addObserver(o); + } + } + void updatedAuto() { + synchronized(updatedAutoListeners) { + updatedAutoListeners.event(); + } + } + + private CallbackListener updatedManualListeners = new CallbackListener(this); + public void addUpdatedManualObserver(Observer o) { + synchronized(updatedManualListeners) { + updatedManualListeners.addObserver(o); + } + } + void updatedManual() { + synchronized(updatedManualListeners) { + updatedManualListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 63f535eac..3ec588879 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -102,7 +102,6 @@ public class UAVObjectManager { newInstance.event(newObj); } obj.initialize(mobj); - //emit new instance signal instList.add(obj); newInstance.event(obj); @@ -155,7 +154,7 @@ public class UAVObjectManager { List ls = new ArrayList(); ls.add(obj); objects.add(ls); - //emit newObject(obj); + newObject.event(obj); } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 7ea9c7c60..847b7c425 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -7,8 +7,9 @@ import java.io.InputStream; import java.io.OutputStream; import java.nio.ByteBuffer; import java.nio.ByteOrder; +import java.util.Observable; -public class UAVTalk { +public class UAVTalk extends Observable{ private Thread inputProcessingThread = null; /** @@ -632,8 +633,8 @@ public class UAVTalk { if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; - // TODO: Signals -// emit transactionCompleted(obj); + setChanged(); + notifyObservers(obj); } } From b10c3f623d5312948ac306bc3f5b2de8b24a3a45 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:39:33 -0600 Subject: [PATCH 063/165] Changes to TelemetryMonitor, ready for testing --- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 54 +++++++++++-------- 2 files changed, 32 insertions(+), 24 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 79e821fe3..4bed72fea 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -585,7 +585,7 @@ public class Telemetry { processObjectUpdates(obj, EV_UNPACKED, false, true); } - private synchronized void updateRequested(UAVObject obj) + public synchronized void updateRequested(UAVObject obj) { processObjectUpdates(obj, EV_UPDATE_REQ, false, true); } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 39d332457..dabbf1d4b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -28,6 +28,7 @@ public class TelemetryMonitor { private UAVObject flightStatsObj; private Timer periodicTask; private int currentPeriod; + private long lastUpdateTime; private List queue; public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) @@ -121,9 +122,15 @@ public class TelemetryMonitor { Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object - //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + obj.addTransactionCompleted(new Observer() { + public void update(Observable observable, Object data) { + UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + transactionCompleted(result.obj, result.success); + } + }); + // Request update - tel.requestUpdate(obj); + tel.updateRequested(obj); objPending = obj; } @@ -184,9 +191,10 @@ public class TelemetryMonitor { boolean connectionTimeout; if ( telStats.rxObjects > 0 ) { - //connectionTimer.start(); + lastUpdateTime = System.currentTimeMillis(); + } - if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + if ( (System.currentTimeMillis() - lastUpdateTime) > CONNECTION_TIMEOUT_MS ) { connectionTimeout = true; } @@ -196,53 +204,53 @@ public class TelemetryMonitor { } // Update connection state - int oldStatus = gcsStats.Status; - if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + UAVObjectField statusField = gcsStatsObj.getField("Connection"); + String oldStatus = (String) statusField.getValue(); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection - gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + statusField.setValue("HandshakeReq"); } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + else if ( oldStatus.compareTo("HandshakeReq") == 0 ) { // Check for connection acknowledge - if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { - gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + statusField.setValue("Connected"); } } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + else if ( oldStatus.compareTo("Connected") == 0 ) { // Check if the connection is still active and the the autopilot is still connected - if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") == 0 || connectionTimeout) { - gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + statusField.setValue("Disconnected"); } } - // Set data - gcsStatsObj->setData(gcsStats); - // Force telemetry update if not yet connected - if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || - flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; + boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + if ( gcsStatusChanged || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { - gcsStatsObj->updated(); + gcsStatsObj.updated(); } // Act on new connections or disconnections - if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } - if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); Log.d(TAG,"Connection with the autopilot lost"); Log.d(TAG,"Trying to connect to the autopilot"); - emit disconnected(); + //emit disconnected(); } } From f80424875e58106f9e54a6d17ecdf96e7e559fad Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:27 -0600 Subject: [PATCH 064/165] Fixed bug in object signals that stopped updates sending. Various tweaks. --- .../src/org/openpilot/uavtalk/Telemetry.java | 33 ++++++++++------- .../openpilot/uavtalk/TelemetryMonitor.java | 35 +++++++++++++++---- .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 8 +++-- .../org/openpilot/uavtalk/UAVObjectField.java | 4 +-- .../src/org/openpilot/uavtalk/UAVTalk.java | 15 +++++--- 6 files changed, 68 insertions(+), 29 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 4bed72fea..d2f82459b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,5 +1,6 @@ package org.openpilot.uavtalk; +import java.util.ArrayList; import java.util.LinkedList; import java.util.List; import java.util.ListIterator; @@ -91,6 +92,15 @@ public class Telemetry { // Setup transaction timer transPending = false; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + updateTimerSetPeriod(1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; + } + + synchronized void transTimerSetPeriod(int periodMs) { transTimer = new Timer(); transTimerTask = new TimerTask() { @Override @@ -98,9 +108,10 @@ public class Telemetry { transactionTimeout(); } }; - // Setup and start the periodic timer - timeToNextUpdateMs = 0; - + transTimer.schedule(transTimerTask, periodMs, periodMs); + } + + synchronized void updateTimerSetPeriod(int periodMs) { updateTimer = new Timer(); updateTimerTask = new TimerTask() { @Override @@ -108,10 +119,8 @@ public class Telemetry { processPeriodicUpdates(); } }; - updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); - // Setup and start the stats timer - txErrors = 0; - txRetries = 0; + updateTimer.schedule(updateTimerTask, periodMs, periodMs); + } /** @@ -341,7 +350,7 @@ public class Telemetry { // Start timer if a response is expected if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) { - transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + transTimerSetPeriod(REQ_TIMEOUT_MS); } else { @@ -433,6 +442,7 @@ public class Telemetry { // Check if a connection has been established, only process GCSTelemetryStats updates // (used to establish the connection) + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) { objQueue.clear(); @@ -538,8 +548,7 @@ public class Telemetry { timeToNextUpdateMs = minDelay; // Restart timer - //updateTimer->start(timeToNextUpdateMs); - updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + updateTimerSetPeriod(timeToNextUpdateMs); } public TelemetryStats getStats() @@ -607,10 +616,10 @@ public class Telemetry { private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; - private List objList; + private List objList = new ArrayList(); private Queue objQueue = new LinkedList(); private Queue objPriorityQueue = new LinkedList(); - private ObjectTransactionInfo transInfo; + private ObjectTransactionInfo transInfo = new ObjectTransactionInfo(); private boolean transPending; private Timer updateTimer; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index dabbf1d4b..bc0bfd6eb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -92,7 +92,7 @@ public class TelemetryMonitor { } } // Start retrieving - Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + System.out.println(TAG + "Starting to retrieve meta and settings objects from the autopilot (" + queue.size() + " objects)"); retrieveNextObject(); } @@ -120,7 +120,7 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); - Log.d(TAG, "Retrieving object: " + obj.getName()) ; +// Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -161,6 +161,10 @@ public class TelemetryMonitor { public synchronized void flightStatsUpdated(UAVObject obj) { // Force update if not yet connected + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -204,8 +208,17 @@ public class TelemetryMonitor { } // Update connection state - UAVObjectField statusField = gcsStatsObj.getField("Connection"); + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + if(gcsStatsObj == null) { + System.out.println("No GCS stats yet"); + return; + } + UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = (String) statusField.getValue(); + + System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection @@ -217,6 +230,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); + System.out.println("Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -230,11 +244,18 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + + if(gcsStatusChanged) + System.out.println("GCS Status changed"); boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + + if(gcsConnected) + System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { + System.out.println("Sending gcs status\n\n\n"); gcsStatsObj.updated(); } @@ -242,14 +263,15 @@ public class TelemetryMonitor { if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot established"); + System.out.println(TAG + " Connection with the autopilot established"); + //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot lost"); - Log.d(TAG,"Trying to connect to the autopilot"); + System.out.println(TAG + " Connection with the autopilot lost"); + //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } @@ -260,6 +282,7 @@ public class TelemetryMonitor { periodicTask.cancel(); currentPeriod = ms; + periodicTask = new Timer(); periodicTask.scheduleAtFixedRate(new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 5694cc9d8..0acc02226 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,7 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } - public boolean isMetadata() { return true; }; + public boolean isMetadata() { return false; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 9e4f69a39..fac67cabc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -53,11 +53,14 @@ public abstract class UAVObject { updatedListeners.addObserver(o); } } - void updated() { + void updated(boolean manually) { synchronized(updatedListeners) { updatedListeners.event(); } + if(manually) + updatedManual(); } + void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { @@ -67,7 +70,6 @@ public abstract class UAVObject { } void unpacked() { synchronized(unpackedListeners) { - System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); unpackedListeners.event(); } } @@ -387,7 +389,7 @@ public abstract class UAVObject { // Trigger all the listeners for the unpack event unpacked(); - updated(); + updated(false); return numBytes; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 2fd7f7846..8d792bb39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -131,7 +131,7 @@ public class UAVObjectField { case UINT32: // TODO: Deal properly with unsigned for (int index = 0; index < numElements; ++index) { - Integer val = (Integer) getValue(index); + Integer val = (int) ( ((Long) getValue(index)).longValue() & 0xffffffffL); dataOut.putInt(val); } break; @@ -364,7 +364,7 @@ public class UAVObjectField { public double getDouble() { return getDouble(0); }; public double getDouble(int index) { - return Double.valueOf((Double) getValue(index)); + return ((Number) getValue(index)).doubleValue(); } public void setDouble(double value) { setDouble(value, 0); }; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 847b7c425..8576be78c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -200,9 +200,9 @@ public class UAVTalk extends Observable{ * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - //QMutexLocker locker(mutex); + System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -216,9 +216,8 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public void cancelTransaction() + public synchronized void cancelTransaction() { - //QMutexLocker locker(mutex); respObj = null; } @@ -250,6 +249,7 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { + System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -763,7 +763,12 @@ public class UAVTalk extends Observable{ bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); try { - outStream.write(bbuf.array()); + int packlen = bbuf.position(); + bbuf.position(0); + byte [] dst = new byte[packlen]; + bbuf.get(dst,0,packlen); + System.out.println("Outputting: " + dst.length); + outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); From abc07fd7484d58a4abf79c370493962305a183fb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:59 -0600 Subject: [PATCH 065/165] Unit test for telemetry --- .../uavtalk/TelemetryMonitorTest.java | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java new file mode 100644 index 000000000..1fc02d145 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java @@ -0,0 +1,64 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TelemetryMonitorTest { + + static UAVObjectManager objMngr; + static UAVTalk talk; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 7777; + static Socket connection = null; + boolean succeed = false; + + @Test + public void testTelemetry() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(talk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + Thread.sleep(10000); + + System.out.println("Done"); + } + + +} From 29fd09b204c5d95a95da2c3293327c75f7b0275e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 13:44:40 -0600 Subject: [PATCH 066/165] Little updates --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 56 ++++++++++++++----- 2 files changed, 51 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8576be78c..92b5585de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -202,7 +202,6 @@ public class UAVTalk extends Observable{ */ public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -249,7 +248,6 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { - System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -263,7 +261,7 @@ public class UAVTalk extends Observable{ * \param[in] rxbyte Received byte * \return Success (true), Failure (false) */ - public boolean processInputByte(int rxbyte) + public synchronized boolean processInputByte(int rxbyte) { assert(objMngr != null); @@ -448,12 +446,10 @@ public class UAVTalk extends Observable{ break; } - //mutex->lock(); rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; stats.rxObjects++; - //mutex->unlock(); rxState = RxStateType.STATE_SYNC; break; @@ -484,13 +480,13 @@ public class UAVTalk extends Observable{ boolean error = false; boolean allInstances = (instId == ALL_INSTANCES? true : false); - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages if (!allInstances) { + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -512,6 +508,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { + System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -531,6 +528,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object + System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -553,6 +551,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { + System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -578,7 +577,7 @@ public class UAVTalk extends Observable{ * If the object instance could not be found in the list, then a * new one is created. */ - public UAVObject updateObject(int objId, int instId, ByteBuffer data) + public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) { assert(objMngr != null); @@ -613,13 +612,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } + System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 252927122..044ddfd06 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -1,10 +1,13 @@ package org.openpilot.uavtalk; import static org.junit.Assert.*; +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.InputStreamReader; import java.io.OutputStream; +import java.io.OutputStreamWriter; import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; @@ -31,7 +34,7 @@ public class TalkTest { UAVObjectsInitialize.register(objMngr); } - @Test + //@Test public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; @@ -78,22 +81,49 @@ public class TalkTest { @Test public void testSendObjectRequest() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + + talk.sendObject(obj, false, false); + + System.out.println("Size: " + os.size()); + byte [] array = os.toByteArray(); + for(int i = 0; i < array.length; i++) { + System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + if(i != array.length-1) + System.out.print(", "); + } + System.out.print("\n"); } - - @Test - public void testSendObject() { - fail("Not yet implemented"); - } - + @Test public void testReceiveObject() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + // Send object to create the test packet (should hard code in test string) + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + talk.sendObject(obj, false, false); + + obj.getField("Status").setValue("Disconnected"); + + // Test receiving from that stream + is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); + talk = new UAVTalk(is,os,objMngr); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + System.out.println("Should be FlightTelemetry Stats:"); + System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); + + fail("Not working yet"); } - @Test - public void testUpdateObject() { - fail("Not yet implemented"); - } } From 1ea90c415879a2ea123af97d0d14b7137aa5a243 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 14:36:37 -0600 Subject: [PATCH 067/165] Fix the CRC calculation for java sending --- .../src/org/openpilot/uavtalk/UAVTalk.java | 13 ++++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 34 ++++++++++++------- 2 files changed, 31 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 92b5585de..d656aa707 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -175,7 +175,12 @@ public class UAVTalk extends Observable{ e.printStackTrace(); break; } - //System.out.println("Received byte " + val + " in state + " + rxState); + if(val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + break; + } + + System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -760,7 +765,7 @@ public class UAVTalk extends Observable{ } // Calculate checksum - bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + bbuf.put((byte) (updateCRC(0, bbuf.array(), bbuf.position()) & 0xff)); try { int packlen = bbuf.position(); @@ -818,9 +823,9 @@ public class UAVTalk extends Observable{ { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data) + int updateCRC(int crc, byte [] data, int length) { - for (int i = 0; i < data.length; i++) + for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); return crc; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 044ddfd06..91f3aa198 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -28,6 +28,16 @@ public class TalkTest { static final int PORT_NUM = 7777; boolean succeed = false; + byte[] flightStatsConnected = + {0x3c,0x20,0x1d,0x00, + (byte) 0x5e,(byte) 0x26,(byte) 0x0c,(byte) 0x66, + 0x03,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,(byte) 0xAE}; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -89,40 +99,40 @@ public class TalkTest { obj.getField("Status").setValue("Connected"); talk.sendObject(obj, false, false); - + System.out.println("Size: " + os.size()); byte [] array = os.toByteArray(); for(int i = 0; i < array.length; i++) { System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + System.out.print("/0x" + Integer.toHexString((int) flightStatsConnected[i] & 0xff)); if(i != array.length-1) - System.out.print(", "); + System.out.print("\n"); } System.out.print("\n"); + for(int i = 0; i < array.length; i++) + assertEquals(os.toByteArray()[i], flightStatsConnected[i]); } @Test - public void testReceiveObject() { - ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + public void testReceiveObject() throws InterruptedException { + ByteArrayInputStream is = new ByteArrayInputStream(flightStatsConnected, 0, flightStatsConnected.length); ByteArrayOutputStream os = new ByteArrayOutputStream(100); - // Send object to create the test packet (should hard code in test string) - UAVTalk talk = new UAVTalk(is,os,objMngr); + // Make the Status wrong initially UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.getField("Status").setValue("Connected"); - talk.sendObject(obj, false, false); - obj.getField("Status").setValue("Disconnected"); // Test receiving from that stream - is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); - talk = new UAVTalk(is,os,objMngr); + UAVTalk talk = new UAVTalk(is,os,objMngr); Thread inputStream = talk.getInputProcessThread(); inputStream.start(); + Thread.sleep(1000); + System.out.println("Should be FlightTelemetry Stats:"); System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); - fail("Not working yet"); + assertEquals(obj.getField("Status").getValue(), new String("Connected")); } From 20a4021bd32c4dc8f287a2624678ac931f752423 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 21:36:09 -0600 Subject: [PATCH 068/165] Fixed some timer issues. Got connection with this. --- .../src/org/openpilot/uavtalk/Telemetry.java | 9 ++++++++- .../org/openpilot/uavtalk/TelemetryMonitor.java | 3 --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++++++--------- 3 files changed, 15 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index d2f82459b..7f04e344b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -101,7 +101,14 @@ public class Telemetry { } synchronized void transTimerSetPeriod(int periodMs) { - transTimer = new Timer(); + if(transTimerTask != null) + transTimerTask.cancel(); + + if(transTimer != null) + transTimer.purge(); + + transTimer = new Timer(); + transTimerTask = new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index bc0bfd6eb..eb406923d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -164,7 +164,6 @@ public class TelemetryMonitor { gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -250,8 +249,6 @@ public class TelemetryMonitor { boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - if(gcsConnected) - System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index d656aa707..825f9d9fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -180,7 +180,7 @@ public class UAVTalk extends Observable{ break; } - System.out.println("Received byte " + val + " in state + " + rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -423,7 +423,6 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - //System.out.println(rxCount + "/" + rxLength); rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); if (rxCount < rxLength) break; @@ -491,7 +490,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ messages if (!allInstances) { - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + System.out.println("Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -513,7 +512,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -533,7 +532,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object - System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -556,7 +555,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -617,14 +616,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } - System.out.println("Unpacking new object"); +// System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); +// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } @@ -772,7 +771,6 @@ public class UAVTalk extends Observable{ bbuf.position(0); byte [] dst = new byte[packlen]; bbuf.get(dst,0,packlen); - System.out.println("Outputting: " + dst.length); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block From 34dfaf0023c41729ddfe2779eaa965e6b969763d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 13 Mar 2011 21:01:11 -0500 Subject: [PATCH 069/165] Works on Nook, but recursive loop too deep in registering objects --- androidgcs/AndroidManifest.xml | 12 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/main.xml | 1 - androidgcs/res/values/strings.xml | 1 - .../openpilot/androidgcs/ObjectBrowser.java | 129 ++++++++++++++++++ .../src/org/openpilot/uavtalk/Telemetry.java | 47 ++++--- .../openpilot/uavtalk/TelemetryMonitor.java | 15 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 +- 8 files changed, 186 insertions(+), 33 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 7a96a6600..8b3a9e4b3 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -5,8 +5,18 @@ android:versionName="1.0"> - + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 46769a720..66db0d159 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-7 +target=android-10 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 3a5f117d3..7e4a852bf 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -7,6 +7,5 @@ diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 0d9f93bc2..52fa56534 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,5 +1,4 @@ - Hello World! OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..3c6231258 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,129 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.Intent; +import android.os.Bundle; +import android.util.Log; + +import org.openpilot.androidgcs.*; +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjectBrowser extends Activity { + + private final String TAG = "ObjectBrower"; + private final String DEVICE_NAME = "RN42-222D"; + private final int REQUEST_ENABLE_BT = 0; + private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + BluetoothAdapter mBluetoothAdapter; + UAVObjectManager objMngr; + UAVTalk uavTalk; + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + + Log.d(TAG, "Launching Object Browser"); + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.d(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); + } else { + queryDevices(); + } + } + + @Override + public void onActivityResult(int requestCode, int resultCode, Intent data) { + if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { + Log.d(TAG, "Bluetooth started succesfully"); + queryDevices(); + } + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) + Log.d(TAG, "Bluetooth could not be started"); + + } + + public void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + openTelmetryBluetooth(device); + openTelmetryBluetooth(device); + } + } + } + + } + + private void openTelmetryBluetooth(BluetoothDevice device) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + BluetoothSocket socket = null; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return; + } + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + e.printStackTrace(); + return; + } + + Thread inputStream = uavTalk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(uavTalk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 7f04e344b..b403f85e3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -12,8 +12,12 @@ import java.util.TimerTask; import org.openpilot.uavtalk.UAVObject.Acked; +import android.util.Log; + public class Telemetry { + private final String TAG = "Telemetry"; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -133,7 +137,7 @@ public class Telemetry { /** * Register a new object for periodic updates (if enabled) */ - private void registerObject(UAVObject obj) + private synchronized void registerObject(UAVObject obj) { // Setup object for periodic updates addObject(obj); @@ -145,7 +149,7 @@ public class Telemetry { /** * Add an object in the list used for periodic updates */ - private void addObject(UAVObject obj) + private synchronized void addObject(UAVObject obj) { // Check if object type is already in the list ListIterator li = objList.listIterator(); @@ -169,7 +173,7 @@ public class Telemetry { /** * Update the object's timers */ - private void setUpdatePeriod(UAVObject obj, int periodMs) + private synchronized void setUpdatePeriod(UAVObject obj, int periodMs) { // Find object type (not instance!) and update its period ListIterator li = objList.listIterator(); @@ -186,7 +190,7 @@ public class Telemetry { /** * Connect to all instances of an object depending on the event mask specified */ - private void connectToObjectInstances(UAVObject obj, int eventMask) + private synchronized void connectToObjectInstances(UAVObject obj, int eventMask) { List objs = objMngr.getObjectInstances(obj.getObjID()); ListIterator li = objs.listIterator(); @@ -235,7 +239,7 @@ public class Telemetry { /** * Update an object based on its metadata properties */ - private void updateObject(UAVObject obj) + private synchronized void updateObject(UAVObject obj) { // Get metadata UAVObject.Metadata metadata = obj.getMetadata(); @@ -287,12 +291,12 @@ public class Telemetry { /** * Called when a transaction is successfully completed (uavtalk event) */ - private void transactionCompleted(UAVObject obj) + private synchronized void transactionCompleted(UAVObject obj) { // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -302,16 +306,16 @@ public class Telemetry { processObjectQueue(); } else { - // qDebug() << "Error: received a transaction completed when did not expect it."; + Log.e(TAG,"Error: received a transaction completed when did not expect it."); } } /** * Called when a transaction is not completed within the timeout period (timer event) */ - private void transactionTimeout() + private synchronized void transactionTimeout() { -// qDebug() << "Telemetry: transaction timeout."; + Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -340,11 +344,11 @@ public class Telemetry { /** * Start an object transaction with UAVTalk, all information is stored in transInfo */ - private void processObjectTransaction() + private synchronized void processObjectTransaction() { if (transPending) { - // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -366,17 +370,17 @@ public class Telemetry { } } else { - // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + Log.e(TAG,"Error: inside of processObjectTransaction with no transPending"); } } /** * Process the event received from an object */ - private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue -// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -391,7 +395,7 @@ public class Telemetry { { ++txErrors; obj.transactionCompleted(false); - //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + Log.w(TAG,"Telemetry: priority event queue is full, event lost " + obj.getName()); } } else @@ -410,25 +414,26 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else { - // qDebug() << "Transaction pending, DO NOT process object queue..."; + Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } /** * Process events from the object queue */ - private void processObjectQueue() + private synchronized void processObjectQueue() { - // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) { -// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + Log.e(TAG,"Dequeue while a transaction pending"); return; } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index eb406923d..e2050fc25 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -55,7 +55,7 @@ public class TelemetryMonitor { /** * Initiate object retrieval, initialize queue with objects to be retrieved. */ - public void startRetrievingObjects() + public synchronized void startRetrievingObjects() { // Clear object queue queue.clear(); @@ -108,7 +108,7 @@ public class TelemetryMonitor { /** * Retrieve the next object in the queue */ - public void retrieveNextObject() + public synchronized void retrieveNextObject() { // If queue is empty return if ( queue.isEmpty() ) @@ -120,7 +120,12 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); -// Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if(obj == null) { + Log.e(TAG, "Got null object forom transaction queue"); + return; + } + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -137,10 +142,12 @@ public class TelemetryMonitor { /** * Called by the retrieved object when a transaction is completed. */ - public void transactionCompleted(UAVObject obj, boolean success) + public synchronized void transactionCompleted(UAVObject obj, boolean success) { //QMutexLocker locker(mutex); // Disconnect from sending object + Log.d(TAG,"transactionCompleted"); + // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fac67cabc..b74df9218 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -17,12 +17,16 @@ public abstract class UAVObject { } public void event () { - setChanged(); - notifyObservers(parent); + synchronized(this) { + setChanged(); + notifyObservers(parent); + } } public void event (Object data) { - setChanged(); - notifyObservers(data); + synchronized(this) { + setChanged(); + notifyObservers(data); + } } } From 594978e2abd21764289b93e5a43de0f0510f686e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:18:45 -0500 Subject: [PATCH 070/165] Update display to show connected icon --- androidgcs/res/drawable-hdpi/icon.png | Bin 4147 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 1723 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 2574 -> 48558 bytes androidgcs/res/layout/main.xml | 2 + .../openpilot/androidgcs/ObjectBrowser.java | 92 +++++++++++++++--- 5 files changed, 83 insertions(+), 11 deletions(-) diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index 8074c4c571b8cd19e27f4ee5545df367420686d7..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index 1095584ec21f71cd0afc9e0993aa2209671b590c..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(h + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 3c6231258..a8c58d58d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,6 +1,8 @@ package org.openpilot.androidgcs; import java.io.IOException; +import java.util.Observable; +import java.util.Observer; import java.util.Set; import java.util.UUID; @@ -10,11 +12,15 @@ import android.bluetooth.BluetoothDevice; import android.bluetooth.BluetoothSocket; import android.content.Intent; import android.os.Bundle; +import android.os.Handler; import android.util.Log; +import android.widget.TextView; +import android.widget.ToggleButton; import org.openpilot.androidgcs.*; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -26,9 +32,35 @@ public class ObjectBrowser extends Activity { private final int REQUEST_ENABLE_BT = 0; private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); BluetoothAdapter mBluetoothAdapter; + BluetoothSocket socket; + boolean connected; UAVObjectManager objMngr; UAVTalk uavTalk; + final Handler uavobjHandler = new Handler(); + final Runnable updateText = new Runnable() { + public void run() { + ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); + button.setChecked(!connected); + + Log.d(TAG,"HERE" + connected); + + TextView text = (TextView) findViewById(R.id.textView1); + + UAVObject obj1 = objMngr.getObject("SystemStats"); + UAVObject obj2 = objMngr.getObject("AttitudeRaw"); + UAVObject obj3 = objMngr.getObject("AttitudeActual"); + UAVObject obj4 = objMngr.getObject("SystemAlarms"); + + if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) + return; + + Log.d(TAG,"And here"); + text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); + + } + }; + /** Called when the activity is first created. */ @Override public void onCreate(Bundle savedInstanceState) { @@ -36,11 +68,16 @@ public class ObjectBrowser extends Activity { setContentView(R.layout.main); Log.d(TAG, "Launching Object Browser"); + + connected = false; + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); if (mBluetoothAdapter == null) { // Device does not support Bluetooth - Log.d(TAG, "Device does not support Bluetooth"); + Log.e(TAG, "Device does not support Bluetooth"); return; } @@ -50,16 +87,49 @@ public class ObjectBrowser extends Activity { } else { queryDevices(); } + + + UAVObject obj = objMngr.getObject("SystemStats"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeRaw"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("SystemAlarms"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + + } @Override public void onActivityResult(int requestCode, int resultCode, Intent data) { if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - Log.d(TAG, "Bluetooth started succesfully"); + //Log.d(TAG, "Bluetooth started succesfully"); queryDevices(); } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) - Log.d(TAG, "Bluetooth could not be started"); + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { + //Log.d(TAG, "Bluetooth could not be started"); + } } @@ -84,12 +154,13 @@ public class ObjectBrowser extends Activity { private void openTelmetryBluetooth(BluetoothDevice device) { Log.d(TAG, "Opening conncetion to " + device.getName()); - BluetoothSocket socket = null; + socket = null; + connected = false; try { socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); } catch (IOException e) { Log.e(TAG,"Unable to create Rfcomm socket"); - e.printStackTrace(); + //e.printStackTrace(); } mBluetoothAdapter.cancelDiscovery(); @@ -102,20 +173,19 @@ public class ObjectBrowser extends Activity { try { socket.close(); } catch (IOException e2) { - Log.e(TAG, "unable to close() socket during connection failure", e2); + //Log.e(TAG, "unable to close() socket during connection failure", e2); } return; } - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - + connected = true; + try { uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); } catch (IOException e) { Log.e(TAG,"Error starting UAVTalk"); // TODO Auto-generated catch block - e.printStackTrace(); + //e.printStackTrace(); return; } From 8dc6b09b961d3a90f13aab07b7b2ccc6891e8a77 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:19:18 -0500 Subject: [PATCH 071/165] Make it easy to enable or disable logging in separate modules --- .../src/org/openpilot/uavtalk/Telemetry.java | 30 +- .../openpilot/uavtalk/TelemetryMonitor.java | 41 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 + .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 593 ++++++++---------- 5 files changed, 324 insertions(+), 354 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index b403f85e3..c754c8329 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,10 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -227,7 +230,7 @@ public class Telemetry { } if ( (eventMask&EV_UPDATE_REQ) != 0) { - obj.addUpdatedObserver(new Observer() { + obj.addUpdateRequestedObserver(new Observer() { public void update(Observable observable, Object data) { updateRequested( (UAVObject) data); } @@ -293,10 +296,11 @@ public class Telemetry { */ private synchronized void transactionCompleted(UAVObject obj) { + if (DEBUG) Log.d(TAG,"UAVTalk transactionCompleted"); // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); + if (DEBUG) Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -315,7 +319,7 @@ public class Telemetry { */ private synchronized void transactionTimeout() { - Log.d(TAG,"Telemetry: transaction timeout."); + if (DEBUG) Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -348,7 +352,7 @@ public class Telemetry { { if (transPending) { - Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); + if (DEBUG) Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -380,7 +384,9 @@ public class Telemetry { private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue - Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if (DEBUG) Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if(event == 8 && obj.getName().compareTo("GCSTelemetryStats") == 0) + Thread.dumpStack(); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -414,12 +420,7 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - processObjectQueue(); - - } else - { - Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } @@ -428,7 +429,7 @@ public class Telemetry { */ private synchronized void processObjectQueue() { - Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); + if (DEBUG) Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) @@ -460,6 +461,9 @@ public class Telemetry { objQueue.clear(); if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) { + if (DEBUG) Log.d(TAG,"transactionCompleted(false) due to receiving object not GCSTelemetryStats while not connected."); + System.out.println(gcsStatsObj.toString()); + System.out.println(objInfo.obj.toString()); objInfo.obj.transactionCompleted(false); return; } @@ -511,6 +515,8 @@ public class Telemetry { */ private synchronized void processPeriodicUpdates() { + + if (DEBUG) Log.d(TAG, "processPeriodicUpdates()"); // Stop timer updateTimer.cancel(); diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index e2050fc25..a5885e7bc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -57,6 +57,8 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { + Log.d(TAG, "Start retrieving objects"); + // Clear object queue queue.clear(); // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue @@ -101,7 +103,7 @@ public class TelemetryMonitor { */ public void stopRetrievingObjects() { - //qxtLog->debug("Object retrieval has been cancelled"); + Log.d(TAG, "Stop retrieving objects"); queue.clear(); } @@ -113,6 +115,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { + Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -121,8 +124,7 @@ public class TelemetryMonitor { UAVObject obj = queue.remove(0); if(obj == null) { - Log.e(TAG, "Got null object forom transaction queue"); - return; + throw new Error("Got null object forom transaction queue"); } Log.d(TAG, "Retrieving object: " + obj.getName()) ; @@ -130,6 +132,7 @@ public class TelemetryMonitor { obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -146,11 +149,16 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted"); + Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; + if(!success) { + Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); + return; + } + // Process next object if telemetry is still available if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -184,6 +192,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats + Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -221,9 +230,9 @@ public class TelemetryMonitor { return; } UAVObjectField statusField = gcsStatsObj.getField("Status"); - String oldStatus = (String) statusField.getValue(); + String oldStatus = new String((String) statusField.getValue()); - System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -236,7 +245,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - System.out.println("Connected" + statusField.toString()); + Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -251,31 +260,31 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) - System.out.println("GCS Status changed"); + if(gcsStatusChanged) { + Log.d(TAG,"GCS Status changed"); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; - if ( gcsStatusChanged || - ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) + if ( !gcsConnected || !flightConnected ) { - System.out.println("Sending gcs status\n\n\n"); + Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { + Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot established"); - //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { + Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot lost"); - //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index b74df9218..ba3bf1ae3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -102,6 +102,18 @@ public abstract class UAVObject { } } + private CallbackListener updateRequestedListeners = new CallbackListener(this); + public void addUpdateRequestedObserver(Observer o) { + synchronized(updateRequestedListeners) { + updateRequestedListeners.addObserver(o); + } + } + void updateRequested() { + synchronized(updateRequestedListeners) { + updateRequestedListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 8d792bb39..de2059e90 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -358,7 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } - obj.updated(); + //obj.updated(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 825f9d9fe..33daefab7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -9,49 +9,66 @@ import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.Observable; -public class UAVTalk extends Observable{ +import android.util.Log; + +public class UAVTalk extends Observable { + + static final String TAG = "UAVTalk"; + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; private Thread inputProcessingThread = null; + /** * A reference to the thread for processing the incoming stream + * * @return */ public Thread getInputProcessThread() { - if(inputProcessingThread == null) + if (inputProcessingThread == null) inputProcessingThread = new Thread() { - public void run() { - processInputStream(); - } - }; + public void run() { + processInputStream(); + } + }; return inputProcessingThread; } - + /** * Constants */ private static final int SYNC_VAL = 0x3C; - private static final short crc_table[] = { - 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, - 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, - 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, - 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, - 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, - 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, - 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, - 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, - 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, - 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, - 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, - 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, - 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, - 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, - 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, - 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 - }; + private static final short crc_table[] = { 0x00, 0x07, 0x0e, 0x09, 0x1c, + 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, + 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, + 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, 0x90, + 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, + 0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, + 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, + 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, + 0x94, 0x9d, 0x9a, 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, + 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, + 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, + 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, + 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, 0xf9, 0xfe, 0xf7, 0xf0, + 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, + 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, + 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10, 0x05, + 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, + 0x7f, 0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, + 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, + 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, + 0x8a, 0x8d, 0x84, 0x83, 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, + 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 }; - enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + enum RxStateType { + STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS + }; static final int TYPE_MASK = 0xFC; static final int TYPE_VER = 0x20; @@ -60,17 +77,21 @@ public class UAVTalk extends Observable{ static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); static final int TYPE_ACK = (TYPE_VER | 0x03); - static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) - static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), + // object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), + // object ID (4), instance ID(2, + // not used in single objects) static final int CHECKSUM_LENGTH = 1; static final int MAX_PAYLOAD_LENGTH = 256; - static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); static final int ALL_INSTANCES = 0xFFFF; - static final int TX_BUFFER_SIZE = 2*1024; + static final int TX_BUFFER_SIZE = 2 * 1024; /** * Private data @@ -93,12 +114,12 @@ public class UAVTalk extends Observable{ int rxCSPacket, rxCS; int rxCount; int packetSize; - RxStateType rxState; + RxStateType rxState; ComStats stats = new ComStats(); /** * Comm stats - */ + */ public class ComStats { public int txBytes = 0; public int rxBytes = 0; @@ -113,8 +134,8 @@ public class UAVTalk extends Observable{ /** * Constructor */ - public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) - { + public UAVTalk(InputStream inStream, OutputStream outStream, + UAVObjectManager objMngr) { this.objMngr = objMngr; this.inStream = inStream; this.outStream = outStream; @@ -122,7 +143,7 @@ public class UAVTalk extends Observable{ rxState = RxStateType.STATE_SYNC; rxPacketLength = 0; - //mutex = new QMutex(QMutex::Recursive); + // mutex = new QMutex(QMutex::Recursive); respObj = null; resetStats(); @@ -131,88 +152,80 @@ public class UAVTalk extends Observable{ rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); rxBuffer.order(ByteOrder.LITTLE_ENDIAN); - // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, + // SLOT(processInputStream())); } /** * Reset the statistics counters */ - public void resetStats() - { - //QMutexLocker locker(mutex); + public void resetStats() { + // QMutexLocker locker(mutex); stats = new ComStats(); } /** * Get the statistics counters */ - public ComStats getStats() - { - //QMutexLocker locker(mutex); + public ComStats getStats() { + // QMutexLocker locker(mutex); return stats; } /** * Called each time there are data in the input buffer */ - public void processInputStream() - { + public void processInputStream() { int val; - - while (true) - { + + while (true) { try { - //inStream.wait(); + // inStream.wait(); val = inStream.read(); - } /*catch (InterruptedException e) { - // TODO Auto-generated catch block - System.out.println("Connection was aborted\n"); - e.printStackTrace(); - break; - }*/ catch (IOException e) { + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { // TODO Auto-generated catch block System.out.println("Error reading from stream\n"); e.printStackTrace(); break; } - if(val == -1) { - System.out.println("End of stream, terminating processInputStream thread"); + if (val == -1) { + System.out + .println("End of stream, terminating processInputStream thread"); break; } - - //System.out.println("Received byte " + val + " in state + " + rxState); + + // System.out.println("Received byte " + val + " in state + " + + // rxState); processInputByte(val); } } /** - * Request an update for the specified object, on success the object data would have been - * updated by the GCS. - * \param[in] obj Object to update + * Request an update for the specified object, on success the object data + * would have been updated by the GCS. \param[in] obj Object to update * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObjectRequest(UAVObject obj, boolean allInstances) - { - //QMutexLocker locker(mutex); + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) { + // QMutexLocker locker(mutex); return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); } /** - * Send the specified object through the telemetry link. - * \param[in] obj Object to send - * \param[in] acked Selects if an ack is required - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Send the specified object through the telemetry link. \param[in] obj + * Object to send \param[in] acked Selects if an ack is required \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) - { - if (acked) - { + public synchronized boolean sendObject(UAVObject obj, boolean acked, + boolean allInstances) { + if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); - } - else - { + } else { return objectTransaction(obj, TYPE_OBJ, allInstances); } } @@ -220,64 +233,49 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public synchronized void cancelTransaction() - { + public synchronized void cancelTransaction() { respObj = null; } /** - * Execute the requested transaction on an object. - * \param[in] obj Object - * \param[in] type Transaction type - * TYPE_OBJ: send object, - * TYPE_OBJ_REQ: request object update - * TYPE_OBJ_ACK: send object with an ack - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Execute the requested transaction on an object. \param[in] obj Object + * \param[in] type Transaction type TYPE_OBJ: send object, TYPE_OBJ_REQ: + * request object update TYPE_OBJ_ACK: send object with an ack \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) - { + public boolean objectTransaction(UAVObject obj, int type, + boolean allInstances) { // Send object depending on if a response is needed - if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) - { - if ( transmitObject(obj, type, allInstances) ) - { + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) { + if (transmitObject(obj, type, allInstances)) { respObj = obj; - respAllInstances = allInstances; + respAllInstances = allInstances; return true; - } - else - { + } else { return false; } - } - else if (type == TYPE_OBJ) - { + } else if (type == TYPE_OBJ) { return transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { return false; } } /** - * Process an byte from the telemetry stream. - * \param[in] rxbyte Received byte - * \return Success (true), Failure (false) + * Process an byte from the telemetry stream. \param[in] rxbyte Received + * byte \return Success (true), Failure (false) */ - public synchronized boolean processInputByte(int rxbyte) - { - assert(objMngr != null); + public synchronized boolean processInputByte(int rxbyte) { + assert (objMngr != null); // Update stats stats.rxBytes++; - rxPacketLength++; // update packet byte count + rxPacketLength++; // update packet byte count // Receive state machine - switch (rxState) - { + switch (rxState) { case STATE_SYNC: if (rxbyte != SYNC_VAL) @@ -296,8 +294,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if ((rxbyte & TYPE_MASK) != TYPE_VER) - { + if ((rxbyte & TYPE_MASK) != TYPE_VER) { rxState = RxStateType.STATE_SYNC; break; } @@ -315,8 +312,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if (rxCount == 0) - { + if (rxCount == 0) { packetSize += rxbyte; rxCount++; break; @@ -324,10 +320,12 @@ public class UAVTalk extends Observable{ packetSize += (rxbyte << 8) & 0xff00; - if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) - { // incorrect packet size + if (packetSize < MIN_HEADER_LENGTH + || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) { // incorrect + // packet + // size rxState = RxStateType.STATE_SYNC; - break; + break; } rxCount = 0; @@ -348,8 +346,7 @@ public class UAVTalk extends Observable{ rxObjId = rxTmpBuffer.getInt(0); { UAVObject rxObj = objMngr.getObject(rxObjId); - if (rxObj == null) - { + if (rxObj == null) { stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -361,38 +358,38 @@ public class UAVTalk extends Observable{ else rxLength = rxObj.getNumBytes(); - // Check length and determine next state - if (rxLength >= MAX_PAYLOAD_LENGTH) - { - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check the lengths match - if ((rxPacketLength + rxLength) != packetSize) - { // packet error - mismatched packet size - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) { // packet error + // - + // mismatched + // packet + // size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check if this is a single instance object (i.e. if the instance ID field is coming next) - if (rxObj.isSingleInstance()) - { - // If there is a payload get it, otherwise receive checksum - if (rxLength > 0) - rxState = RxStateType.STATE_DATA; - else - rxState = RxStateType.STATE_CS; - rxInstId = 0; - rxCount = 0; - } + // Check if this is a single instance object (i.e. if the + // instance ID field is coming next) + if (rxObj.isSingleInstance()) { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; else - { - rxState = RxStateType.STATE_INSTID; - rxCount = 0; - } + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } else { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } } break; @@ -419,7 +416,7 @@ public class UAVTalk extends Observable{ break; case STATE_DATA: - + // Update CRC rxCS = updateCRC(rxCS, rxbyte); @@ -436,15 +433,15 @@ public class UAVTalk extends Observable{ // The CRC byte rxCSPacket = rxbyte; - if (rxCS != rxCSPacket) - { // packet error - faulty CRC + if (rxCS != rxCSPacket) { // packet error - faulty CRC stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } - if (rxPacketLength != (packetSize + 1)) - { // packet error - mismatched packet size + if (rxPacketLength != (packetSize + 1)) { // packet error - + // mismatched packet + // size stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -468,103 +465,84 @@ public class UAVTalk extends Observable{ } /** - * Receive an object. This function process objects received through the telemetry stream. - * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) - * \param[in] obj Handle of the received object - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] data Data buffer - * \param[in] length Buffer length - * \return Success (true), Failure (false) + * Receive an object. This function process objects received through the + * telemetry stream. \param[in] type Type of received message (TYPE_OBJ, + * TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) \param[in] obj Handle of the + * received object \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES + * for all instances. \param[in] data Data buffer \param[in] length Buffer + * length \return Success (true), Failure (false) */ - public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); - + public boolean receiveObject(int type, int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); + UAVObject obj = null; boolean error = false; - boolean allInstances = (instId == ALL_INSTANCES? true : false); + boolean allInstances = (instId == ALL_INSTANCES ? true : false); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages - if (!allInstances) - { - System.out.println("Received object: " + objMngr.getObject(objId).getName()); + if (!allInstances) { + if (DEBUG) Log.d(TAG,"Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending - if ( obj != null ) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages - if (!allInstances) - { -// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received object ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK - if ( obj != null ) - { + if (obj != null) { transmitObject(obj, TYPE_ACK, false); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_REQ: - // Get object, if all instances are requested get instance 0 of the object -// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); - if (allInstances) - { + // Get object, if all instances are requested get instance 0 of the + // object + // System.out.println("Received object request: " + objId + " " + + // objMngr.getObject(objId).getName()); + if (allInstances) { obj = objMngr.getObject(objId); - } - else - { + } else { obj = objMngr.getObject(objId, instId); } // If object was found transmit it - if (obj != null) - { + if (obj != null) { transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { error = true; } break; case TYPE_ACK: // All instances, not allowed for ACK messages - if (!allInstances) - { -// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending - if (obj != null) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } } @@ -577,23 +555,20 @@ public class UAVTalk extends Observable{ } /** - * Update the data of an object from a byte array (unpack). - * If the object instance could not be found in the list, then a - * new one is created. + * Update the data of an object from a byte array (unpack). If the object + * instance could not be found in the list, then a new one is created. */ - public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); + public synchronized UAVObject updateObject(int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); // Get object UAVObject obj = objMngr.getObject(objId, instId); // If the instance does not exist create it - if (obj == null) - { + if (obj == null) { // Get the object type UAVObject tobj = objMngr.getObject(objId); - if (tobj == null) - { + if (tobj == null) { return null; } // Make sure this is a data object @@ -604,26 +579,26 @@ public class UAVTalk extends Observable{ // Failed to cast to a data object return null; } - + // Create a new instance, unpack and register UAVDataObject instobj = dobj.clone(instId); try { - if ( !objMngr.registerObject(instobj) ) - { + if (!objMngr.registerObject(instobj)) { return null; } } catch (Exception e) { // TODO Auto-generated catch block e.printStackTrace(); } -// System.out.println("Unpacking new object"); + // System.out.println("Unpacking new object"); + if (DEBUG) Log.d(TAG, "Unpacking new object"); instobj.unpack(data); return instobj; - } - else - { + } else { // Unpack data into object instance -// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); + // System.out.println("Unpacking existing object: " + + // data.position() + " / " + data.capacity() ); + if (DEBUG) Log.d(TAG, "Unpacking existing object: " + obj.getName()); obj.unpack(data); return obj; } @@ -632,10 +607,9 @@ public class UAVTalk extends Observable{ /** * Check if a transaction is pending and if yes complete it. */ - public void updateAck(UAVObject obj) - { - if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) - { + synchronized void updateAck(UAVObject obj) { + if (respObj != null && respObj.getObjID() == obj.getObjID() + && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; setChanged(); notifyObservers(obj); @@ -643,111 +617,88 @@ public class UAVTalk extends Observable{ } /** - * Send an object through the telemetry link. - * \param[in] obj Object to send - * \param[in] type Transaction type - * \param[in] allInstances True is all instances of the object are to be sent - * \return Success (true), Failure (false) + * Send an object through the telemetry link. + * @param[in] obj Object to send + * @param[in] type Transaction type + * @param[in] allInstances True is all instances of the object are to be sent + * @return Success (true), Failure (false) */ - public boolean transmitObject(UAVObject obj, int type, boolean allInstances) - { - // If all instances are requested on a single instance object it is an error - if (allInstances && obj.isSingleInstance()) - { + public synchronized boolean transmitObject(UAVObject obj, int type, boolean allInstances) { + // If all instances are requested on a single instance object it is an + // error + if (allInstances && obj.isSingleInstance()) { allInstances = false; } // Process message type - if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) - { - if (allInstances) - { + if (type == TYPE_OBJ || type == TYPE_OBJ_ACK) { + if (allInstances) { // Get number of instances int numInst = objMngr.getNumInstances(obj.getObjID()); // Send all instances - for (int instId = 0; instId < numInst; ++instId) - { + for (int instId = 0; instId < numInst; ++instId) { UAVObject inst = objMngr.getObject(obj.getObjID(), instId); transmitSingleObject(inst, type, false); } return true; - } - else - { + } else { return transmitSingleObject(obj, type, false); } - } - else if (type == TYPE_OBJ_REQ) - { + } else if (type == TYPE_OBJ_REQ) { return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); - } - else if (type == TYPE_ACK) - { - if (!allInstances) - { + } else if (type == TYPE_ACK) { + if (!allInstances) { return transmitSingleObject(obj, TYPE_ACK, false); - } - else - { + } else { return false; } - } - else - { + } else { return false; } } - /** - * Send an object through the telemetry link. - * \param[in] obj Object handle to send - * \param[in] type Transaction type - * \return Success (true), Failure (false) + * Send an object through the telemetry link. \param[in] obj Object handle + * to send \param[in] type Transaction type \return Success (true), Failure + * (false) */ - public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) - { + public synchronized boolean transmitSingleObject(UAVObject obj, int type, + boolean allInstances) { int length; int dataOffset; int objId; int instId; int allInstId = ALL_INSTANCES; - - assert(objMngr != null && outStream != null); - + + assert (objMngr != null && outStream != null); + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); bbuf.order(ByteOrder.LITTLE_ENDIAN); // Determine data length - if (type == TYPE_OBJ_REQ || type == TYPE_ACK) - { + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) { length = 0; - } - else - { + } else { length = obj.getNumBytes(); } - + // Setup type and object id fields bbuf.put((byte) (SYNC_VAL & 0xff)); bbuf.put((byte) (type & 0xff)); - bbuf.putShort((short) (length + - 2 /* SYNC, Type */ + - 2 /* Size */ + - 4 /* ObjID */ + - (obj.isSingleInstance() ? 0 : 2) )); + bbuf + .putShort((short) (length + 2 /* SYNC, Type */+ 2 /* Size */+ 4 /* ObjID */+ (obj + .isSingleInstance() ? 0 : 2))); bbuf.putInt(obj.getObjID()); - + // Setup instance ID if one is required - if ( !obj.isSingleInstance() ) - { + if (!obj.isSingleInstance()) { // Check if all instances are requested if (allInstances) bbuf.putShort((short) (allInstId & 0xffff)); else bbuf.putShort((short) (obj.getInstID() & 0xffff)); } - + // Check length if (length >= MAX_PAYLOAD_LENGTH) return false; @@ -755,7 +706,7 @@ public class UAVTalk extends Observable{ // Copy data (if any) if (length > 0) try { - if ( obj.pack(bbuf) == 0) + if (obj.pack(bbuf) == 0) return false; } catch (Exception e) { // TODO Auto-generated catch block @@ -769,26 +720,28 @@ public class UAVTalk extends Observable{ try { int packlen = bbuf.position(); bbuf.position(0); - byte [] dst = new byte[packlen]; - bbuf.get(dst,0,packlen); + byte[] dst = new byte[packlen]; + bbuf.get(dst, 0, packlen); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); return false; } - -// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE -// // Send buffer, check that the transmit backlog does not grow above limit -// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) -// { -// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); -// } -// else -// { -// ++stats.txErrors; -// return false; -// } + + // //TODO: Need to use a different outStream type and check that the + // backlog isn't more than TX_BUFFER_SIZE + // // Send buffer, check that the transmit backlog does not grow above + // limit + // if ( io->bytesToWrite() < TX_BUFFER_SIZE ) + // { + // io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); + // } + // else + // { + // ++stats.txErrors; + // return false; + // } // Update stats ++stats.txObjects; @@ -801,33 +754,23 @@ public class UAVTalk extends Observable{ /** * Update the crc value with new data. - * - * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ - * using the configuration: - * Width = 8 - * Poly = 0x07 - * XorIn = 0x00 - * ReflectIn = False - * XorOut = 0x00 - * ReflectOut = False - * Algorithm = table-driven - * - * \param crc The current crc value. - * \param data Pointer to a buffer of \a data_len bytes. - * \param length Number of bytes in the \a data buffer. - * \return The updated crc value. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ using the + * configuration: Width = 8 Poly = 0x07 XorIn = 0x00 ReflectIn = False + * XorOut = 0x00 ReflectOut = False Algorithm = table-driven + * + * \param crc The current crc value. \param data Pointer to a buffer of \a + * data_len bytes. \param length Number of bytes in the \a data buffer. + * \return The updated crc value. */ - int updateCRC(int crc, int data) - { + int updateCRC(int crc, int data) { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data, int length) - { + + int updateCRC(int crc, byte[] data, int length) { for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); - return crc; + return crc; } - - } From cdac9d7f9e897acea31e63ba53f226a90b7dc2fe Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:57:18 -0500 Subject: [PATCH 072/165] Make the UAVTalk object process one byte per call so it can be embedded in another loop. Also clean up some warnings. --- .../src/org/openpilot/uavtalk/UAVTalk.java | 59 +++++++++---------- 1 file changed, 28 insertions(+), 31 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 33daefab7..8671cdef9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -1,7 +1,5 @@ package org.openpilot.uavtalk; -import java.io.ByteArrayInputStream; -import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.OutputStream; @@ -30,7 +28,10 @@ public class UAVTalk extends Observable { inputProcessingThread = new Thread() { public void run() { - processInputStream(); + while(true) { + if( !processInputStream() ) + break; + } } }; return inputProcessingThread; @@ -173,37 +174,36 @@ public class UAVTalk extends Observable { } /** - * Called each time there are data in the input buffer + * Process any data in the queue */ - public void processInputStream() { + public boolean processInputStream() { int val; - while (true) { - try { - // inStream.wait(); - val = inStream.read(); - } /* - * catch (InterruptedException e) { // TODO Auto-generated catch - * block System.out.println("Connection was aborted\n"); - * e.printStackTrace(); break; } - */catch (IOException e) { - // TODO Auto-generated catch block - System.out.println("Error reading from stream\n"); - e.printStackTrace(); - break; - } - if (val == -1) { - System.out - .println("End of stream, terminating processInputStream thread"); - break; - } + try { + // inStream.wait(); + val = inStream.read(); + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + return false; + } + if (val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + return false; + } - // System.out.println("Received byte " + val + " in state + " + - // rxState); - processInputByte(val); - } + // System.out.println("Received byte " + val + " in state + " + + // rxState); + processInputByte(val); + return true; } + /** * Request an update for the specified object, on success the object data * would have been updated by the GCS. \param[in] obj Object to update @@ -665,9 +665,6 @@ public class UAVTalk extends Observable { public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; - int dataOffset; - int objId; - int instId; int allInstId = ALL_INSTANCES; assert (objMngr != null && outStream != null); From d3f9c979613e547992ac1ebcd550b2cff8d252af Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:58:55 -0500 Subject: [PATCH 073/165] Create a UAVTalk service that is called from the object browser --- androidgcs/AndroidManifest.xml | 1 + .../androidgcs/BluetoothUAVTalk.java | 146 ++++++++++++++++++ .../androidgcs/OPTelemetryService.java | 88 +++++++++++ .../openpilot/androidgcs/ObjectBrowser.java | 97 +----------- 4 files changed, 238 insertions(+), 94 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 8b3a9e4b3..6c89f2632 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,5 +18,6 @@ + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java new file mode 100644 index 000000000..b240f3adc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -0,0 +1,146 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.BroadcastReceiver; +import android.content.Context; +import android.content.Intent; +import android.util.Log; + +public class BluetoothUAVTalk { + private final String TAG = "BluetoothUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String DEVICE_NAME = "RN42-222D"; + private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + + private BluetoothAdapter mBluetoothAdapter; + private BluetoothSocket socket; + private BluetoothDevice device; + private UAVTalk uavTalk; + private boolean connected; + + public BluetoothUAVTalk(Context caller, String deviceName) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + + connected = false; + device = null; + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.e(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + // Enable bluetooth if it isn't already + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + caller.sendOrderedBroadcast(enableBtIntent, "android.permission.BLUETOOTH_ADMIN", new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.e(TAG,"Received " + context + intent); + //TODO: some logic here to see if it worked + queryDevices(); + } + }, null, Activity.RESULT_OK, null, null); + } else { + queryDevices(); + } + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !getFoundDevice() ) + return false; + if( !openTelemetryBluetooth(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public boolean getFoundDevice() { + return (device != null); + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + private void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + this.device = device; + return; + } + } + } + + } + + private boolean openTelemetryBluetooth(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + socket = null; + connected = false; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + return false; + //e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java new file mode 100644 index 000000000..2994be6d2 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -0,0 +1,88 @@ +package org.openpilot.androidgcs; + +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.app.Service; +import android.content.Intent; +import android.os.IBinder; +import android.os.Looper; +import android.util.Log; + +public class OPTelemetryService extends Service { + private final String TAG = "OPTElemetryService"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + @Override + public IBinder onBind(Intent arg0) { + return null; + } + + @Override + public void onCreate() { + super.onCreate(); + + if (DEBUG) Log.d(TAG, "Telemetry Service started"); + + Thread telemetryThread = new Thread(telemetryRunnable); + telemetryThread.start(); + } + + @Override + public void onDestroy() { + super.onDestroy(); + } + + private final Runnable telemetryRunnable = new Runnable() { + + public void run() { + Looper.prepare(); + + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + while(true) { + if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); + if(! bt.getConnected() ) + bt.connect(objMngr); + else + break; + Looper.loop(); + } + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); + + uavTalk = bt.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while(true) { + if( !uavTalk.processInputStream() ) + break; + Looper.loop(); + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + + public UAVObjectManager getObjMngr() { return objMngr; }; + public UAVTalk getUavTalk() { return uavTalk; }; + public Telemetry getTelemetry() { return tel; }; + public TelemetryMonitor getTelemetryMonitor() { return mon; }; + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a8c58d58d..6bb217930 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -69,26 +69,12 @@ public class ObjectBrowser extends Activity { Log.d(TAG, "Launching Object Browser"); - connected = false; + Log.d(TAG, "Start OP Telemetry Service"); + startService( new Intent( this, OPTelemetryService.class ) ); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); - if (mBluetoothAdapter == null) { - // Device does not support Bluetooth - Log.e(TAG, "Device does not support Bluetooth"); - return; - } - - if (!mBluetoothAdapter.isEnabled()) { - Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); - startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); - } else { - queryDevices(); - } - - UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -116,84 +102,7 @@ public class ObjectBrowser extends Activity { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } - }); - - + }); } - @Override - public void onActivityResult(int requestCode, int resultCode, Intent data) { - if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - //Log.d(TAG, "Bluetooth started succesfully"); - queryDevices(); - } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { - //Log.d(TAG, "Bluetooth could not be started"); - } - - } - - public void queryDevices() { - Log.d(TAG, "Searching for devices"); - Set pairedDevices = mBluetoothAdapter.getBondedDevices(); - // If there are paired devices - if (pairedDevices.size() > 0) { - // Loop through paired devices - for (BluetoothDevice device : pairedDevices) { - // Add the name and address to an array adapter to show in a ListView - //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); - Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { - openTelmetryBluetooth(device); - openTelmetryBluetooth(device); - } - } - } - - } - - private void openTelmetryBluetooth(BluetoothDevice device) { - Log.d(TAG, "Opening conncetion to " + device.getName()); - socket = null; - connected = false; - try { - socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); - } catch (IOException e) { - Log.e(TAG,"Unable to create Rfcomm socket"); - //e.printStackTrace(); - } - - mBluetoothAdapter.cancelDiscovery(); - - try { - socket.connect(); - } - catch (IOException e) { - Log.e(TAG,"Unable to connect to requested device", e); - try { - socket.close(); - } catch (IOException e2) { - //Log.e(TAG, "unable to close() socket during connection failure", e2); - } - return; - } - - connected = true; - - try { - uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); - } catch (IOException e) { - Log.e(TAG,"Error starting UAVTalk"); - // TODO Auto-generated catch block - //e.printStackTrace(); - return; - } - - Thread inputStream = uavTalk.getInputProcessThread(); - inputStream.start(); - - Telemetry tel = new Telemetry(uavTalk, objMngr); - TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); - - } } From f247443d6420db79bb3afa228c4a6d9209130119 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 10:09:35 -0500 Subject: [PATCH 074/165] Clean up the logging somewhat --- .../androidgcs/OPTelemetryService.java | 62 +- .../openpilot/uavtalk/TelemetryMonitor.java | 31 +- flight/Revolution/Makefile.osx | 672 ++++++++++++++++++ 3 files changed, 740 insertions(+), 25 deletions(-) create mode 100644 flight/Revolution/Makefile.osx diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 2994be6d2..5a48bbc05 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -6,8 +6,14 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import android.app.Notification; +import android.app.NotificationManager; +import android.app.PendingIntent; import android.app.Service; +import android.content.Context; import android.content.Intent; +import android.net.Uri; +import android.os.Handler; import android.os.IBinder; import android.os.Looper; import android.util.Log; @@ -18,10 +24,16 @@ public class OPTelemetryService extends Service { public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; + final int DISCONNECT_MESSAGE = 0; + final int CONNECT_MESSAGE = 1; + final int CONNECT_FAILED_MESSAGE = 2; + private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; private TelemetryMonitor mon; + + private Handler handler; @Override public IBinder onBind(Intent arg0) { @@ -46,22 +58,38 @@ public class OPTelemetryService extends Service { private final Runnable telemetryRunnable = new Runnable() { public void run() { - Looper.prepare(); - if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - + + postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); - while(true) { + for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - if(! bt.getConnected() ) - bt.connect(objMngr); - else + + bt.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( bt.getConnected() ) break; - Looper.loop(); + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } } + if( ! bt.getConnected() ) { + postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); + return; + } + + postNotification(CONNECT_MESSAGE, "Connected to UAV port"); if (DEBUG) Log.d(TAG, "Connected via bluetooth"); @@ -73,13 +101,29 @@ public class OPTelemetryService extends Service { while(true) { if( !uavTalk.processInputStream() ) break; - Looper.loop(); } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } }; + void postNotification(int id, String message) { + String ns = Context.NOTIFICATION_SERVICE; + NotificationManager mNManager = (NotificationManager) getSystemService(ns); + final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); + + Context context = getApplicationContext(); + CharSequence contentTitle = "OpenPilot"; + CharSequence contentText = message; + Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); + PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); + + msg.setLatestEventInfo(context, contentTitle, contentText, intent); + + mNManager.notify(id, msg); + } + public UAVObjectManager getObjMngr() { return objMngr; }; public UAVTalk getUavTalk() { return uavTalk; }; public Telemetry getTelemetry() { return tel; }; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index a5885e7bc..9b4474d8e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -16,7 +16,10 @@ import android.util.Log; public class TelemetryMonitor { private static final String TAG = "TelemetryMonitor"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + static final int STATS_UPDATE_PERIOD_MS = 4000; static final int STATS_CONNECT_PERIOD_MS = 1000; static final int CONNECTION_TIMEOUT_MS = 8000; @@ -57,7 +60,7 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { - Log.d(TAG, "Start retrieving objects"); + if (DEBUG) Log.d(TAG, "Start retrieving objects"); // Clear object queue queue.clear(); @@ -115,7 +118,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { - Log.d(TAG, "All objects retrieved: Connected Successfully"); + if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -127,12 +130,12 @@ public class TelemetryMonitor { throw new Error("Got null object forom transaction queue"); } - Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if (DEBUG) Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; - Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); + if (DEBUG) Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -149,7 +152,7 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted. Status: " + success); + if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; @@ -192,7 +195,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats - Log.d(TAG, "processStatsUpdates()"); + if (DEBUG) Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -232,7 +235,7 @@ public class TelemetryMonitor { UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = new String((String) statusField.getValue()); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -245,7 +248,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - Log.d(TAG,"Connected" + statusField.toString()); + if (DEBUG) Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -260,30 +263,26 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) { - Log.d(TAG,"GCS Status changed"); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); - } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; if ( !gcsConnected || !flightConnected ) { - Log.d(TAG,"Sending gcs status"); + if (DEBUG) Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { - Log.d(TAG,"Connection with the autopilot established"); + if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { - Log.d(TAG,"Trying to connect to the autopilot"); + if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); //emit disconnected(); } diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx new file mode 100644 index 000000000..e2c8ea694 --- /dev/null +++ b/flight/Revolution/Makefile.osx @@ -0,0 +1,672 @@ + ##### + # Project: Revolution + # + # + # Makefile for OpenPilot project build PiOS and the AP. + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + + +# Set developer code and compile options +# Set to YES to compile for debugging +DEBUG ?= YES + +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# +USE_BOOTLOADER ?= NO + + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) +TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +# Remove command is different for Code Sourcery on Windows +REMOVE_CMD ?= rm + +FLASH_TOOL = OPENOCD + +# YES enables -mthumb option to flags for source-files listed +# in SRC and CPPSRC +USE_THUMB_MODE = YES + +# List of modules to include +MODULES += Actuator ManualControl Stabilization +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +MODULES += Attitude/revolution +#MODULES += OveroSync/simulated + +# To run simulation instead of connect to SITL +MODULES += Sensors/simulated + +MODULES += Telemetry + +# MCU name, submodel and board +# - MCU used for compiler-option (-mtune) +# - MODEL used for linker-script name (-T) and passed as define +# - BOARD just passed as define (optional) +MCU = i686 +#CHIP = STM32F103RET +#BOARD = STM3210E_OP +MODEL = HD +ifeq ($(USE_BOOTLOADER), YES) +BOOT_MODEL = $(MODEL)_BL + +else +BOOT_MODEL = $(MODEL)_NB +endif + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR = ../../build/sim_osx + +# Target file name (without extension). +TARGET = Revolution + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../PiOS.osx +PIOSINC = $(PIOS)/inc +PIOSPOSIX = $(PIOS)/osx +APPLIBDIR = $(PIOSPOSIX)/Libraries +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +MODNAMES = $(notdir ${MODULES}) + +ifndef TESTAPP + +## PyMite files +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +SRC += $(wildcard ${PYMITEVM}/*.c) +SRC += $(wildcard ${PYMITEPLAT}/*.c) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board_sim.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + + + +## UAVOBJECTS +ifndef TESTAPP +#include $(UAVOBJSYNTHDIR)/Makefile.inc +include ./UAVObjects.inc + +UAVOBJSRCFILENAMES += attitudesimulated +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + +SRC += $(UAVOBJSRC) +CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) +endif + +## PIOS Hardware (posix) +SRC += $(PIOSPOSIX)/pios_crc.c +SRC += $(PIOSPOSIX)/pios_sys.c +SRC += $(PIOSPOSIX)/pios_led.c +SRC += $(PIOSPOSIX)/pios_irq.c +SRC += $(PIOSPOSIX)/pios_delay.c +SRC += $(PIOSPOSIX)/pios_sdcard.c +SRC += $(PIOSPOSIX)/pios_udp.c +SRC += $(PIOSPOSIX)/pios_tcp.c +SRC += $(PIOSPOSIX)/pios_com.c +SRC += $(PIOSPOSIX)/pios_servo.c +SRC += $(PIOSPOSIX)/pios_wdg.c +SRC += $(PIOSPOSIX)/pios_debug.c + +SRC += $(PIOSPOSIX)/pios_rcvr.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c + +## RTOS and RTOS Portable +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +UNAME := $(shell uname) +SRC += $(RTOSSRCDIR)/task.c +SRC += $(RTOSSRCDIR)/timers.c +SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c + + + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSPOSIX) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix +EXTRAINCDIRS += $(PYMITEINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +#DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(USE_BOOTLOADER), YES) +CDEFS += -DUSE_BOOTLOADER +endif + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS = -g$(DEBUGF) -DDEBUG +endif + +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +CFLAGS += $(CFLAGS_UAVOBJECTS) +CFLAGS += -DARCH_POSIX +CFLAGS += -O$(OPT) +CFLAGS += -mtune=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +CFLAGS += -Werror +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS += -lpthread +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +# To include simulation model +LDFLAGS += -L$(OUTDIR) +#LDFLAGS += -lsimmodel + + +# Define programs and commands. +CC = $(TCHAIN_PREFIX)gcc +CPP = $(TCHAIN_PREFIX)g++ +AR = $(TCHAIN_PREFIX)ar +OBJCOPY = $(TCHAIN_PREFIX)objcopy +OBJDUMP = $(TCHAIN_PREFIX)objdump +SIZE = $(TCHAIN_PREFIX)size +NM = $(TCHAIN_PREFIX)nm +REMOVE = $(REMOVE_CMD) -f +PYTHON = python +###SHELL = sh +###COPY = cp + + + +# Define Messages +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} +MSG_END = ${quote}-------- end --------${quote} +MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} +MSG_SIZE_BEFORE = ${quote}Size before:${quote} +MSG_SIZE_AFTER = ${quote}Size after build:${quote} +MSG_LOAD_FILE = ${quote}Creating load file:${quote} +MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} +MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} +MSG_LINKING = ${quote}**** Linking :${quote} +MSG_COMPILING = ${quote}**** Compiling C :${quote} +MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} +MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} +MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} +MSG_ASSEMBLING = ${quote}**** Assembling:${quote} +MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} +MSG_CLEANING = ${quote}Cleaning project:${quote} +MSG_FORMATERROR = ${quote}Can not handle output-format${quote} +MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} +MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} +MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin + +# Default target. +#all: begin gccversion sizebefore build sizeafter finished end +#all: begin gencode gccversion build sizeafter finished end +all: elf + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Test if quotes are needed for the echo-command +result = ${shell echo "test"} +ifeq (${result}, test) + quote = ' +else + quote = +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +getmodname = $(firstword $(subst /, ,$1)) + +MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile.osx + echo ${MOD_GEN} + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @echo ${MSG_PYMITEINIT} + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py + +# Eye candy. +begin: +## @echo + @echo $(MSG_BEGIN) + +finished: +## @echo $(MSG_ERRORS_NONE) + +end: + @echo $(MSG_END) +## @echo + +# Display sizes of sections. +ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf +##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf +sizebefore: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi + +sizeafter: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi + @echo $(MSG_SIZE_AFTER) + $(ELFSIZE) + +# Display compiler version information. +gccversion : + @$(CC) --version +# @echo $(ALLOBJ) + +# Program the device. +ifeq ($(USE_BOOTLOADER), YES) +# Program the device with OP Upload Tool". +program: $(OUTDIR)/$(TARGET).bin + @echo ${quote}Programming with OP Upload Tool${quote} + ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin +else +ifeq ($(FLASH_TOOL),OPENOCD) +# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". +program: $(OUTDIR)/$(TARGET).elf + @echo ${quote}Programming with OPENOCD${quote} + $(OOCD_EXE) $(OOCD_CL) +endif +endif + +# Create final output file (.hex) from ELF output file. +%.hex: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O ihex $< $@ + +# Create final output file (.bin) from ELF output file. +%.bin: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O binary $< $@ + +# Create extended listing file/disassambly from ELF output file. +# using objdump testing: option -C +%.lss: %.elf +## @echo + @echo $(MSG_EXTENDED_LISTING) $@ + $(OBJDUMP) -h -S -C -r $< > $@ +# $(OBJDUMP) -x -S $< > $@ + +# Create a symbol table from ELF output file. +%.sym: %.elf +## @echo + @echo $(MSG_SYMBOL_TABLE) $@ + $(NM) -n $< > $@ + +# Link: create ELF output file from object files. +.SECONDARY : $(TARGET).elf +.PRECIOUS : $(ALLOBJ) +%.elf: $(ALLOBJ) + @echo $(MSG_LINKING) $@ +# use $(CC) for C-only projects or $(CPP) for C++-projects: + $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) +# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) + + +# Assemble: create object files from assembler source files. +define ASSEMBLE_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING) $$< to $$@ + $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +define ASSEMBLE_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ + $(CC) -c $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C source files. +define COMPILE_C_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +define COMPILE_C_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C++ source files. +define COMPILE_CPP_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +define COMPILE_CPP_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + + +# Compile: create assembler files from C source files. ARM/Thumb +$(SRC:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC) $< to $@ + $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Compile: create assembler files from C source files. ARM only +$(SRCARM:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC_ARM) $< to $@ + $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Target: clean project. +clean: begin clean_list finished end + +clean_list : +## @echo + @echo $(MSG_CLEANING) + $(REMOVE) $(OUTDIR)/$(TARGET).map + $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(REMOVE) $(wildcard $(OUTDIR)/*.h) + $(REMOVE) $(ALLOBJ) + $(REMOVE) $(LSTFILES) + $(REMOVE) $(DEPFILES) + $(REMOVE) $(SRC:.c=.s) + $(REMOVE) $(SRCARM:.c=.s) + $(REMOVE) $(CPPSRC:.cpp=.s) + $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(OUTDIR) 2>NUL) +else +$(shell mkdir $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + + + +# Listing of phony targets. +.PHONY : all begin finish end sizebefore sizeafter gccversion \ +build elf hex bin lss sym clean clean_list program gencode + From 2f7320fc16dd1c51765908952e4b863614b56fcb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 19:58:57 -0500 Subject: [PATCH 075/165] Common Activity class that binds to the Telemetry service --- .../androidgcs/ObjectManagerActivity.java | 97 +++++++++++++++++++ 1 file changed, 97 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java new file mode 100644 index 000000000..9f57796dc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -0,0 +1,97 @@ +package org.openpilot.androidgcs; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVObjectManager; + +import android.app.Activity; +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; + +public abstract class ObjectManagerActivity extends Activity { + + private final String TAG = "ObjectManagerActivity"; + private static int LOGLEVEL = 2; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + void onOPConnected() { + + } + + void onOPDisconnected() { + + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + binder = (LocalBinder) service; + binder.openFakeConnection(); + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + mConnected = false; + objMngr = null; + } + }; +} From a70c967f9c4da5564b2e5e2957a4436b90d70b36 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 20:00:12 -0500 Subject: [PATCH 076/165] Start of a widget for monitoring telemetry status --- androidgcs/AndroidManifest.xml | 43 +++++++++++++------ androidgcs/res/layout/telemetry_widget.xml | 7 +++ .../openpilot/androidgcs/TelemetryWidget.java | 31 +++++++++++++ 3 files changed, 67 insertions(+), 14 deletions(-) create mode 100644 androidgcs/res/layout/telemetry_widget.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 6c89f2632..9a3d1dd25 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -1,23 +1,38 @@ - + package="org.openpilot.androidgcs" android:versionCode="1" + android:versionName="1.0"> + - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - + \ No newline at end of file diff --git a/androidgcs/res/layout/telemetry_widget.xml b/androidgcs/res/layout/telemetry_widget.xml new file mode 100644 index 000000000..6af378104 --- /dev/null +++ b/androidgcs/res/layout/telemetry_widget.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java new file mode 100644 index 000000000..90ab80899 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -0,0 +1,31 @@ +package org.openpilot.androidgcs; + +import android.appwidget.AppWidgetManager; +import android.appwidget.AppWidgetProvider; +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.widget.RemoteViews; + +public class TelemetryWidget extends AppWidgetProvider { + + private static boolean connected = false; + + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { + final int N = appWidgetIds.length; + + // Perform this loop procedure for each App Widget that belongs to this provider + for (int i=0; i Date: Sat, 19 Mar 2011 20:01:01 -0500 Subject: [PATCH 077/165] Get rid of lots of warnings --- .../androidgcs/OPTelemetryService.java | 211 ++++++++++++++---- .../openpilot/androidgcs/ObjectBrowser.java | 83 ++----- .../openpilot/androidgcs/TelemetryWidget.java | 4 - .../src/org/openpilot/uavtalk/Telemetry.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 11 +- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 11 +- 7 files changed, 194 insertions(+), 129 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5a48bbc05..557c3b256 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -2,6 +2,7 @@ package org.openpilot.androidgcs; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -13,69 +14,192 @@ import android.app.Service; import android.content.Context; import android.content.Intent; import android.net.Uri; +import android.os.Binder; import android.os.Handler; +import android.os.HandlerThread; import android.os.IBinder; import android.os.Looper; +import android.os.Message; +import android.os.Process; import android.util.Log; +import android.widget.Toast; public class OPTelemetryService extends Service { + + // Logging settings private final String TAG = "OPTElemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - final int DISCONNECT_MESSAGE = 0; - final int CONNECT_MESSAGE = 1; - final int CONNECT_FAILED_MESSAGE = 2; - - private UAVObjectManager objMngr; - private UAVTalk uavTalk; - private Telemetry tel; - private TelemetryMonitor mon; - - private Handler handler; + // Intent category + public final static String INTENT_CATEGORY_GCS = "org.openpilot.intent.category.GCS"; - @Override - public IBinder onBind(Intent arg0) { - return null; - } + // Intent actions + public final static String INTENT_ACTION_CONNECTED = "org.openpilot.intent.action.CONNECTED"; + public final static String INTENT_ACTION_DISCONNECTED = "org.openpilot.intent.action.DISCONNECTED"; + + // Variables for local message handler thread + private Looper mServiceLooper; + private ServiceHandler mServiceHandler; + + // Message ids + final int MSG_START = 0; + final int MSG_CONNECT_BT = 1; + final int MSG_CONNECT_FAKE = 2; + final int MSG_TOAST = 100; + + private Thread activeTelem; + + private final IBinder mBinder = new LocalBinder(); + + private final class ServiceHandler extends Handler { + public ServiceHandler(Looper looper) { + super(looper); + } + @Override + public void handleMessage(Message msg) { + switch(msg.arg1) { + case MSG_START: + Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); + System.out.println("HERE"); + stopSelf(msg.arg2); + case MSG_CONNECT_BT: + activeTelem = new BTTelemetryThread(); + activeTelem.start(); + break; + case MSG_CONNECT_FAKE: + activeTelem = new FakeTelemetryThread(); + activeTelem.start(); + break; + case MSG_TOAST: + Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); + break; + default: + System.out.println(msg.toString()); + throw new Error("Invalid message"); + } + } + }; @Override public void onCreate() { - super.onCreate(); - - if (DEBUG) Log.d(TAG, "Telemetry Service started"); + // Low priority thread for message handling with service + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", + Process.THREAD_PRIORITY_BACKGROUND); + thread.start(); - Thread telemetryThread = new Thread(telemetryRunnable); - telemetryThread.start(); - } + // Get the HandlerThread's Looper and use it for our Handler + mServiceLooper = thread.getLooper(); + mServiceHandler = new ServiceHandler(mServiceLooper); + } + + @Override + public int onStartCommand(Intent intent, int flags, int startId) { + Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); + + System.out.println("Start"); + // For each start request, send a message to start a job and deliver the + // start ID so we know which request we're stopping when we finish the job + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_START; + msg.arg2 = startId; + mServiceHandler.sendMessage(msg); + + // If we get killed, after returning from here, restart + return START_STICKY; + } + + @Override + public IBinder onBind(Intent intent) { + return mBinder; + } @Override public void onDestroy() { - super.onDestroy(); + Toast.makeText(this, "Telemetry service done", Toast.LENGTH_SHORT).show(); } + + public class LocalBinder extends Binder { + public TelemTask getTelemTask(int id) { + return (TelemTask) activeTelem; + } + public void openFakeConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_FAKE; + mServiceHandler.sendMessage(msg); + } + }; - private final Runnable telemetryRunnable = new Runnable() { + public void toastMessage(String msgText) { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_TOAST; + msg.obj = msgText; + mServiceHandler.sendMessage(msg); + } + + public interface TelemTask { + public UAVObjectManager getObjectManager(); + }; + + // Fake class for testing, simply emits periodic updates on + private class FakeTelemetryThread extends Thread implements TelemTask { + private UAVObjectManager objMngr; + public UAVObjectManager getObjectManager() { return objMngr; }; + + FakeTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + System.out.println("Runnin fake thread"); + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + + //toastMessage("Started fake telemetry thread"); + UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + while(true) { + systemStats.updated(); + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + break; + } + } + } + } + private class BTTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + //private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + BTTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } public void run() { if (DEBUG) Log.d(TAG, "Telemetry Thread started"); Looper.prepare(); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - - postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - + bt.connect(objMngr); - + if (DEBUG) Log.d(TAG, "Done attempting connection"); if( bt.getConnected() ) break; - + try { Thread.sleep(1000); } catch (InterruptedException e) { @@ -85,17 +209,15 @@ public class OPTelemetryService extends Service { } } if( ! bt.getConnected() ) { - postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); return; } - - postNotification(CONNECT_MESSAGE, "Connected to UAV port"); - + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); - + uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - mon = new TelemetryMonitor(objMngr,tel); + new TelemetryMonitor(objMngr,tel); if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); while(true) { @@ -103,30 +225,23 @@ public class OPTelemetryService extends Service { break; } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); - postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } - + }; - + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); - + Context context = getApplicationContext(); CharSequence contentTitle = "OpenPilot"; CharSequence contentText = message; Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); - + msg.setLatestEventInfo(context, contentTitle, contentText, intent); - + mNManager.notify(id, msg); } - - public UAVObjectManager getObjMngr() { return objMngr; }; - public UAVTalk getUavTalk() { return uavTalk; }; - public Telemetry getTelemetry() { return tel; }; - public TelemetryMonitor getTelemetryMonitor() { return mon; }; - } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 6bb217930..48aa1cd10 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,21 @@ package org.openpilot.androidgcs; -import java.io.IOException; import java.util.Observable; import java.util.Observer; -import java.util.Set; -import java.util.UUID; -import android.app.Activity; -import android.bluetooth.BluetoothAdapter; -import android.bluetooth.BluetoothDevice; -import android.bluetooth.BluetoothSocket; -import android.content.Intent; import android.os.Bundle; import android.os.Handler; import android.util.Log; import android.widget.TextView; import android.widget.ToggleButton; -import org.openpilot.androidgcs.*; -import org.openpilot.uavtalk.Telemetry; -import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVTalk; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; -public class ObjectBrowser extends Activity { - +public class ObjectBrowser extends ObjectManagerActivity { + private final String TAG = "ObjectBrower"; - private final String DEVICE_NAME = "RN42-222D"; - private final int REQUEST_ENABLE_BT = 0; - private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); - BluetoothAdapter mBluetoothAdapter; - BluetoothSocket socket; boolean connected; - UAVObjectManager objMngr; - UAVTalk uavTalk; - + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -44,9 +23,9 @@ public class ObjectBrowser extends Activity { button.setChecked(!connected); Log.d(TAG,"HERE" + connected); - + TextView text = (TextView) findViewById(R.id.textView1); - + UAVObject obj1 = objMngr.getObject("SystemStats"); UAVObject obj2 = objMngr.getObject("AttitudeRaw"); UAVObject obj3 = objMngr.getObject("AttitudeActual"); @@ -57,52 +36,30 @@ public class ObjectBrowser extends Activity { Log.d(TAG,"And here"); text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + } }; - - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - setContentView(R.layout.main); - - Log.d(TAG, "Launching Object Browser"); - Log.d(TAG, "Start OP Telemetry Service"); - startService( new Intent( this, OPTelemetryService.class ) ); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + } + + @Override + void onOPConnected() { + // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Log.d(TAG, "onOPConnected()"); UAVObject obj = objMngr.getObject("SystemStats"); + Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } }); - obj = objMngr.getObject("AttitudeRaw"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("AttitudeActual"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("SystemAlarms"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - } - + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index 90ab80899..d316526ef 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -3,14 +3,10 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; import android.content.Context; -import android.content.Intent; -import android.os.Bundle; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { - private static boolean connected = false; - public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index c754c8329..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -630,7 +630,6 @@ public class Telemetry { /** * Private variables */ - private TelemetryStats stats; private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 9b4474d8e..7208181ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -8,9 +8,6 @@ import java.util.Observer; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; -import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; - import android.util.Log; public class TelemetryMonitor { @@ -26,7 +23,7 @@ public class TelemetryMonitor { private UAVObjectManager objMngr; private Telemetry tel; - private UAVObject objPending; +// private UAVObject objPending; private UAVObject gcsStatsObj; private UAVObject flightStatsObj; private Timer periodicTask; @@ -38,7 +35,7 @@ public class TelemetryMonitor { { this.objMngr = objMngr; this.tel = tel; - this.objPending = null; +// this.objPending = null; queue = new ArrayList(); // Get stats objects @@ -142,7 +139,7 @@ public class TelemetryMonitor { // Request update tel.updateRequested(obj); - objPending = obj; +// objPending = obj; } /** @@ -155,7 +152,7 @@ public class TelemetryMonitor { if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); - objPending = null; +// objPending = null; if(!success) { Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index ba3bf1ae3..940b076a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -64,7 +64,7 @@ public abstract class UAVObject { if(manually) updatedManual(); } - void updated() { updated(true); }; + public void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index de2059e90..78ad70630 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -1,6 +1,5 @@ package org.openpilot.uavtalk; -import java.io.Serializable; import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.ArrayList; @@ -91,7 +90,8 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public synchronized int pack(ByteBuffer dataOut) { + @SuppressWarnings("unchecked") + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -152,7 +152,8 @@ public class UAVObjectField { return getNumBytes(); } - public synchronized int unpack(ByteBuffer dataIn) { + @SuppressWarnings("unchecked") + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -436,9 +437,9 @@ public class UAVObjectField { } } - public String toString() { + public String toString() { String sout = new String(); - sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; + sout += name + ": " + data.toString() + " (" + units + ")\n"; return sout; } From 6613e4d3bf2eb381998ddb1d6b64bc29d5797271 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 06:09:06 -0500 Subject: [PATCH 078/165] Added some missing files. Improved object browser to use ListView. ExpandableListView next. --- androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 0 -> 12288 bytes androidgcs/Doc/AndroidArchitecture.txt | 31 +++++++ androidgcs/res/layout/main.xml | 17 ++-- androidgcs/res/layout/object_view.xml | 7 ++ androidgcs/res/menu/options_menu.xml | 6 ++ androidgcs/res/values/strings.xml | 4 + androidgcs/res/xml/telemetry_widget_info.xml | 9 ++ .../androidgcs/OPTelemetryService.java | 69 +++++++++++--- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++----- .../androidgcs/ObjectManagerActivity.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 30 +++++-- .../src/org/openpilot/uavtalk/UAVTalk.java | 3 +- 12 files changed, 202 insertions(+), 59 deletions(-) create mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp create mode 100644 androidgcs/Doc/AndroidArchitecture.txt create mode 100644 androidgcs/res/layout/object_view.xml create mode 100644 androidgcs/res/menu/options_menu.xml create mode 100644 androidgcs/res/xml/telemetry_widget_info.xml diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp new file mode 100644 index 0000000000000000000000000000000000000000..167a072526a8207b396d71d6dd7d3e7a417cba19 GIT binary patch literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 literal 0 HcmV?d00001 diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt new file mode 100644 index 000000000..d9cdf2ada --- /dev/null +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -0,0 +1,31 @@ +------- TELEMETRY --------- +The Telemetry system has been implemented, and is composed of a few +major components: + +Telemetry.java - receives command to transmit objects through telemetry and +also emits notification when transactions are completed + +TelemetryMonitor.java - monitors the FlightTelemetryStats and GCSTelemetryStats +to establish when a working connection is in place. Also initiates downloading +all the objects on a new connection. + +UAVObjectManager.java - the central data store. The data is actually stored +within objects, but this maintains the handles to all of them. + +UAVTalk.java - the actual communication layer. Can packetize an object and +insert into stream and process the incoming stream and update objects +accordingly. + +---- MESSAGE PASSING ---- +The current implementation/analog to the slots/sockets in QT are Observers +which are registered as added to an Observable. This is used extensibly within +the telemetry system. I will continue to use this _within_ the Telemetry +module so it doesn't depend on any android features. + +In android there is a constraint that UI operations should all be done from the +UI thread. The most common way to do this is for the UI object (such as +Activity) to instantiate a Handler to which messages or runnables are posted. + +So for external objects they will register a runnable somehow... + + diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 9e5f90add..880e276ff 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -1,13 +1,6 @@ - - - - - + + + diff --git a/androidgcs/res/layout/object_view.xml b/androidgcs/res/layout/object_view.xml new file mode 100644 index 000000000..fdf5a0bae --- /dev/null +++ b/androidgcs/res/layout/object_view.xml @@ -0,0 +1,7 @@ + + + diff --git a/androidgcs/res/menu/options_menu.xml b/androidgcs/res/menu/options_menu.xml new file mode 100644 index 000000000..db86aa670 --- /dev/null +++ b/androidgcs/res/menu/options_menu.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 52fa56534..8daa0ec36 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,4 +1,8 @@ OpenPilot GCS + Settings + Connect + Disconnect + OpenPilot Object Browser diff --git a/androidgcs/res/xml/telemetry_widget_info.xml b/androidgcs/res/xml/telemetry_widget_info.xml new file mode 100644 index 000000000..f2ced6645 --- /dev/null +++ b/androidgcs/res/xml/telemetry_widget_info.xml @@ -0,0 +1,9 @@ + + + android:minWidth="294dp" + android:minHeight="72dp" + android:updatePeriodMillis="86400000" + android:initialLayout="@layout/telemetry_widget"> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 557c3b256..7b3030d4f 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -1,5 +1,8 @@ package org.openpilot.androidgcs; +import java.util.Observable; +import java.util.Observer; + import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVDataObject; @@ -27,7 +30,7 @@ import android.widget.Toast; public class OPTelemetryService extends Service { // Logging settings - private final String TAG = "OPTElemetryService"; + private final String TAG = "OPTelemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -44,10 +47,13 @@ public class OPTelemetryService extends Service { private ServiceHandler mServiceHandler; // Message ids - final int MSG_START = 0; - final int MSG_CONNECT_BT = 1; - final int MSG_CONNECT_FAKE = 2; - final int MSG_TOAST = 100; + static final int MSG_START = 0; + static final int MSG_CONNECT_BT = 1; + static final int MSG_CONNECT_FAKE = 2; + static final int MSG_DISCONNECT = 3; + static final int MSG_TOAST = 100; + + private boolean terminate = false; private Thread activeTelem; @@ -65,12 +71,28 @@ public class OPTelemetryService extends Service { System.out.println("HERE"); stopSelf(msg.arg2); case MSG_CONNECT_BT: + terminate = false; activeTelem = new BTTelemetryThread(); activeTelem.start(); break; case MSG_CONNECT_FAKE: + terminate = false; activeTelem = new FakeTelemetryThread(); activeTelem.start(); + break; + case MSG_DISCONNECT: + terminate = true; + try { + activeTelem.join(); + } catch (InterruptedException e) { + e.printStackTrace(); + } + activeTelem = null; + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_DISCONNECTED); + sendBroadcast(intent,null); + break; case MSG_TOAST: Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); @@ -129,8 +151,18 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_CONNECT_FAKE; mServiceHandler.sendMessage(msg); } + public void openBTConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_BT; + mServiceHandler.sendMessage(msg); + } + public void stopConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_DISCONNECT; + mServiceHandler.sendMessage(msg); + } }; - + public void toastMessage(String msgText) { Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_TOAST; @@ -151,17 +183,17 @@ public class OPTelemetryService extends Service { objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); } - + public void run() { - System.out.println("Runnin fake thread"); + System.out.println("Running fake thread"); Intent intent = new Intent(); intent.setAction(INTENT_ACTION_CONNECTED); sendBroadcast(intent,null); - + //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); - while(true) { + while( !terminate ) { systemStats.updated(); try { Thread.sleep(1000); @@ -176,7 +208,7 @@ public class OPTelemetryService extends Service { private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; - //private TelemetryMonitor mon; + private TelemetryMonitor mon; public UAVObjectManager getObjectManager() { return objMngr; }; @@ -217,10 +249,21 @@ public class OPTelemetryService extends Service { uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - new TelemetryMonitor(objMngr,tel); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); - while(true) { + while( !terminate ) { if( !uavTalk.processInputStream() ) break; } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 48aa1cd10..f68e839c1 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,67 @@ package org.openpilot.androidgcs; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; +import android.view.View; +import android.view.ViewGroup; +import android.widget.ArrayAdapter; +import android.widget.ExpandableListAdapter; +import android.widget.ExpandableListView; +import android.widget.ListView; +import android.widget.SimpleAdapter; +import android.widget.SimpleExpandableListAdapter; import android.widget.TextView; -import android.widget.ToggleButton; +import android.widget.Toast; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity { + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openBTConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + updateText.run(); + return true; + case R.id.menu_settings: + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + private final String TAG = "ObjectBrower"; boolean connected; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); - button.setChecked(!connected); - - Log.d(TAG,"HERE" + connected); - - TextView text = (TextView) findViewById(R.id.textView1); - - UAVObject obj1 = objMngr.getObject("SystemStats"); - UAVObject obj2 = objMngr.getObject("AttitudeRaw"); - UAVObject obj3 = objMngr.getObject("AttitudeActual"); - UAVObject obj4 = objMngr.getObject("SystemAlarms"); - - if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) - return; - - Log.d(TAG,"And here"); - text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + Log.d(TAG,"Update"); + update(); } }; @@ -44,16 +69,15 @@ public class ObjectBrowser extends ObjectManagerActivity { @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.main); } @Override void onOPConnected() { - // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + UAVObject obj = objMngr.getObject("SystemStats"); - Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { @@ -62,4 +86,18 @@ public class ObjectBrowser extends ObjectManagerActivity { }); } + + public void update() { + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 9f57796dc..12a072de7 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -85,7 +85,6 @@ public abstract class ObjectManagerActivity extends Activity { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); binder = (LocalBinder) service; - binder.openFakeConnection(); } public void onServiceDisconnected(ComponentName name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 7208181ad..daedcc85b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -10,10 +10,10 @@ import java.util.TimerTask; import android.util.Log; -public class TelemetryMonitor { +public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -31,6 +31,12 @@ public class TelemetryMonitor { private long lastUpdateTime; private List queue; + private boolean connected = false; + private boolean objects_updated = false; + + public boolean getConnected() { return connected; }; + public boolean getObjectsUpdated() { return objects_updated; }; + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) { this.objMngr = objMngr; @@ -116,8 +122,9 @@ public class TelemetryMonitor { if ( queue.isEmpty() ) { if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); - //qxtLog->debug("Object retrieval completed"); - //emit connected(); + objects_updated = true; + setChanged(); + notifyObservers(); return; } // Get next object from the queue @@ -260,9 +267,9 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; - boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; + boolean gcsConnected = statusField.getValue().equals("Connected"); + boolean gcsDisconnected = statusField.getValue().equals("Disconnected"); + boolean flightConnected = flightStatsObj.getField("Status").equals("Connected"); if ( !gcsConnected || !flightConnected ) { @@ -275,14 +282,21 @@ public class TelemetryMonitor { { if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); + connected = true; + objects_updated = false; startRetrievingObjects(); + setChanged(); } if (gcsDisconnected && gcsStatusChanged) { if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - //emit disconnected(); + connected = false; + objects_updated = false; + setChanged(); } + notifyObservers(); + } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8671cdef9..39c1f6ee7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -197,8 +197,7 @@ public class UAVTalk extends Observable { return false; } - // System.out.println("Received byte " + val + " in state + " + - // rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); return true; } From 247d3a7754ac5b48a0af2ce6ee91a483cdc5e91d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 21:34:03 -0500 Subject: [PATCH 079/165] Added a home page, added an option to select connection type. Made the ListView adapter trigger updates on the data. --- androidgcs/AndroidManifest.xml | 8 ++- androidgcs/Doc/AndroidArchitecture.txt | 39 +++++++++++ androidgcs/res/layout/gcs_home.xml | 7 ++ androidgcs/res/values/arrays.xml | 15 +++++ androidgcs/res/values/strings.xml | 9 ++- androidgcs/res/xml/preferences.xml | 12 ++++ .../org/openpilot/androidgcs/HomePage.java | 23 +++++++ .../androidgcs/OPTelemetryService.java | 39 ++++++----- .../openpilot/androidgcs/ObjectBrowser.java | 65 ++++++++----------- .../androidgcs/ObjectManagerActivity.java | 28 ++++++++ .../org/openpilot/androidgcs/Preferences.java | 12 ++++ 11 files changed, 201 insertions(+), 56 deletions(-) create mode 100644 androidgcs/res/layout/gcs_home.xml create mode 100644 androidgcs/res/values/arrays.xml create mode 100644 androidgcs/res/xml/preferences.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/HomePage.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/Preferences.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 9a3d1dd25..a791d0fbb 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -10,17 +10,23 @@ - + + + + + + + diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt index d9cdf2ada..0a17a8dfa 100644 --- a/androidgcs/Doc/AndroidArchitecture.txt +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -16,6 +16,11 @@ UAVTalk.java - the actual communication layer. Can packetize an object and insert into stream and process the incoming stream and update objects accordingly. +** Threading +Currently object updates run within the thread of the function that called +update. This should be changed so that it adds a message to the Telemetry +thread which will then send on its own time. + ---- MESSAGE PASSING ---- The current implementation/analog to the slots/sockets in QT are Observers which are registered as added to an Observable. This is used extensibly within @@ -28,4 +33,38 @@ Activity) to instantiate a Handler to which messages or runnables are posted. So for external objects they will register a runnable somehow... +--- TELEMETRY SERVICE --- +The telemetry connection will be maintained by a service separate from the the +main activity(s). Although it is a bit unusual, the service will support being +started and stopped, as well as being bound. Binding will be required to get +access to the Object Manager. +In addition, to make it forward looking, the start intent can specify a +connection to open. This will allow the service in future to monitor multiple +connections. + +The service will destroy itself only when all active connections disappear and +all activies are unbound. + +It will also handle any logging desired (I think). + +There will be a primary message handler thread. This thread will separately +launch telemetry threads when required. + +The service should send broadcast intents whenever a connection is estabilished +or dropped. + +I dont think the service should have the options about which UAVs are +supported. + +** Telemetry IBinder +*** Give handle to the ObjectManager for each UAV +*** Call disconnect +*** Query conncetion status + +--- TELEMETRY WIDGET --- +Listens for conncet/disconnect intents + +Also show if service is running? + +Ability to launch service? diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml new file mode 100644 index 000000000..e6f4ea567 --- /dev/null +++ b/androidgcs/res/layout/gcs_home.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/res/values/arrays.xml b/androidgcs/res/values/arrays.xml new file mode 100644 index 000000000..18ee52298 --- /dev/null +++ b/androidgcs/res/values/arrays.xml @@ -0,0 +1,15 @@ + + + + None + Fake + Bluetooth + Network + + + 0 + 1 + 2 + 3 + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 8daa0ec36..e9b66a312 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,8 +1,13 @@ - OpenPilot GCS + OpenPilot GCS Home + OpenPilot Object Browser Settings Connect Disconnect - OpenPilot Object Browser + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml new file mode 100644 index 000000000..d731f59dd --- /dev/null +++ b/androidgcs/res/xml/preferences.xml @@ -0,0 +1,12 @@ + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java new file mode 100644 index 000000000..478c7cdca --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -0,0 +1,23 @@ +package org.openpilot.androidgcs; + +import android.content.Intent; +import android.os.Bundle; +import android.view.View; +import android.view.View.OnClickListener; +import android.widget.Button; + +public class HomePage extends ObjectManagerActivity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); + objectBrowser.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, ObjectBrowser.class)); + } + }); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 7b3030d4f..5af7c7d60 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -16,6 +16,7 @@ import android.app.PendingIntent; import android.app.Service; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; import android.net.Uri; import android.os.Binder; import android.os.Handler; @@ -24,6 +25,7 @@ import android.os.IBinder; import android.os.Looper; import android.os.Message; import android.os.Process; +import android.preference.PreferenceManager; import android.util.Log; import android.widget.Toast; @@ -48,8 +50,7 @@ public class OPTelemetryService extends Service { // Message ids static final int MSG_START = 0; - static final int MSG_CONNECT_BT = 1; - static final int MSG_CONNECT_FAKE = 2; + static final int MSG_CONNECT = 1; static final int MSG_DISCONNECT = 3; static final int MSG_TOAST = 100; @@ -70,14 +71,22 @@ public class OPTelemetryService extends Service { Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT_BT: + case MSG_CONNECT: terminate = false; - activeTelem = new BTTelemetryThread(); - activeTelem.start(); - break; - case MSG_CONNECT_FAKE: - terminate = false; - activeTelem = new FakeTelemetryThread(); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + int connection_type = Integer.decode(prefs.getString("connection_type", "")); + switch(connection_type) { + case 0: // No connection + return; + case 1: + activeTelem = new FakeTelemetryThread(); + break; + case 2: + activeTelem = new BTTelemetryThread(); + break; + case 3: + throw new Error("Unsupported"); + } activeTelem.start(); break; case MSG_DISCONNECT: @@ -146,14 +155,9 @@ public class OPTelemetryService extends Service { public TelemTask getTelemTask(int id) { return (TelemTask) activeTelem; } - public void openFakeConnection() { + public void openConnection() { Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_FAKE; - mServiceHandler.sendMessage(msg); - } - public void openBTConnection() { - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_BT; + msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); } public void stopConnection() { @@ -161,6 +165,9 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_DISCONNECT; mServiceHandler.sendMessage(msg); } + public boolean isConnected() { + return activeTelem != null; + } }; public void toastMessage(String msgText) { diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f68e839c1..f3cc56d47 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -6,15 +6,20 @@ import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.content.Intent; +import android.content.SharedPreferences; +import android.content.SharedPreferences.OnSharedPreferenceChangeListener; import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; +import android.preference.PreferenceManager; import android.util.Log; import android.view.Menu; import android.view.MenuInflater; import android.view.MenuItem; import android.view.View; import android.view.ViewGroup; +import android.widget.Adapter; import android.widget.ArrayAdapter; import android.widget.ExpandableListAdapter; import android.widget.ExpandableListView; @@ -27,36 +32,13 @@ import android.widget.Toast; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; -public class ObjectBrowser extends ObjectManagerActivity { - - @Override - public boolean onOptionsItemSelected(MenuItem item) { - switch(item.getItemId()) { - case R.id.menu_connect: - binder.openBTConnection(); - return true; - case R.id.menu_disconnect: - binder.stopConnection(); - updateText.run(); - return true; - case R.id.menu_settings: - return true; - default: - return super.onOptionsItemSelected(item); - } - - } - - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); - inflater.inflate(R.menu.options_menu, menu); - return true; - } +public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; boolean connected; - + SharedPreferences prefs; + ArrayAdapter adapter; + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -70,6 +52,8 @@ public class ObjectBrowser extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.main); + prefs = PreferenceManager.getDefaultSharedPreferences(this); + prefs.registerOnSharedPreferenceChangeListener(this); } @Override @@ -77,6 +61,17 @@ public class ObjectBrowser extends ObjectManagerActivity { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -88,16 +83,12 @@ public class ObjectBrowser extends ObjectManagerActivity { } public void update() { - List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); - ListIterator> li = allobjects.listIterator(); - while(li.hasNext()) { - linearized.addAll(li.next()); - } - - ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); - ListView objects = (ListView) findViewById(R.id.object_list); - objects.setAdapter(adapter); + adapter.notifyDataSetChanged(); + } + public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, + String key) { + // TODO Auto-generated method stub + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 12a072de7..d91946b92 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -14,6 +14,9 @@ import android.content.ServiceConnection; import android.os.Bundle; import android.os.IBinder; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { @@ -72,6 +75,31 @@ public abstract class ObjectManagerActivity extends Activity { } + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + @Override public void onStart() { super.onStart(); diff --git a/androidgcs/src/org/openpilot/androidgcs/Preferences.java b/androidgcs/src/org/openpilot/androidgcs/Preferences.java new file mode 100644 index 000000000..913de0f73 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/Preferences.java @@ -0,0 +1,12 @@ +package org.openpilot.androidgcs; + +import android.os.Bundle; +import android.preference.PreferenceActivity; + +public class Preferences extends PreferenceActivity { + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + addPreferencesFromResource(R.xml.preferences); + } +} From fd3a02eb92ddd89d6b1faefe8c2382f1570167a1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 21 Mar 2011 18:33:47 -0500 Subject: [PATCH 080/165] More work on the object browser/editor. Hard to make it resize itself though. --- androidgcs/AndroidManifest.xml | 1 + androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 12288 -> 0 bytes .../layout/{main.xml => object_browser.xml} | 0 androidgcs/res/layout/object_edit.xml | 9 +++ .../openpilot/androidgcs/ObjectBrowser.java | 44 ++++++++------- .../openpilot/androidgcs/ObjectEditor.java | 52 ++++++++++++++++++ .../androidgcs/ObjectManagerActivity.java | 23 +++++++- 7 files changed, 108 insertions(+), 21 deletions(-) delete mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp rename androidgcs/res/layout/{main.xml => object_browser.xml} (100%) create mode 100644 androidgcs/res/layout/object_edit.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index a791d0fbb..fe8c6ae9a 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -26,6 +26,7 @@ + diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp deleted file mode 100644 index 167a072526a8207b396d71d6dd7d3e7a417cba19..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/object_browser.xml similarity index 100% rename from androidgcs/res/layout/main.xml rename to androidgcs/res/layout/object_browser.xml diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml new file mode 100644 index 000000000..62a482be9 --- /dev/null +++ b/androidgcs/res/layout/object_edit.xml @@ -0,0 +1,9 @@ + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f3cc56d47..df2d114a4 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -9,25 +9,16 @@ import java.util.Observer; import android.content.Intent; import android.content.SharedPreferences; import android.content.SharedPreferences.OnSharedPreferenceChangeListener; -import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.preference.PreferenceManager; import android.util.Log; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.View; -import android.view.ViewGroup; -import android.widget.Adapter; +import android.widget.AdapterView; import android.widget.ArrayAdapter; -import android.widget.ExpandableListAdapter; -import android.widget.ExpandableListView; import android.widget.ListView; -import android.widget.SimpleAdapter; -import android.widget.SimpleExpandableListAdapter; -import android.widget.TextView; import android.widget.Toast; +import android.widget.AdapterView.OnItemClickListener; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; @@ -38,6 +29,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref boolean connected; SharedPreferences prefs; ArrayAdapter adapter; + List allObjects; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { @@ -51,7 +43,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); } @@ -60,18 +52,32 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); + allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - linearized.addAll(li.next()); + allObjects.addAll(li.next()); } - - adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + + adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); ListView objects = (ListView) findViewById(R.id.object_list); objects.setAdapter(adapter); + objects.setOnItemClickListener(new OnItemClickListener() { + public void onItemClick(AdapterView parent, View view, + int position, long id) { + /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), + Toast.LENGTH_SHORT).show();*/ + Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); + intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); + intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); + intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); + startActivity(intent); + } + }); + + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -81,7 +87,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref }); } - + public void update() { adapter.notifyDataSetChanged(); } @@ -89,6 +95,6 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, String key) { // TODO Auto-generated method stub - + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java new file mode 100644 index 000000000..33d0e2f8e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -0,0 +1,52 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectField; + +import android.os.Bundle; +import android.widget.LinearLayout; +import android.widget.TextView; +import android.widget.Toast; + +public class ObjectEditor extends ObjectManagerActivity { + + String objectName; + int objectID; + int instID; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.object_edit); + + System.out.println("Started. Intent:" + getIntent()); + Bundle extras = getIntent().getExtras(); + if(extras != null){ + objectName = extras.getString("org.openpilot.androidgcs.ObjectName"); + objectID = extras.getInt("org.openpilot.androidgcs.ObjectId"); + instID = extras.getInt("org.openpilot.androidgcs.InstId"); + } + } + + public void onOPConnected() { + UAVObject obj = objMngr.getObject(objectID, instID); + Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); + + TextView objectName = (TextView) findViewById(R.id.object_edit_name); + objectName.setText(obj.getName()); + + LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); + List fields = obj.getFields(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + TextView fieldName = new TextView(this); + fieldName.setText(field.getName()); + fieldViewList.addView(fieldName); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index d91946b92..5027d4d24 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -21,7 +21,7 @@ import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { private final String TAG = "ObjectManagerActivity"; - private static int LOGLEVEL = 2; + private static int LOGLEVEL = 0; // private static boolean WARN = LOGLEVEL > 1; private static boolean DEBUG = LOGLEVEL > 0; @@ -106,19 +106,38 @@ public abstract class ObjectManagerActivity extends Activity { Intent intent = new Intent(this, OPTelemetryService.class); bindService(intent, mConnection, Context.BIND_AUTO_CREATE); } + + public void onBind() { + + } /** Defines callbacks for service binding, passed to bindService() */ private ServiceConnection mConnection = new ServiceConnection() { public void onServiceConnected(ComponentName arg0, IBinder service) { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); - binder = (LocalBinder) service; + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } } public void onServiceDisconnected(ComponentName name) { mBound = false; + binder = null; mConnected = false; objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); } }; } From bee57409835e2faea5b4f28bb8e3ef4d0a612ff8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:01 -0500 Subject: [PATCH 081/165] Added a simple PFD --- androidgcs/AndroidManifest.xml | 9 +- androidgcs/res/drawable-hdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-ldpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-mdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/layout/gcs_home.xml | 9 +- androidgcs/res/layout/pfd.xml | 8 + androidgcs/res/values/colors.xml | 6 + androidgcs/res/values/strings.xml | 6 + .../openpilot/androidgcs/AttitudeView.java | 89 +++++++++++ .../org/openpilot/androidgcs/CompassView.java | 139 ++++++++++++++++++ .../org/openpilot/androidgcs/HomePage.java | 9 ++ .../src/org/openpilot/androidgcs/PFD.java | 51 +++++++ 12 files changed, 318 insertions(+), 8 deletions(-) create mode 100644 androidgcs/res/drawable-hdpi/browser_icon.png create mode 100644 androidgcs/res/drawable-ldpi/browser_icon.png create mode 100644 androidgcs/res/drawable-mdpi/browser_icon.png create mode 100644 androidgcs/res/layout/pfd.xml create mode 100644 androidgcs/res/values/colors.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/AttitudeView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/CompassView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/PFD.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index fe8c6ae9a..1942146c4 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,13 +18,8 @@ - - - - - - - + + diff --git a/androidgcs/res/drawable-hdpi/browser_icon.png b/androidgcs/res/drawable-hdpi/browser_icon.png new file mode 100644 index 0000000000000000000000000000000000000000..3fcee485245922172e66bad2eb2203db14cdac39 GIT binary patch literal 456 zcmV;(0XP1MP)2!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y0000 - + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml new file mode 100644 index 000000000..191a80eb9 --- /dev/null +++ b/androidgcs/res/layout/pfd.xml @@ -0,0 +1,8 @@ + + + + + diff --git a/androidgcs/res/values/colors.xml b/androidgcs/res/values/colors.xml new file mode 100644 index 000000000..dc8eaf315 --- /dev/null +++ b/androidgcs/res/values/colors.xml @@ -0,0 +1,6 @@ + + + #F555 + #AFFF + #AFFF + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index e9b66a312..3b3a38d02 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -2,6 +2,7 @@ OpenPilot GCS Home OpenPilot Object Browser + OpenPilot PFD Settings Connect Disconnect @@ -10,4 +11,9 @@ Connection Type Bluetooth Select the connection method + Compass + N + E + S + W diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java new file mode 100644 index 000000000..24a8bf5f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -0,0 +1,89 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class AttitudeView extends View { + + public AttitudeView(Context context) { + super(context); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats) { + super(context, ats); + initAttitudeView(); + } + + protected void initAttitudeView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double roll; + public void setRoll(double roll) { + this.roll = roll; + } + private double pitch; + public void setPitch(double d) { + this.pitch = d; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + + canvas.drawLine(px,py, (int) (px+radius * Math.cos(roll)), (int) (py + radius * Math.sin(roll)), markerPaint); + canvas.drawLine(px,py, (int) (px+radius * Math.cos(pitch)), (int) (py + radius * Math.sin(pitch)), markerPaint); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/CompassView.java b/androidgcs/src/org/openpilot/androidgcs/CompassView.java new file mode 100644 index 000000000..50e4abc0a --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/CompassView.java @@ -0,0 +1,139 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class CompassView extends View { + + public CompassView(Context context) { + super(context); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats) { + super(context, ats); + initCompassView(); + } + + protected void initCompassView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + northString = r.getString(R.string.cardinal_north); + eastString = r.getString(R.string.cardinal_east); + southString = r.getString(R.string.cardinal_south); + westString = r.getString(R.string.cardinal_west); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + textHeight = (int)textPaint.measureText("yY"); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double bearing; + public void setBearing(double bearing) { + this.bearing = bearing; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + private String northString; + private String eastString; + private String southString; + private String westString; + private int textHeight; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + // Draw the background + canvas.drawCircle(px, py, radius, circlePaint); + + // Rotate our perspective so that the top is + // facing the current bearing. + canvas.save(); + canvas.rotate((float) -bearing, px, py); + + int textWidth = (int)textPaint.measureText("W"); + int cardinalX = px-textWidth/2; + int cardinalY = py-radius+textHeight; + + // Draw the marker every 15 degrees and text every 45. + for (int i = 0; i < 24; i++) { + // Draw a marker. + canvas.drawLine(px, py-radius, px, py-radius+10, markerPaint); + canvas.save(); + canvas.translate(0, textHeight); + // Draw the cardinal points + if (i % 6 == 0) { + String dirString = null; + switch (i) { + case 0 : { + dirString = northString; + int arrowY = 2*textHeight; + canvas.drawLine(px, arrowY, px-5, 3*textHeight, markerPaint); + canvas.drawLine(px, arrowY, px+5, 3*textHeight, markerPaint); + break; + } + case 6: dirString = eastString; break; + case 12: dirString = southString; break; + case 18: dirString = westString; break; + } + canvas.drawText(dirString, cardinalX, cardinalY, textPaint); + } + else if (i % 3 == 0) { + // Draw the text every alternate 45deg + String angle = String.valueOf(i*15); + float angleTextWidth = textPaint.measureText(angle); + + int angleTextX = (int)(px-angleTextWidth/2); + int angleTextY = py-radius+textHeight; + canvas.drawText(angle, angleTextX, angleTextY, textPaint); + } + canvas.restore(); + canvas.rotate(15, px, py); + } + canvas.restore(); + } +} diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 478c7cdca..7d03e1b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -12,12 +12,21 @@ public class HomePage extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); objectBrowser.setOnClickListener(new OnClickListener() { public void onClick(View arg0) { startActivity(new Intent(HomePage.this, ObjectBrowser.class)); } }); + + Button pfd = (Button) findViewById(R.id.launch_pfd); + pfd.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, PFD.class)); + } + }); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PFD.java b/androidgcs/src/org/openpilot/androidgcs/PFD.java new file mode 100644 index 000000000..e0d1b9f24 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/PFD.java @@ -0,0 +1,51 @@ +package org.openpilot.androidgcs; + +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; + +import android.os.Bundle; + +public class PFD extends ObjectManagerActivity { + + double heading; + double roll; + double pitch; + + Runnable update = new Runnable() { + public void run() { + CompassView compass = (CompassView) findViewById(R.id.compass_view); + compass.setBearing((int) heading); + compass.invalidate(); + + AttitudeView attitude = (AttitudeView) findViewById(R.id.attitude_view); + attitude.setRoll(roll / 180 * Math.PI); + attitude.setPitch(pitch / 180 * Math.PI); + attitude.invalidate(); + } + }; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.pfd); + } + + @Override + void onOPConnected() { + + UAVObject obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + heading = obj.getField("Yaw").getDouble(); + pitch = obj.getField("Pitch").getDouble(); + roll = obj.getField("Roll").getDouble(); + runOnUiThread(update); + } + }); + } +} From 0950d0386b4dcde192eaef54e8a69f2e43488ff4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:17 -0500 Subject: [PATCH 082/165] Make fake telemetry show rotating attitude. --- .../org/openpilot/androidgcs/OPTelemetryService.java | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5af7c7d60..43cc13b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -200,8 +200,19 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + double roll = 0; + double pitch = 0; + double yaw = 0; while( !terminate ) { + attitudeActual.getField("Roll").setDouble(roll); + attitudeActual.getField("Pitch").setDouble(pitch); + attitudeActual.getField("Yaw").setDouble(yaw); + roll = (roll + 10) % 180; + pitch = (pitch + 10) % 180; + yaw = (yaw + 10) % 360; systemStats.updated(); + attitudeActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { From c8c7323ab7902377f576a14635cb06b73ad17829 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 13:14:11 -0500 Subject: [PATCH 083/165] Make auto starting work. For now removed support for standalone service but easy to add back. --- .../androidgcs/OPTelemetryService.java | 43 ++++++++++++------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 43cc13b04..67ee56d4e 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -68,10 +68,10 @@ public class OPTelemetryService extends Service { public void handleMessage(Message msg) { switch(msg.arg1) { case MSG_START: - Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); - System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT: + break; + case MSG_CONNECT: + Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); int connection_type = Integer.decode(prefs.getString("connection_type", "")); @@ -90,6 +90,7 @@ public class OPTelemetryService extends Service { activeTelem.start(); break; case MSG_DISCONNECT: + Toast.makeText(getApplicationContext(), "Disconnct", Toast.LENGTH_SHORT).show(); terminate = true; try { activeTelem.join(); @@ -101,6 +102,8 @@ public class OPTelemetryService extends Service { Intent intent = new Intent(); intent.setAction(INTENT_ACTION_DISCONNECTED); sendBroadcast(intent,null); + + stopSelf(); break; case MSG_TOAST: @@ -113,9 +116,9 @@ public class OPTelemetryService extends Service { } }; - @Override - public void onCreate() { - // Low priority thread for message handling with service + public void startup() { + Toast.makeText(getApplicationContext(), "Telemetry service starting", Toast.LENGTH_SHORT).show(); + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", Process.THREAD_PRIORITY_BACKGROUND); thread.start(); @@ -123,20 +126,27 @@ public class OPTelemetryService extends Service { // Get the HandlerThread's Looper and use it for our Handler mServiceLooper = thread.getLooper(); mServiceHandler = new ServiceHandler(mServiceLooper); + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + if(prefs.getBoolean("autoconnect", false)) { + Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT; + msg.arg2 = 0; + mServiceHandler.sendMessage(msg); + } + + } + + @Override + public void onCreate() { + startup(); } @Override public int onStartCommand(Intent intent, int flags, int startId) { - Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); - - System.out.println("Start"); - // For each start request, send a message to start a job and deliver the - // start ID so we know which request we're stopping when we finish the job - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_START; - msg.arg2 = startId; - mServiceHandler.sendMessage(msg); - + // Currently only using as bound service + // If we get killed, after returning from here, restart return START_STICKY; } @@ -156,6 +166,7 @@ public class OPTelemetryService extends Service { return (TelemTask) activeTelem; } public void openConnection() { + Toast.makeText(getApplicationContext(), "Requested open connection", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); From 2139954e49d83beadc4d49be95875c6bda5aae95 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:39:44 -0500 Subject: [PATCH 084/165] Added location feature and made fake stream create movement --- androidgcs/AndroidManifest.xml | 18 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/gcs_home.xml | 1 + androidgcs/res/layout/map_layout.xml | 10 + androidgcs/res/values/strings.xml | 37 ++- .../org/openpilot/androidgcs/HomePage.java | 6 + .../androidgcs/OPTelemetryService.java | 27 ++ .../org/openpilot/androidgcs/UAVLocation.java | 273 ++++++++++++++++++ 8 files changed, 351 insertions(+), 23 deletions(-) create mode 100644 androidgcs/res/layout/map_layout.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/UAVLocation.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 1942146c4..c18dc0cb1 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -4,10 +4,14 @@ android:versionName="1.0"> + + + + @@ -16,13 +20,15 @@ - - + + - - - - + + + + + diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 66db0d159..420db56e3 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-10 +target=Google Inc.:Google APIs:8 diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index 1a5a81cd7..e07f5b003 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -11,4 +11,5 @@ android:id="@+id/launch_object_browser" android:drawableLeft="@drawable/browser_icon" android:layout_centerHorizontal="true"/> + diff --git a/androidgcs/res/layout/map_layout.xml b/androidgcs/res/layout/map_layout.xml new file mode 100644 index 000000000..64c64b16e --- /dev/null +++ b/androidgcs/res/layout/map_layout.xml @@ -0,0 +1,10 @@ + + + + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 3b3a38d02..7cef563e7 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,19 +1,24 @@ - OpenPilot GCS Home - OpenPilot Object Browser - OpenPilot PFD - Settings - Connect - Disconnect - Settings - Automatically Connect - Connection Type - Bluetooth - Select the connection method - Compass - N - E - S - W + OpenPilot GCS Home + OpenPilot Object Browser + OpenPilot PFD + OpenPilot Location + + Settings + Connect + Disconnect + + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method + + Compass + N + E + S + W + Connected diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 7d03e1b04..cf9664d14 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -27,6 +27,12 @@ public class HomePage extends ObjectManagerActivity { } }); + Button location = (Button) findViewById(R.id.launch_location); + location.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, UAVLocation.class)); + } + }); } } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 67ee56d4e..c2914f34a 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -212,18 +212,45 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + UAVDataObject homeLocation = (UAVDataObject) objMngr.getObject("HomeLocation"); + UAVDataObject positionActual = (UAVDataObject) objMngr.getObject("PositionActual"); + + homeLocation.getField("Latitude").setDouble(379420315); + homeLocation.getField("Longitude").setDouble(-88330078); + homeLocation.getField("ECEF").setDouble(497665694,0); + homeLocation.getField("ECEF").setDouble(-77336320,1); + homeLocation.getField("ECEF").setDouble(390037169,2); + homeLocation.getField("RNE").setDouble(-0.60757166,0); + homeLocation.getField("RNE").setDouble(0.09441550,1); + homeLocation.getField("RNE").setDouble(0.78863323,2); + homeLocation.getField("RNE").setDouble(0.15355512,3); + homeLocation.getField("RNE").setDouble(0.98814011,4); + homeLocation.getField("RNE").setDouble(0,5); + homeLocation.getField("RNE").setDouble(-0.77928013,6); + homeLocation.getField("RNE").setDouble(0.12109867,7); + homeLocation.getField("RNE").setDouble(-0.61486387,8); + homeLocation.getField("Be").setDouble(26702.78710938,0); + homeLocation.getField("Be").setDouble(-1468.33605957,1); + homeLocation.getField("Be").setDouble(34181.78515625,2); + + double roll = 0; double pitch = 0; double yaw = 0; + double north = 0; + double east = 0; while( !terminate ) { attitudeActual.getField("Roll").setDouble(roll); attitudeActual.getField("Pitch").setDouble(pitch); attitudeActual.getField("Yaw").setDouble(yaw); + positionActual.getField("North").setDouble(north += 100); + positionActual.getField("East").setDouble(east += 100); roll = (roll + 10) % 180; pitch = (pitch + 10) % 180; yaw = (yaw + 10) % 360; systemStats.updated(); attitudeActual.updated(); + positionActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { diff --git a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java new file mode 100644 index 000000000..72085c1d6 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java @@ -0,0 +1,273 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectManager; + +import com.google.android.maps.GeoPoint; +import com.google.android.maps.MapActivity; +import com.google.android.maps.MapController; +import com.google.android.maps.MapView; +import com.google.android.maps.Overlay; +import com.google.android.maps.Projection; + +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.graphics.Point; +import android.graphics.RectF; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; + +public class UAVLocation extends MapActivity +{ + private final String TAG = "UAVLocation"; + private static int LOGLEVEL = 0; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + private MapView mapView; + private MapController mapController; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + GeoPoint homeLocation; + GeoPoint uavLocation; + + @Override public void onCreate(Bundle icicle) { + super.onCreate(icicle); + setContentView(R.layout.map_layout); + mapView = (MapView)findViewById(R.id.map_view); + mapController = mapView.getController(); + + mapView.displayZoomControls(true); + Double lat = 37.422006*1E6; + Double lng = -122.084095*1E6; + homeLocation = new GeoPoint(lat.intValue(), lng.intValue()); + uavLocation = homeLocation; + mapController.setCenter(homeLocation); + mapController.setZoom(18); + + List overlays = mapView.getOverlays(); + UAVOverlay myOverlay = new UAVOverlay(); + overlays.add(myOverlay); + mapView.postInvalidate(); + + // ObjectManager related stuff (can't inherit standard class) + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + //@Override + protected boolean isRouteDisplayed() { + // IMPORTANT: This method must return true if your Activity // is displaying driving directions. Otherwise return false. + return false; + } + + public class UAVOverlay extends Overlay { + @Override + public void draw(Canvas canvas, MapView mapView, boolean shadow) { + + Projection projection = mapView.getProjection(); + + if (shadow == false) { + Point myPoint = new Point(); + projection.toPixels(uavLocation, myPoint); + + //// Draw UAV + // Create and setup your paint brush + Paint paint = new Paint(); + paint.setARGB(250, 255, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + int rad = 5; + RectF oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("UAV", myPoint.x+rad, myPoint.y, paint); + + //// Draw Home + myPoint = new Point(); + projection.toPixels(homeLocation, myPoint); + + // Create and setup your paint brush + paint.setARGB(250, 0, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + rad = 5; + oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("Home", myPoint.x+rad, myPoint.y, paint); + + } + } + + @Override + public boolean onTap(GeoPoint point, MapView mapView1) { + // Return true if screen tap is handled by this overlay + return false; + } + } + + void onOPConnected() { + UAVObject obj = objMngr.getObject("HomeLocation"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double lat = obj.getField("Latitude").getDouble() / 10; + Double lon = obj.getField("Longitude").getDouble() / 10; + homeLocation = new GeoPoint(lat.intValue(), lon.intValue()); + runOnUiThread(new Runnable() { + public void run() { + mapController.setCenter(homeLocation); + } + }); + System.out.println("HomeLocation: " + homeLocation.toString()); + } + }); + // Hacky - trigger an update + obj.updated(); + + obj = objMngr.getObject("PositionActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double north = obj.getField("North").getDouble(); + Double east = obj.getField("East").getDouble(); + // TODO: Correct convertion from NED to LLA. This is erroneous conversion from cm to deg + uavLocation = new GeoPoint((int) (homeLocation.getLatitudeE6() + north / 100 * 1e6 / 78847), + (int) (homeLocation.getLongitudeE6() + east / 100 * 1e6 / 78847)); + runOnUiThread(new Runnable() { + public void run() { + mapView.invalidate(); + } + }); + } + }); + + } + + void onOPDisconnected() { + + } + + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + public void onBind() { + + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + binder = null; + mConnected = false; + objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); + } + }; +} From dadcb3939621c19ce14c681486bb0541346a7155 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:59:36 -0500 Subject: [PATCH 085/165] Few tweaks and suppress some warnings --- androidgcs/default.properties | 2 +- androidgcs/res/xml/preferences.xml | 23 ++++++++++-------- .../openpilot/androidgcs/TelemetryWidget.java | 24 ++++++++++++++++++- .../uavobjects/UAVObjectsInitialize.java | 2 +- 4 files changed, 38 insertions(+), 13 deletions(-) diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 420db56e3..728f51f97 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:8 +target=Google Inc.:Google APIs:11 diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index d731f59dd..24fd43b5e 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -1,12 +1,15 @@ - - - + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index d316526ef..51afdf568 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -2,11 +2,34 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; +import android.content.ComponentName; import android.content.Context; +import android.content.Intent; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { + @Override + public void onReceive(Context context, Intent intent) { + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_CONNECTED)) { + changeStatus(context, true); + } + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_DISCONNECTED)) { + changeStatus(context, false); + } + + super.onReceive(context, intent); + } + + public void changeStatus(Context context, boolean status) { + RemoteViews updateViews = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); + updateViews.setTextViewText(R.id.telemetryWidgetStatus, "Connection status: " + status); + ComponentName thisWidget = new ComponentName(context, TelemetryWidget.class); + AppWidgetManager manager = AppWidgetManager.getInstance(context); + manager.updateAppWidget(thisWidget, updateViews); + + } + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; @@ -16,7 +39,6 @@ public class TelemetryWidget extends AppWidgetProvider { // Get the layout for the App Widget and attach an on-click listener to the button RemoteViews views = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); - //views.setOnClickPendingIntent(R.id.button, pendingIntent); // Tell the AppWidgetManager to perform an update on the current App Widget appWidgetManager.updateAppWidget(appWidgetId, views); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 4eca6ea82..d1d47aebb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,7 +28,7 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.uavobjects.*; +//import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { From b654d68ee64d6a353340f46c989821b4bcf23ec5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 23 Mar 2011 11:37:20 -0500 Subject: [PATCH 086/165] Cleaner editor interface --- androidgcs/default.properties | 2 +- androidgcs/res/layout/object_browser.xml | 3 +- androidgcs/res/layout/object_edit.xml | 6 +- androidgcs/res/layout/object_editor.xml | 6 + androidgcs/res/values/strings.xml | 3 + .../androidgcs/OPTelemetryService.java | 5 +- .../openpilot/androidgcs/ObjectBrowser.java | 3 + .../openpilot/androidgcs/ObjectEditView.java | 114 ++++++++++++++++++ .../openpilot/androidgcs/ObjectEditor.java | 12 +- 9 files changed, 138 insertions(+), 16 deletions(-) create mode 100644 androidgcs/res/layout/object_editor.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 728f51f97..fd1cedd24 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:11 +target=Google Inc.:Google APIs:10 diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 880e276ff..9c7456915 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,5 +2,6 @@ - + + diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml index 62a482be9..c161caa4c 100644 --- a/androidgcs/res/layout/object_edit.xml +++ b/androidgcs/res/layout/object_edit.xml @@ -3,7 +3,7 @@ xmlns:android="http://schemas.android.com/apk/res/android" android:layout_width="match_parent" android:layout_height="match_parent"> - - - + + + diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml new file mode 100644 index 000000000..d93b1a097 --- /dev/null +++ b/androidgcs/res/layout/object_editor.xml @@ -0,0 +1,6 @@ + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 7cef563e7..6d69e4126 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -21,4 +21,7 @@ S W Connected + Update + Save + Send diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index c2914f34a..ce90f5a48 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -74,7 +74,8 @@ public class OPTelemetryService extends Service { Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + //int connection_type = Integer.decode(prefs.getString("connection_type", "")); + int connection_type = 1; switch(connection_type) { case 0: // No connection return; @@ -128,7 +129,7 @@ public class OPTelemetryService extends Service { mServiceHandler = new ServiceHandler(mServiceLooper); SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - if(prefs.getBoolean("autoconnect", false)) { + if(prefs.getBoolean("autoconnect", false) || true) { Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index df2d114a4..a6ed177a2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -17,6 +17,7 @@ import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; import android.widget.ListView; +import android.widget.Spinner; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -46,6 +47,8 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); + + Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java new file mode 100644 index 000000000..7b81ff18c --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -0,0 +1,114 @@ +package org.openpilot.androidgcs; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectField; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.EditText; +import android.widget.LinearLayout; +import android.widget.TextView; + +public class ObjectEditView extends LinearLayout { + + TextView objectName; + List fields; + + public ObjectEditView(Context context) { + super(context); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats) { + super(context, ats); + initObjectEditView(); + } + + public void initObjectEditView() { + // Set orientation of layout to vertical + setOrientation(LinearLayout.VERTICAL); + + objectName = new TextView(getContext()); + objectName.setText(""); + objectName.setTextSize(14); + + // Lay them out in the compound control. + int lHeight = LayoutParams.WRAP_CONTENT; + int lWidth = LayoutParams.FILL_PARENT; + addView(objectName, new LinearLayout.LayoutParams(lWidth, lHeight)); + + fields = new ArrayList(); + } + + public void setName(String name) { + objectName.setText(name); + } + + public void addField(UAVObjectField field) { + if(field.getNumElements() == 1) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble()).toString()); + } else { + fieldView.setValue(field.getValue().toString()); + } + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + } + else { + ListIterator names = field.getElementNames().listIterator(); + int i = 0; + while(names.hasNext()) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName() + "-" + names.next()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble(i)).toString()); + } else { + fieldView.setValue(field.getValue(i).toString()); + } + i++; + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + + } + } + } + + public class FieldValue extends LinearLayout { + + TextView fieldName; + EditText fieldValue; + + public FieldValue(Context context) { + super(context); + setOrientation(LinearLayout.HORIZONTAL); + + fieldName = new TextView(getContext()); + fieldValue = new EditText(getContext()); + + // Lay them out in the compound control. + addView(fieldName, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + fieldValue.setWidth(300); + addView(fieldValue, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + } + + public void setName(String name) { + fieldName.setText(name); + } + + public void setValue(String value) { + fieldValue.setText(value); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java index 33d0e2f8e..afbddb5e5 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -7,8 +7,6 @@ import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectField; import android.os.Bundle; -import android.widget.LinearLayout; -import android.widget.TextView; import android.widget.Toast; public class ObjectEditor extends ObjectManagerActivity { @@ -35,17 +33,13 @@ public class ObjectEditor extends ObjectManagerActivity { UAVObject obj = objMngr.getObject(objectID, instID); Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); - TextView objectName = (TextView) findViewById(R.id.object_edit_name); - objectName.setText(obj.getName()); + ObjectEditView editView = (ObjectEditView) findViewById(R.id.object_edit_view); + editView.setName(obj.getName()); - LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); List fields = obj.getFields(); ListIterator li = fields.listIterator(); while(li.hasNext()) { - UAVObjectField field = li.next(); - TextView fieldName = new TextView(this); - fieldName.setText(field.getName()); - fieldViewList.addView(fieldName); + editView.addField(li.next()); } } From 723bcddc110c252cc5024ed8fbc59910cccf472b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 17:07:27 -0600 Subject: [PATCH 087/165] Update the project and checked in the meta data. Hopefully this will make it run more easily in future. --- androidgcs/.classpath | 8 +- androidgcs/.metadata/.lock | 0 androidgcs/.metadata/.log | 83 ++++ .../.metadata/.mylyn/repositories.xml.zip | Bin 0 -> 403 bytes androidgcs/.metadata/.mylyn/tasks.xml.zip | Bin 0 -> 250 bytes .../.plugins/org.eclipse.cdt.core/.log | 1 + .../.root/.indexes/history.version | 1 + .../.root/.indexes/properties.index | Bin 0 -> 57 bytes .../.root/.indexes/properties.version | 1 + .../org.eclipse.core.resources/.root/2.tree | Bin 0 -> 149 bytes .../.safetable/org.eclipse.core.resources | Bin 0 -> 614 bytes .../.settings/org.eclipse.cdt.ui.prefs | 5 + .../org.eclipse.core.resources.prefs | 3 + .../org.eclipse.epp.usagedata.recording.prefs | 3 + .../.settings/org.eclipse.jdt.ui.prefs | 15 + .../org.eclipse.mylyn.context.core.prefs | 3 + .../.settings/org.eclipse.team.cvs.ui.prefs | 3 + .../.settings/org.eclipse.team.ui.prefs | 3 + .../.settings/org.eclipse.ui.editors.prefs | 3 + .../.settings/org.eclipse.ui.ide.prefs | 5 + .../.settings/org.eclipse.ui.prefs | 3 + .../.settings/org.eclipse.ui.workbench.prefs | 3 + .../upload0.csv | 251 +++++++++++++ .../usagedata.csv | 83 ++++ .../org.eclipse.jdt.core/nonChainingJarsCache | Bin 0 -> 4 bytes .../variablesAndContainers.dat | Bin 0 -> 96 bytes .../org.eclipse.jdt.ui/OpenTypeHistory.xml | 2 + .../QualifiedTypeNameHistory.xml | 2 + .../org.eclipse.jdt.ui/dialog_settings.xml | 10 + .../org.eclipse.ui.ide/dialog_settings.xml | 9 + .../org.eclipse.ui.intro/dialog_settings.xml | 4 + .../dialog_settings.xml | 5 + .../org.eclipse.ui.workbench/workbench.xml | 355 ++++++++++++++++++ .../org.eclipse.ui.workbench/workingsets.xml | 4 + androidgcs/.metadata/version.ini | 1 + .../.settings/org.eclipse.jdt.core.prefs | 11 +- androidgcs/lint.xml | 3 + ...{default.properties => project.properties} | 4 +- 38 files changed, 879 insertions(+), 8 deletions(-) create mode 100644 androidgcs/.metadata/.lock create mode 100644 androidgcs/.metadata/.log create mode 100644 androidgcs/.metadata/.mylyn/repositories.xml.zip create mode 100644 androidgcs/.metadata/.mylyn/tasks.xml.zip create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/2.tree create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml create mode 100644 androidgcs/.metadata/version.ini create mode 100644 androidgcs/lint.xml rename androidgcs/{default.properties => project.properties} (72%) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 6f3f456df..eb33e4360 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,9 +1,9 @@ + - - - - + + + diff --git a/androidgcs/.metadata/.lock b/androidgcs/.metadata/.lock new file mode 100644 index 000000000..e69de29bb diff --git a/androidgcs/.metadata/.log b/androidgcs/.metadata/.log new file mode 100644 index 000000000..8955f7bbc --- /dev/null +++ b/androidgcs/.metadata/.log @@ -0,0 +1,83 @@ +!SESSION 2012-02-04 14:21:36.086 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 14:21:41.864 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences + +!ENTRY org.eclipse.ui.intro.universal 4 0 2012-02-04 14:21:44.892 +!MESSAGE /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) +!STACK 0 +java.io.FileNotFoundException: /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) + at java.io.FileInputStream.open(Native Method) + at java.io.FileInputStream.(FileInputStream.java:120) + at java.io.FileInputStream.(FileInputStream.java:79) + at sun.net.www.protocol.file.FileURLConnection.connect(FileURLConnection.java:70) + at sun.net.www.protocol.file.FileURLConnection.getInputStream(FileURLConnection.java:161) + at com.sun.org.apache.xerces.internal.impl.XMLEntityManager.setupCurrentEntity(XMLEntityManager.java:653) + at com.sun.org.apache.xerces.internal.impl.XMLVersionDetector.determineDocVersion(XMLVersionDetector.java:186) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:772) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:737) + at com.sun.org.apache.xerces.internal.parsers.XMLParser.parse(XMLParser.java:119) + at com.sun.org.apache.xerces.internal.parsers.DOMParser.parse(DOMParser.java:235) + at com.sun.org.apache.xerces.internal.jaxp.DocumentBuilderImpl.parse(DocumentBuilderImpl.java:284) + at javax.xml.parsers.DocumentBuilder.parse(DocumentBuilder.java:180) + at org.eclipse.ui.internal.intro.universal.IntroData.parse(IntroData.java:159) + at org.eclipse.ui.internal.intro.universal.IntroData.initialize(IntroData.java:63) + at org.eclipse.ui.internal.intro.universal.IntroData.(IntroData.java:47) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.loadData(CustomizationContentsArea.java:624) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.addPages(CustomizationContentsArea.java:489) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.createContents(CustomizationContentsArea.java:453) + at org.eclipse.ui.internal.intro.universal.CustomizationDialog.createDialogArea(CustomizationDialog.java:44) + at org.eclipse.jface.dialogs.Dialog.createContents(Dialog.java:760) + at org.eclipse.jface.window.Window.create(Window.java:431) + at org.eclipse.jface.dialogs.Dialog.create(Dialog.java:1089) + at org.eclipse.jface.window.Window.open(Window.java:790) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:35) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:29) + at org.eclipse.jface.action.Action.runWithEvent(Action.java:498) + at org.eclipse.jface.action.ActionContributionItem.handleWidgetSelection(ActionContributionItem.java:584) + at org.eclipse.jface.action.ActionContributionItem.access$2(ActionContributionItem.java:501) + at org.eclipse.jface.action.ActionContributionItem$6.handleEvent(ActionContributionItem.java:452) + at org.eclipse.swt.widgets.EventTable.sendEvent(EventTable.java:84) + at org.eclipse.swt.widgets.Display.sendEvent(Display.java:3543) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1250) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1273) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1258) + at org.eclipse.swt.widgets.Widget.notifyListeners(Widget.java:1079) + at org.eclipse.swt.widgets.Display.runDeferredEvents(Display.java:3441) + at org.eclipse.swt.widgets.Display.readAndDispatch(Display.java:3100) + at org.eclipse.ui.internal.Workbench.runEventLoop(Workbench.java:2405) + at org.eclipse.ui.internal.Workbench.runUI(Workbench.java:2369) + at org.eclipse.ui.internal.Workbench.access$4(Workbench.java:2221) + at org.eclipse.ui.internal.Workbench$5.run(Workbench.java:500) + at org.eclipse.core.databinding.observable.Realm.runWithDefault(Realm.java:332) + at org.eclipse.ui.internal.Workbench.createAndRunWorkbench(Workbench.java:493) + at org.eclipse.ui.PlatformUI.createAndRunWorkbench(PlatformUI.java:149) + at org.eclipse.ui.internal.ide.application.IDEApplication.start(IDEApplication.java:113) + at org.eclipse.equinox.internal.app.EclipseAppHandle.run(EclipseAppHandle.java:194) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.runApplication(EclipseAppLauncher.java:110) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.start(EclipseAppLauncher.java:79) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:368) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:179) + at sun.reflect.NativeMethodAccessorImpl.invoke0(Native Method) + at sun.reflect.NativeMethodAccessorImpl.invoke(NativeMethodAccessorImpl.java:39) + at sun.reflect.DelegatingMethodAccessorImpl.invoke(DelegatingMethodAccessorImpl.java:25) + at java.lang.reflect.Method.invoke(Method.java:597) + at org.eclipse.equinox.launcher.Main.invokeFramework(Main.java:559) + at org.eclipse.equinox.launcher.Main.basicRun(Main.java:514) + at org.eclipse.equinox.launcher.Main.run(Main.java:1311) +!SESSION 2012-02-04 15:23:30.048 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 15:23:34.575 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences diff --git a/androidgcs/.metadata/.mylyn/repositories.xml.zip b/androidgcs/.metadata/.mylyn/repositories.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..e4df3bd3582f499f1a60b5def214b8ff52af6617 GIT binary patch literal 403 zcmWIWW@Zs#-~hsBMJ^5uNI(F{E=n!PFU~Bdj(; zVVO}bA}k9RU9H|_{jM!-va0dQyZ@?^bz^fywc_@+7(B7PS7R*c8`dl8&6Bbx*kFpf z!UfTNChLMenCzB(Vj$U{HcO2EMwQWWeBm$C<8L3AOn9FDyjhXMjCb8$XV&SwY{4(ytny2L z>Zr1KZsz5i=REypu2G!!Fu39-+x}N6Dmous-A{8_xY)$`S9N}$_2O##r|q}OnXHQb zs!#4`+gH4ys;~2NX}{PedAH=+g>TFBZddPTZ;$@K|4-sWx%33i%5DEskL3q=vvV9^ w68pi($iR@z%)k)f&B!FefCxZjIZyzi0`%Yv@MdKLsbB;`J0NWjG?jq?0GoN09smFU literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.mylyn/tasks.xml.zip b/androidgcs/.metadata/.mylyn/tasks.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..2c8620af394508c77be5ef0f6f867a56804938c0 GIT binary patch literal 250 zcmWIWW@Zs#-~dAIY8M9vB)|h?mn0Tv=VTU_=vCzAY~Hy3#MwX%Z(Xf(XU=a9HM(LP z5ae;z`<(yDGv3=nxp)gNZw(02(DOXw?RnEr%s1&+P<07Q|H{blRA2V9L+CH zm|nGXSgTK4vh2Bds8$6-=~ITSEzeY)TZ~o*1y2$ABUEh2^7U=bm&CMNj0^$Z>>R?m rvc?5KcT54|0B=Sn5e9@?k>x;cMFq$%5AbGX1IaQ1p%su`1y%|G7vM-E literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log new file mode 100644 index 000000000..bce672614 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log @@ -0,0 +1 @@ +*** SESSION Feb 04, 2012 14:21:39.72 ------------------------------------------- diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version new file mode 100644 index 000000000..25cb955ba --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version @@ -0,0 +1 @@ + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index new file mode 100644 index 0000000000000000000000000000000000000000..9c245ea2cfab3511d0f8b7802966a5b2bb67b287 GIT binary patch literal 57 zcmZQ%U|?WmVAN+|WMUA>FG|--P0q4Yy oITE#s5Hp-2#a#t%!FeA{J(nSSiHf?N|MotxHB4MgVOxlqE}m~5?f?J) literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources new file mode 100644 index 0000000000000000000000000000000000000000..f783b188fb03e942944121a16ffc8983afa430df GIT binary patch literal 614 zcmZ?R*xjhShe1S2b=vdAllRFf=Oz}Hq!uZZBqrsgaw!KVmMFNTCMg)0C>WYr8JPf) zf^%?)f{}rt5m$0fYGRQ~YEDUFe11{7UTShqWs%=_gPH`$%3P^!# zML}j!Vo7Fx9*WW|m{LPyBMW0o12Z!d14Bc+THvNbwU}6#8UwZ9a0}c5h+A-|%B{?) w%+o7LEY2?0E6s$uTVJoFC^gmAi0eSa@6X^M3jEwty}SIF!)TDD>X8;?0Hs9PH2?qr literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs new file mode 100644 index 000000000..3f144b036 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +spelling_locale_initialized=true +useAnnotationsPrefPage=true +eclipse.preferences.version=1 +useQuickDiffPrefPage=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs new file mode 100644 index 000000000..360fc96b9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +version=1 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs new file mode 100644 index 000000000..87706c344 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:44 CST 2012 +org.eclipse.epp.usagedata.recording.last-upload=1328386904231 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs new file mode 100644 index 000000000..bdcfb11b5 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs @@ -0,0 +1,15 @@ +#Sat Feb 04 15:21:25 CST 2012 +useQuickDiffPrefPage=true +proposalOrderMigrated=true +tabWidthPropagated=true +content_assist_proposals_background=255,255,255 +org.eclipse.jdt.ui.javadoclocations.migrated=true +useAnnotationsPrefPage=true +org.eclipse.jface.textfont=1|Monaco|11.0|0|COCOA|1|; +org.eclipse.jdt.internal.ui.navigator.layout=2 +org.eclipse.jdt.ui.editor.tab.width= +org.eclipse.jdt.ui.formatterprofiles.version=11 +spelling_locale_initialized=true +eclipse.preferences.version=1 +content_assist_proposals_foreground=0,0,0 +fontPropagated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs new file mode 100644 index 000000000..7ea301b2d --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +mylyn.attention.migrated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs new file mode 100644 index 000000000..62dee9f90 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +pref_first_startup=false +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs new file mode 100644 index 000000000..06b301613 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +org.eclipse.team.ui.first_time=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs new file mode 100644 index 000000000..90e1e2da9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +overviewRuler_migration=migrated_3.1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs new file mode 100644 index 000000000..b945f2889 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +tipsAndTricks=true +platformState=1328386704250 +PROBLEMS_FILTERS_MIGRATE=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs new file mode 100644 index 000000000..a97c1c1ab --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +showIntro=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs new file mode 100644 index 000000000..005c5e9bc --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +ENABLED_DECORATORS=com.android.ide.eclipse.adt.project.FolderDecorator\:true,org.eclipse.cdt.ui.indexedFiles\:false,org.eclipse.jdt.ui.override.decorator\:true,org.eclipse.jdt.ui.interface.decorator\:false,org.eclipse.jdt.ui.buildpath.decorator\:true,org.eclipse.mylyn.context.ui.decorator.interest\:true,org.eclipse.mylyn.tasks.ui.decorators.task\:true,org.eclipse.mylyn.team.ui.changeset.decorator\:true,org.eclipse.team.cvs.ui.decorator\:true,org.eclipse.ui.LinkedResourceDecorator\:true,org.eclipse.ui.ContentTypeDecorator\:true, diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv new file mode 100644 index 000000000..bc6540615 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv @@ -0,0 +1,251 @@ +what,kind,bundleId,bundleVersion,description,time +activated,perspective,org.eclipse.cdt.ui,,"org.eclipse.cdt.ui.CPerspective",1328386903139 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328386903141 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328386903142 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328386903143 +started,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328386903143 +started,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328386903144 +started,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328386903147 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328386903148 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328386903148 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328386903149 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328386903149 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328386903150 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328386903151 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328386903152 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328386903153 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328386903153 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328386903154 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328386903154 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328386903155 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328386903155 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328386903156 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328386903157 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328386903158 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328386903159 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328386903161 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328386903164 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328386903165 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328386903166 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328386903167 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328386903168 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328386903168 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328386903169 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328386903169 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328386903171 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328386903171 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328386903172 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328386903172 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328386903172 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328386903175 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328386903176 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328386903177 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328386903177 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328386903178 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328386903179 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328386903179 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328386903180 +started,bundle,org.eclipse.ltk.core.refactoring,3.5.0.v20090513-2000,"org.eclipse.ltk.core.refactoring",1328386903180 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328386903181 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328386903181 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328386903182 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328386903183 +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328386903183 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328386903184 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328386903185 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328386903186 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328386903186 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328386903187 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328386903188 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328386903189 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328386903189 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328386903191 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328386903191 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328386903195 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328386903196 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328386903198 +started,bundle,org.eclipse.ui.intro,3.3.2.v20100111_35x,"org.eclipse.ui.intro",1328386903198 +started,bundle,org.eclipse.ui.intro.universal,3.2.300.v20090526,"org.eclipse.ui.intro.universal",1328386903198 +started,bundle,org.eclipse.ui.navigator,3.4.2.M20100120-0800,"org.eclipse.ui.navigator",1328386903199 +started,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328386903200 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328386903200 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328386903201 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328386903202 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328386903203 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328386903207 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328386903209 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328386903210 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328386903211 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328386903212 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328386903218 +os,sysinfo,,,"macosx",1328386903226 +arch,sysinfo,,,"x86_64",1328386903226 +ws,sysinfo,,,"cocoa",1328386903226 +locale,sysinfo,,,"en_US",1328386903226 +processors,sysinfo,,,"4",1328386903226 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328386903226 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328386903227 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328386903227 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.specification.version,sysinfo,,,"1.6",1328386903227 +java.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.version,sysinfo,,,"1.6.0_29",1328386903227 +java.vm.info,sysinfo,,,"mixed mode",1328386903227 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328386903227 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328386903227 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.vm.specification.version,sysinfo,,,"1.0",1328386903227 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.vm.version,sysinfo,,,"20.4-b02-402",1328386903227 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328386903389 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328386903414 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328386903450 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328386903464 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386903480 +activated,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386903487 +error,log,,,"/Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory)",1328386904897 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386905209 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386906797 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328386912464 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912583 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912596 +closed,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386912607 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328386912856 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328386912895 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386920116 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387108087 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387114332 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387670491 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387680147 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389984496 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389985341 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390196855 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390210754 +started,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390214192 +started,bundle,org.eclipse.wst.sse.core,1.1.402.v201001251516,"org.eclipse.wst.sse.core",1328390214246 +started,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390214248 +started,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390214467 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390455517 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390462855 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390470613 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.PackageExplorer",1328390470944 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390471037 +opened,view,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui.views.tasks",1328390471127 +activated,perspective,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavaPerspective",1328390471151 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390471175 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474490 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474500 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475141 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475161 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390475451 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390475842 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390485206 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390485703 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390485705 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390485706 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390485707 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390485707 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390485708 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390485709 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390485709 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390485710 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390485710 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390485712 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390485713 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390485714 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.tasks.bugs,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.bugs",1328390485717 +stopped,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390485719 +stopped,bundle,org.eclipse.ant.ui,3.4.2.v20091204_r352,"org.eclipse.ant.ui",1328390485719 +stopped,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390485719 +stopped,bundle,org.eclipse.jdt.junit,3.5.2.r352_v20100113-0800,"org.eclipse.jdt.junit",1328390485720 +stopped,bundle,org.eclipse.jdt.debug.ui,3.4.1.v20090811_r351,"org.eclipse.jdt.debug.ui",1328390485721 +stopped,bundle,org.eclipse.jdt.apt.ui,3.3.200.v20090930-2100_R35x,"org.eclipse.jdt.apt.ui",1328390485722 +stopped,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390485726 +stopped,bundle,org.eclipse.wst.dtd.ui,1.0.400.v200904300717,"org.eclipse.wst.dtd.ui",1328390485730 +stopped,bundle,org.eclipse.wst.xsd.ui,1.2.204.v200909021537,"org.eclipse.wst.xsd.ui",1328390485747 +stopped,bundle,org.eclipse.wst.xml.ui,1.1.2.v201001222130,"org.eclipse.wst.xml.ui",1328390485747 +stopped,bundle,org.eclipse.wst.common.ui,1.1.402.v200901262305,"org.eclipse.wst.common.ui",1328390485748 +stopped,bundle,org.eclipse.wst.sse.ui,1.1.102.v200910200227,"org.eclipse.wst.sse.ui",1328390485749 +stopped,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390485750 +stopped,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390485750 +stopped,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390485751 +stopped,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390485751 +stopped,bundle,org.eclipse.compare,3.5.2.r35x_20100113-0800,"org.eclipse.compare",1328390485752 +stopped,bundle,org.eclipse.ui.externaltools,3.2.0.v20090504,"org.eclipse.ui.externaltools",1328390485753 +stopped,bundle,org.eclipse.debug.ui,3.5.2.v20091028_r352,"org.eclipse.debug.ui",1328390485756 +stopped,bundle,org.eclipse.mylyn.wikitext.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.ui",1328390485757 +stopped,bundle,com.android.ide.eclipse.hierarchyviewer,10.0.1.v201103111512-110841,"com.android.ide.eclipse.hierarchyviewer",1328390485757 +stopped,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390485757 +stopped,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390485757 +stopped,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390485757 +stopped,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390485758 +stopped,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328390485758 +activated,perspective,org.eclipse.jdt.ui,,"org.eclipse.jdt.ui.JavaPerspective",1328390616647 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328390616648 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328390616653 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328390616654 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328390616654 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328390616655 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328390616656 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328390616656 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328390616656 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328390616657 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328390616658 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328390616660 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328390616660 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328390616661 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328390616662 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328390616663 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328390616663 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328390616664 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328390616668 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328390616676 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328390616676 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328390616677 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328390616679 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328390616680 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328390616681 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328390616682 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328390616688 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328390616689 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328390616690 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328390616691 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328390616692 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328390616692 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328390616693 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328390616693 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328390616694 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328390616695 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328390616695 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328390616696 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328390616697 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328390616697 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328390616698 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328390616698 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328390616699 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390616706 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328390616706 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390616707 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv new file mode 100644 index 000000000..510c72478 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv @@ -0,0 +1,83 @@ +what,kind,bundleId,bundleVersion,description,time +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328390616707 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390616708 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328390616708 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390616709 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390616710 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390616711 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328390616712 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328390616712 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390616713 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390616714 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328390616715 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390616716 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390616717 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328390616717 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328390616718 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328390616719 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328390616720 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328390616720 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328390616721 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328390616722 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328390616722 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328390616723 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328390616724 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328390616725 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390616730 +os,sysinfo,,,"macosx",1328390616740 +arch,sysinfo,,,"x86_64",1328390616740 +ws,sysinfo,,,"cocoa",1328390616740 +locale,sysinfo,,,"en_US",1328390616740 +processors,sysinfo,,,"4",1328390616740 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328390616740 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328390616740 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328390616740 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.specification.version,sysinfo,,,"1.6",1328390616740 +java.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.version,sysinfo,,,"1.6.0_29",1328390616740 +java.vm.info,sysinfo,,,"mixed mode",1328390616740 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328390616740 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328390616740 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.vm.specification.version,sysinfo,,,"1.0",1328390616740 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.vm.version,sysinfo,,,"20.4-b02-402",1328390616740 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328390616768 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328390616783 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328390616808 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328390616820 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390619481 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328390623001 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328390623371 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328390623409 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328390630622 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390659248 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.file.import",1328390659277 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390663881 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390664441 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390664444 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390664445 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390664447 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390664448 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390664449 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390664452 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390664453 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390664454 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390664455 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390664455 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390664458 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390664459 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390664462 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390664462 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache new file mode 100644 index 0000000000000000000000000000000000000000..593f4708db84ac8fd0f5cc47c634f38c013fe9e4 GIT binary patch literal 4 LcmZQzU|;|M00aO5 literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat new file mode 100644 index 0000000000000000000000000000000000000000..3aea61cb8e5c86745251f85e5305774c8841c019 GIT binary patch literal 96 zcmZQzU|?c^09G)??iJ)39~|V&2;?y`aCwFLd4|M$`1`to1eh4Oq0&MA{vjX{W(KeZ SA5SL`kA;B`q5)_CL=yl}T@PLW literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml new file mode 100644 index 000000000..a4ee3cbc9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml new file mode 100644 index 000000000..9e390f501 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml new file mode 100644 index 000000000..8bc608925 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml @@ -0,0 +1,10 @@ + +
+
+ + + + + +
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml new file mode 100644 index 000000000..ab9bf177c --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml @@ -0,0 +1,9 @@ + +
+
+ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml new file mode 100644 index 000000000..f118f0213 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml @@ -0,0 +1,4 @@ + +
+ +
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml new file mode 100644 index 000000000..5b583c4be --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml @@ -0,0 +1,5 @@ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml new file mode 100644 index 000000000..931fd0157 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml @@ -0,0 +1,355 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml new file mode 100644 index 000000000..8daaf65a1 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/version.ini b/androidgcs/.metadata/version.ini new file mode 100644 index 000000000..c51ff745b --- /dev/null +++ b/androidgcs/.metadata/version.ini @@ -0,0 +1 @@ +org.eclipse.core.runtime=1 \ No newline at end of file diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs index f3fe4d6d6..a149e8e84 100644 --- a/androidgcs/.settings/org.eclipse.jdt.core.prefs +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -1,5 +1,12 @@ -#Tue Mar 01 01:16:25 CST 2011 +#Sat Feb 04 16:05:48 CST 2012 eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.inlineJsrBytecode=enabled org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 -org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.codegen.unusedLocal=preserve +org.eclipse.jdt.core.compiler.compliance=1.6 +org.eclipse.jdt.core.compiler.debug.lineNumber=generate +org.eclipse.jdt.core.compiler.debug.localVariable=generate +org.eclipse.jdt.core.compiler.debug.sourceFile=generate +org.eclipse.jdt.core.compiler.problem.assertIdentifier=error +org.eclipse.jdt.core.compiler.problem.enumIdentifier=error org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/lint.xml b/androidgcs/lint.xml new file mode 100644 index 000000000..ee0eead5b --- /dev/null +++ b/androidgcs/lint.xml @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/project.properties similarity index 72% rename from androidgcs/default.properties rename to androidgcs/project.properties index fd1cedd24..5d85d779c 100644 --- a/androidgcs/default.properties +++ b/androidgcs/project.properties @@ -4,8 +4,8 @@ # This file must be checked in Version Control Systems. # # To customize properties used by the Ant build system use, -# "build.properties", and override values to adapt the script to your +# "ant.properties", and override values to adapt the script to your # project structure. # Project target. -target=Google Inc.:Google APIs:10 +target=Google Inc.:Google APIs:13 From e1ba3d2e6311182491d3667c5cd456421ad9ef6a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 18:30:04 -0600 Subject: [PATCH 088/165] Update the UAVObjects to the version on next. At some point a make script should generate these and copy from build/uavobjects-synth/java to this directory automatically. Also make sure java objects use CamelCase --- .../uavtalk/uavobjects/AHRSCalibration.java | 51 +- .../uavtalk/uavobjects/AHRSSettings.java | 32 +- .../uavtalk/uavobjects/AccessoryDesired.java | 139 +++++ .../uavtalk/uavobjects/ActuatorCommand.java | 12 +- .../uavtalk/uavobjects/ActuatorDesired.java | 2 +- .../uavtalk/uavobjects/ActuatorSettings.java | 496 ++++++++++-------- .../uavtalk/uavobjects/AhrsStatus.java | 10 +- .../uavtalk/uavobjects/AttitudeActual.java | 4 +- .../uavtalk/uavobjects/AttitudeRaw.java | 24 +- .../uavtalk/uavobjects/AttitudeSettings.java | 68 ++- .../uavtalk/uavobjects/BaroAltitude.java | 2 +- .../uavtalk/uavobjects/CameraDesired.java | 147 ++++++ .../uavobjects/CameraStabSettings.java | 205 ++++++++ ...emetrySettings.java => FaultSettings.java} | 45 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 97 +--- .../uavobjects/FlightBatterySettings.java | 177 +++++++ .../uavobjects/FlightBatteryState.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavobjects/FlightPlanSettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 35 +- .../uavtalk/uavobjects/FlightStatus.java | 155 ++++++ .../uavobjects/FlightTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GCSReceiver.java | 144 +++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GPSPosition.java | 28 +- .../uavtalk/uavobjects/GPSSatellites.java | 48 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 10 +- .../uavtalk/uavobjects/GuidanceSettings.java | 76 +-- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 291 ++++++++++ .../uavtalk/uavobjects/I2CStats.java | 34 +- .../uavobjects/ManualControlCommand.java | 55 +- .../uavobjects/ManualControlSettings.java | 313 +++++------ .../uavtalk/uavobjects/MixerSettings.java | 161 +++++- .../uavtalk/uavobjects/MixerStatus.java | 2 +- .../uavtalk/uavobjects/NedAccel.java | 2 +- .../uavtalk/uavobjects/ObjectPersistence.java | 23 +- .../uavtalk/uavobjects/PositionActual.java | 2 +- .../uavtalk/uavobjects/PositionDesired.java | 2 +- .../uavtalk/uavobjects/RateDesired.java | 2 +- ...erySettings.java => ReceiverActivity.java} | 74 ++- .../uavtalk/uavobjects/SonarAltitude.java | 2 +- .../uavobjects/StabilizationDesired.java | 4 +- .../uavobjects/StabilizationSettings.java | 119 +++-- .../uavtalk/uavobjects/SystemAlarms.java | 8 +- .../uavtalk/uavobjects/SystemSettings.java | 9 +- .../uavtalk/uavobjects/SystemStats.java | 6 +- .../uavtalk/uavobjects/TaskInfo.java | 24 +- .../uavobjects/UAVObjectsInitialize.java | 13 +- .../uavtalk/uavobjects/VelocityActual.java | 2 +- .../uavtalk/uavobjects/VelocityDesired.java | 2 +- .../uavtalk/uavobjects/WatchdogStatus.java | 2 +- .../java/uavobjectgeneratorjava.cpp | 2 +- 53 files changed, 2363 insertions(+), 867 deletions(-) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{TelemetrySettings.java => FaultSettings.java} (74%) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{BatterySettings.java => ReceiverActivity.java} (61%) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index 922582398..47d42991e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -51,30 +51,29 @@ public class AHRSCalibration extends UAVDataObject { List fields = new ArrayList(); - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - List accel_biasElemNames = new ArrayList(); accel_biasElemNames.add("X"); accel_biasElemNames.add("Y"); accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); List accel_scaleElemNames = new ArrayList(); accel_scaleElemNames.add("X"); accel_scaleElemNames.add("Y"); accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_orthoElemNames = new ArrayList(); + accel_orthoElemNames.add("XY"); + accel_orthoElemNames.add("XZ"); + accel_orthoElemNames.add("YZ"); + fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); List accel_varElemNames = new ArrayList(); accel_varElemNames.add("X"); accel_varElemNames.add("Y"); accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); List gyro_biasElemNames = new ArrayList(); gyro_biasElemNames.add("X"); @@ -126,6 +125,13 @@ public class AHRSCalibration extends UAVDataObject { pos_varElemNames.add("0"); fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -171,19 +177,21 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); getField("accel_scale").setValue(0.0359,0); getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(-0.0359,2); + getField("accel_scale").setValue(0.0359,2); + getField("accel_ortho").setValue(0,0); + getField("accel_ortho").setValue(0,1); + getField("accel_ortho").setValue(0,2); getField("accel_var").setValue(0.0005,0); getField("accel_var").setValue(0.0005,1); getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(23,0); - getField("gyro_bias").setValue(-23,1); - getField("gyro_bias").setValue(23,2); + getField("gyro_bias").setValue(28,0); + getField("gyro_bias").setValue(-28,1); + getField("gyro_bias").setValue(28,2); getField("gyro_scale").setValue(-0.017,0); getField("gyro_scale").setValue(0.017,1); getField("gyro_scale").setValue(-0.017,2); @@ -196,14 +204,15 @@ public class AHRSCalibration extends UAVDataObject { getField("mag_bias").setValue(0,0); getField("mag_bias").setValue(0,1); getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(-2,0); - getField("mag_scale").setValue(-2,1); - getField("mag_scale").setValue(-2,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); getField("mag_var").setValue(50,0); getField("mag_var").setValue(50,1); getField("mag_var").setValue(50,2); - getField("vel_var").setValue(0.4); - getField("pos_var").setValue(0.4); + getField("vel_var").setValue(10); + getField("pos_var").setValue(0.04); + getField("measure_var").setValue("SET"); } @@ -232,7 +241,7 @@ public class AHRSCalibration extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30101BB2; + protected static final int OBJID = 0xFD0EDFC4; protected static final String NAME = "AHRSCalibration"; protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index c49c04778..032dae775 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -51,6 +51,18 @@ public class AHRSSettings extends UAVDataObject { List fields = new ArrayList(); + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + List AlgorithmElemNames = new ArrayList(); AlgorithmElemNames.add("0"); List AlgorithmEnumOptions = new ArrayList(); @@ -75,18 +87,6 @@ public class AHRSSettings extends UAVDataObject { BiasCorrectedRawEnumOptions.add("FALSE"); fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -132,13 +132,13 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); getField("BiasCorrectedRaw").setValue("TRUE"); - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); } @@ -167,7 +167,7 @@ public class AHRSSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDEFC5548; + protected static final int OBJID = 0xF8591ED8; protected static final String NAME = "AHRSSettings"; protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java new file mode 100644 index 000000000..13c63dfdd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + +generated from accessorydesired.xml + **/ +public class AccessoryDesired extends UAVDataObject { + + public AccessoryDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccessoryValElemNames = new ArrayList(); + AccessoryValElemNames.add("0"); + fields.add( new UAVObjectField("AccessoryVal", "", UAVObjectField.FieldType.FLOAT32, AccessoryValElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AccessoryDesired obj = new AccessoryDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AccessoryDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AccessoryDesired)(objMngr.getObject(AccessoryDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xC409985A; + protected static final String NAME = "AccessoryDesired"; + protected static String DESCRIPTION = "Desired Auxillary actuator settings. Comes from @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index a5d6230ac..08f2ebefe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -60,16 +60,18 @@ public class ActuatorCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); + ChannelElemNames.add("9"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); - List UpdateTimeElemNames = new ArrayList(); - UpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); - List MaxUpdateTimeElemNames = new ArrayList(); MaxUpdateTimeElemNames.add("0"); fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + List NumFailedUpdatesElemNames = new ArrayList(); NumFailedUpdatesElemNames.add("0"); fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); @@ -147,7 +149,7 @@ public class ActuatorCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE8E077D8; + protected static final int OBJID = 0x5324CB8; protected static final String NAME = "ActuatorCommand"; protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index b81ca29da..03ff1985c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -148,7 +148,7 @@ public class ActuatorDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD4516782; + protected static final int OBJID = 0xCA4BC4A4; protected static final String NAME = "ActuatorDesired"; protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 542b433d1..71b0bb49f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -51,202 +51,6 @@ public class ActuatorSettings extends UAVDataObject { List fields = new ArrayList(); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYawElemNames = new ArrayList(); - FixedWingYawElemNames.add("0"); - List FixedWingYawEnumOptions = new ArrayList(); - FixedWingYawEnumOptions.add("Channel1"); - FixedWingYawEnumOptions.add("Channel2"); - FixedWingYawEnumOptions.add("Channel3"); - FixedWingYawEnumOptions.add("Channel4"); - FixedWingYawEnumOptions.add("Channel5"); - FixedWingYawEnumOptions.add("Channel6"); - FixedWingYawEnumOptions.add("Channel7"); - FixedWingYawEnumOptions.add("Channel8"); - FixedWingYawEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelUpdateFreqElemNames = new ArrayList(); ChannelUpdateFreqElemNames.add("0"); ChannelUpdateFreqElemNames.add("1"); @@ -263,6 +67,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelMaxElemNames.add("5"); ChannelMaxElemNames.add("6"); ChannelMaxElemNames.add("7"); + ChannelMaxElemNames.add("8"); + ChannelMaxElemNames.add("9"); fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); List ChannelNeutralElemNames = new ArrayList(); @@ -274,6 +80,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelNeutralElemNames.add("5"); ChannelNeutralElemNames.add("6"); ChannelNeutralElemNames.add("7"); + ChannelNeutralElemNames.add("8"); + ChannelNeutralElemNames.add("9"); fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); List ChannelMinElemNames = new ArrayList(); @@ -285,8 +93,250 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("5"); ChannelMinElemNames.add("6"); ChannelMinElemNames.add("7"); + ChannelMinElemNames.add("8"); + ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("Channel9"); + FixedWingRoll1EnumOptions.add("Channel10"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("Channel9"); + FixedWingRoll2EnumOptions.add("Channel10"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("Channel9"); + FixedWingPitch1EnumOptions.add("Channel10"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("Channel9"); + FixedWingPitch2EnumOptions.add("Channel10"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYaw1ElemNames = new ArrayList(); + FixedWingYaw1ElemNames.add("0"); + List FixedWingYaw1EnumOptions = new ArrayList(); + FixedWingYaw1EnumOptions.add("Channel1"); + FixedWingYaw1EnumOptions.add("Channel2"); + FixedWingYaw1EnumOptions.add("Channel3"); + FixedWingYaw1EnumOptions.add("Channel4"); + FixedWingYaw1EnumOptions.add("Channel5"); + FixedWingYaw1EnumOptions.add("Channel6"); + FixedWingYaw1EnumOptions.add("Channel7"); + FixedWingYaw1EnumOptions.add("Channel8"); + FixedWingYaw1EnumOptions.add("Channel9"); + FixedWingYaw1EnumOptions.add("Channel10"); + FixedWingYaw1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); + + List FixedWingYaw2ElemNames = new ArrayList(); + FixedWingYaw2ElemNames.add("0"); + List FixedWingYaw2EnumOptions = new ArrayList(); + FixedWingYaw2EnumOptions.add("Channel1"); + FixedWingYaw2EnumOptions.add("Channel2"); + FixedWingYaw2EnumOptions.add("Channel3"); + FixedWingYaw2EnumOptions.add("Channel4"); + FixedWingYaw2EnumOptions.add("Channel5"); + FixedWingYaw2EnumOptions.add("Channel6"); + FixedWingYaw2EnumOptions.add("Channel7"); + FixedWingYaw2EnumOptions.add("Channel8"); + FixedWingYaw2EnumOptions.add("Channel9"); + FixedWingYaw2EnumOptions.add("Channel10"); + FixedWingYaw2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("Channel9"); + FixedWingThrottleEnumOptions.add("Channel10"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("Channel9"); + VTOLMotorNEnumOptions.add("Channel10"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("Channel9"); + VTOLMotorNEEnumOptions.add("Channel10"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("Channel9"); + VTOLMotorEEnumOptions.add("Channel10"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("Channel9"); + VTOLMotorSEEnumOptions.add("Channel10"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("Channel9"); + VTOLMotorSEnumOptions.add("Channel10"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("Channel9"); + VTOLMotorSWEnumOptions.add("Channel10"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("Channel9"); + VTOLMotorWEnumOptions.add("Channel10"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("Channel9"); + VTOLMotorNWEnumOptions.add("Channel10"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -296,10 +346,13 @@ public class ActuatorSettings extends UAVDataObject { ChannelTypeElemNames.add("5"); ChannelTypeElemNames.add("6"); ChannelTypeElemNames.add("7"); + ChannelTypeElemNames.add("8"); + ChannelTypeElemNames.add("9"); List ChannelTypeEnumOptions = new ArrayList(); ChannelTypeEnumOptions.add("PWM"); ChannelTypeEnumOptions.add("MK"); ChannelTypeEnumOptions.add("ASTEC4"); + ChannelTypeEnumOptions.add("PWM Alarm Buzzer"); fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); List ChannelAddrElemNames = new ArrayList(); @@ -311,8 +364,17 @@ public class ActuatorSettings extends UAVDataObject { ChannelAddrElemNames.add("5"); ChannelAddrElemNames.add("6"); ChannelAddrElemNames.add("7"); + ChannelAddrElemNames.add("8"); + ChannelAddrElemNames.add("9"); fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + List MotorsSpinWhileArmedElemNames = new ArrayList(); + MotorsSpinWhileArmedElemNames.add("0"); + List MotorsSpinWhileArmedEnumOptions = new ArrayList(); + MotorsSpinWhileArmedEnumOptions.add("FALSE"); + MotorsSpinWhileArmedEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("MotorsSpinWhileArmed", "", UAVObjectField.FieldType.ENUM, MotorsSpinWhileArmedElemNames, MotorsSpinWhileArmedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -358,20 +420,6 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -384,6 +432,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMax").setValue(1000,5); getField("ChannelMax").setValue(1000,6); getField("ChannelMax").setValue(1000,7); + getField("ChannelMax").setValue(1000,8); + getField("ChannelMax").setValue(1000,9); getField("ChannelNeutral").setValue(1000,0); getField("ChannelNeutral").setValue(1000,1); getField("ChannelNeutral").setValue(1000,2); @@ -392,6 +442,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelNeutral").setValue(1000,5); getField("ChannelNeutral").setValue(1000,6); getField("ChannelNeutral").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,8); + getField("ChannelNeutral").setValue(1000,9); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -400,6 +452,23 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelMin").setValue(1000,9); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw1").setValue("None"); + getField("FixedWingYaw2").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -408,6 +477,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelType").setValue("PWM",5); getField("ChannelType").setValue("PWM",6); getField("ChannelType").setValue("PWM",7); + getField("ChannelType").setValue("PWM",8); + getField("ChannelType").setValue("PWM",9); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); @@ -416,6 +487,9 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelAddr").setValue(5,5); getField("ChannelAddr").setValue(6,6); getField("ChannelAddr").setValue(7,7); + getField("ChannelAddr").setValue(8,8); + getField("ChannelAddr").setValue(9,9); + getField("MotorsSpinWhileArmed").setValue("FALSE"); } @@ -444,7 +518,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1BF864C2; + protected static final int OBJID = 0xF2875746; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java index 3ee8304ae..82e447a70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -51,6 +51,10 @@ public class AhrsStatus extends UAVDataObject { List fields = new ArrayList(); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + List SerialNumberElemNames = new ArrayList(); SerialNumberElemNames.add("0"); SerialNumberElemNames.add("1"); @@ -66,10 +70,6 @@ public class AhrsStatus extends UAVDataObject { CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - List IdleTimePerCyleElemNames = new ArrayList(); IdleTimePerCyleElemNames.add("0"); fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); @@ -190,7 +190,7 @@ public class AhrsStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37A5F7A2; + protected static final int OBJID = 0x706D1AB8; protected static final String NAME = "AhrsStatus"; protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 714c18571..7c9272cad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -110,7 +110,7 @@ public class AttitudeActual extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 500; + metadata.flightTelemetryUpdatePeriod = 100; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; metadata.loggingUpdatePeriod = 0; @@ -152,7 +152,7 @@ public class AttitudeActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xFC5B8CF4; + protected static final int OBJID = 0x33DAD5E6; protected static final String NAME = "AttitudeActual"; protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java index d28302b6a..b8c3aacb4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -51,29 +51,29 @@ public class AttitudeRaw extends UAVDataObject { List fields = new ArrayList(); - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - List gyrosElemNames = new ArrayList(); gyrosElemNames.add("X"); gyrosElemNames.add("Y"); gyrosElemNames.add("Z"); fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - List accelsElemNames = new ArrayList(); accelsElemNames.add("X"); accelsElemNames.add("Y"); accelsElemNames.add("Z"); fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -147,7 +147,7 @@ public class AttitudeRaw extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37747DE6; + protected static final int OBJID = 0xDB722974; protected static final String NAME = "AttitudeRaw"; protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 482fc12ce..3034a99ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -51,12 +51,6 @@ public class AttitudeSettings extends UAVDataObject { List fields = new ArrayList(); - List AccelBiasElemNames = new ArrayList(); - AccelBiasElemNames.add("X"); - AccelBiasElemNames.add("Y"); - AccelBiasElemNames.add("Z"); - fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); - List GyroGainElemNames = new ArrayList(); GyroGainElemNames.add("0"); fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); @@ -69,6 +63,50 @@ public class AttitudeSettings extends UAVDataObject { AccelKiElemNames.add("0"); fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + List YawBiasRateElemNames = new ArrayList(); + YawBiasRateElemNames.add("0"); + fields.add( new UAVObjectField("YawBiasRate", "channel", UAVObjectField.FieldType.FLOAT32, YawBiasRateElemNames, null) ); + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroBiasElemNames = new ArrayList(); + GyroBiasElemNames.add("X"); + GyroBiasElemNames.add("Y"); + GyroBiasElemNames.add("Z"); + fields.add( new UAVObjectField("GyroBias", "deg/s * 100", UAVObjectField.FieldType.INT16, GyroBiasElemNames, null) ); + + List BoardRotationElemNames = new ArrayList(); + BoardRotationElemNames.add("Roll"); + BoardRotationElemNames.add("Pitch"); + BoardRotationElemNames.add("Yaw"); + fields.add( new UAVObjectField("BoardRotation", "deg", UAVObjectField.FieldType.INT16, BoardRotationElemNames, null) ); + + List ZeroDuringArmingElemNames = new ArrayList(); + ZeroDuringArmingElemNames.add("0"); + List ZeroDuringArmingEnumOptions = new ArrayList(); + ZeroDuringArmingEnumOptions.add("FALSE"); + ZeroDuringArmingEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ZeroDuringArming", "channel", UAVObjectField.FieldType.ENUM, ZeroDuringArmingElemNames, ZeroDuringArmingEnumOptions) ); + + List BiasCorrectGyroElemNames = new ArrayList(); + BiasCorrectGyroElemNames.add("0"); + List BiasCorrectGyroEnumOptions = new ArrayList(); + BiasCorrectGyroEnumOptions.add("FALSE"); + BiasCorrectGyroEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectGyro", "channel", UAVObjectField.FieldType.ENUM, BiasCorrectGyroElemNames, BiasCorrectGyroEnumOptions) ); + + List TrimFlightElemNames = new ArrayList(); + TrimFlightElemNames.add("0"); + List TrimFlightEnumOptions = new ArrayList(); + TrimFlightEnumOptions.add("NORMAL"); + TrimFlightEnumOptions.add("START"); + TrimFlightEnumOptions.add("LOAD"); + fields.add( new UAVObjectField("TrimFlight", "channel", UAVObjectField.FieldType.ENUM, TrimFlightElemNames, TrimFlightEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -114,12 +152,22 @@ public class AttitudeSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.05); + getField("AccelKi").setValue(0.0001); + getField("YawBiasRate").setValue(1e-06); getField("AccelBias").setValue(0,0); getField("AccelBias").setValue(0,1); getField("AccelBias").setValue(0,2); - getField("GyroGain").setValue(0.42); - getField("AccelKp").setValue(0.01); - getField("AccelKi").setValue(0.0001); + getField("GyroBias").setValue(0,0); + getField("GyroBias").setValue(0,1); + getField("GyroBias").setValue(0,2); + getField("BoardRotation").setValue(0,0); + getField("BoardRotation").setValue(0,1); + getField("BoardRotation").setValue(0,2); + getField("ZeroDuringArming").setValue("TRUE"); + getField("BiasCorrectGyro").setValue("TRUE"); + getField("TrimFlight").setValue("NORMAL"); } @@ -148,7 +196,7 @@ public class AttitudeSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x327BF29A; + protected static final int OBJID = 0xC307BC4A; protected static final String NAME = "AttitudeSettings"; protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index a2c2c7e3d..ecde53985 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -136,7 +136,7 @@ public class BaroAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0xED4424F6; + protected static final int OBJID = 0x99622E6A; protected static final String NAME = "BaroAltitude"; protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java new file mode 100644 index 000000000..7a36ec1ea --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired camera outputs. Comes from @ref CameraStabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired camera outputs. Comes from @ref CameraStabilization module. + +generated from cameradesired.xml + **/ +public class CameraDesired extends UAVDataObject { + + public CameraDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraDesired obj = new CameraDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraDesired)(objMngr.getObject(CameraDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x531F544E; + protected static final String NAME = "CameraDesired"; + protected static String DESCRIPTION = "Desired camera outputs. Comes from @ref CameraStabilization module."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java new file mode 100644 index 000000000..a8e03df32 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -0,0 +1,205 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref CameraStab mmodule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref CameraStab mmodule + +generated from camerastabsettings.xml + **/ +public class CameraStabSettings extends UAVDataObject { + + public CameraStabSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.FLOAT32, MaxAxisLockRateElemNames, null) ); + + List ResponseTimeElemNames = new ArrayList(); + ResponseTimeElemNames.add("Roll"); + ResponseTimeElemNames.add("Pitch"); + ResponseTimeElemNames.add("Yaw"); + fields.add( new UAVObjectField("ResponseTime", "ms", UAVObjectField.FieldType.UINT16, ResponseTimeElemNames, null) ); + + List InputElemNames = new ArrayList(); + InputElemNames.add("Roll"); + InputElemNames.add("Pitch"); + InputElemNames.add("Yaw"); + List InputEnumOptions = new ArrayList(); + InputEnumOptions.add("Accessory0"); + InputEnumOptions.add("Accessory1"); + InputEnumOptions.add("Accessory2"); + InputEnumOptions.add("Accessory3"); + InputEnumOptions.add("Accessory4"); + InputEnumOptions.add("Accessory5"); + InputEnumOptions.add("None"); + fields.add( new UAVObjectField("Input", "channel", UAVObjectField.FieldType.ENUM, InputElemNames, InputEnumOptions) ); + + List InputRangeElemNames = new ArrayList(); + InputRangeElemNames.add("Roll"); + InputRangeElemNames.add("Pitch"); + InputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRange", "deg", UAVObjectField.FieldType.UINT8, InputRangeElemNames, null) ); + + List InputRateElemNames = new ArrayList(); + InputRateElemNames.add("Roll"); + InputRateElemNames.add("Pitch"); + InputRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRate", "deg/s", UAVObjectField.FieldType.UINT8, InputRateElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + List OutputRangeElemNames = new ArrayList(); + OutputRangeElemNames.add("Roll"); + OutputRangeElemNames.add("Pitch"); + OutputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("OutputRange", "deg", UAVObjectField.FieldType.UINT8, OutputRangeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAxisLockRate").setValue(1); + getField("ResponseTime").setValue(150,0); + getField("ResponseTime").setValue(150,1); + getField("ResponseTime").setValue(150,2); + getField("Input").setValue("None",0); + getField("Input").setValue("None",1); + getField("Input").setValue("None",2); + getField("InputRange").setValue(20,0); + getField("InputRange").setValue(20,1); + getField("InputRange").setValue(20,2); + getField("InputRate").setValue(50,0); + getField("InputRate").setValue(50,1); + getField("InputRate").setValue(50,2); + getField("StabilizationMode").setValue("Attitude",0); + getField("StabilizationMode").setValue("Attitude",1); + getField("StabilizationMode").setValue("Attitude",2); + getField("OutputRange").setValue(20,0); + getField("OutputRange").setValue(20,1); + getField("OutputRange").setValue(20,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraStabSettings obj = new CameraStabSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraStabSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraStabSettings)(objMngr.getObject(CameraStabSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3B95DDBA; + protected static final String NAME = "CameraStabSettings"; + protected static String DESCRIPTION = "Settings for the @ref CameraStab mmodule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java similarity index 74% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index 675f9b592..b22b8185e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Select baud rate of telemetry. Warning - this must match your modem. + * Allows testers to simulate various fault scenarios. * * @see The GNU Public License (GPL) Version 3 * @@ -39,29 +39,28 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Select baud rate of telemetry. Warning - this must match your modem. +Allows testers to simulate various fault scenarios. -generated from telemetrysettings.xml +generated from faultsettings.xml **/ -public class TelemetrySettings extends UAVDataObject { +public class FaultSettings extends UAVDataObject { - public TelemetrySettings() { + public FaultSettings() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List SpeedElemNames = new ArrayList(); - SpeedElemNames.add("0"); - List SpeedEnumOptions = new ArrayList(); - SpeedEnumOptions.add("2400"); - SpeedEnumOptions.add("4800"); - SpeedEnumOptions.add("9600"); - SpeedEnumOptions.add("19200"); - SpeedEnumOptions.add("38400"); - SpeedEnumOptions.add("57600"); - SpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + List ActivateFaultElemNames = new ArrayList(); + ActivateFaultElemNames.add("0"); + List ActivateFaultEnumOptions = new ArrayList(); + ActivateFaultEnumOptions.add("NoFault"); + ActivateFaultEnumOptions.add("ModuleInitAssert"); + ActivateFaultEnumOptions.add("InitOutOfMemory"); + ActivateFaultEnumOptions.add("InitBusError"); + ActivateFaultEnumOptions.add("RunawayTask"); + ActivateFaultEnumOptions.add("TaskOutOfMemory"); + fields.add( new UAVObjectField("ActivateFault", "fault", UAVObjectField.FieldType.ENUM, ActivateFaultElemNames, ActivateFaultEnumOptions) ); // Compute the number of bytes for this object @@ -108,7 +107,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue("57600"); + getField("ActivateFault").setValue("NoFault"); } @@ -120,7 +119,7 @@ public class TelemetrySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - TelemetrySettings obj = new TelemetrySettings(); + FaultSettings obj = new FaultSettings(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -131,15 +130,15 @@ public class TelemetrySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + public FaultSettings GetInstance(UAVObjectManager objMngr, int instID) { - return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + return (FaultSettings)(objMngr.getObject(FaultSettings.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA608C526; - protected static final String NAME = "TelemetrySettings"; - protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final int OBJID = 0x2778BA3C; + protected static final String NAME = "FaultSettings"; + protected static String DESCRIPTION = "Allows testers to simulate various fault scenarios."; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 1 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 493d6cd64..71c681bd2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Firmware IAP + * Queries board for SN, model, revision, and sends reset command * * @see The GNU Public License (GPL) Version 3 * @@ -39,7 +39,7 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Firmware IAP +Queries board for SN, model, revision, and sends reset command generated from firmwareiapobj.xml **/ @@ -51,10 +51,18 @@ public class FirmwareIAPObj extends UAVDataObject { List fields = new ArrayList(); + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + List CommandElemNames = new ArrayList(); CommandElemNames.add("0"); fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List DescriptionElemNames = new ArrayList(); DescriptionElemNames.add("0"); DescriptionElemNames.add("1"); @@ -96,71 +104,22 @@ public class FirmwareIAPObj extends UAVDataObject { DescriptionElemNames.add("37"); DescriptionElemNames.add("38"); DescriptionElemNames.add("39"); - DescriptionElemNames.add("40"); - DescriptionElemNames.add("41"); - DescriptionElemNames.add("42"); - DescriptionElemNames.add("43"); - DescriptionElemNames.add("44"); - DescriptionElemNames.add("45"); - DescriptionElemNames.add("46"); - DescriptionElemNames.add("47"); - DescriptionElemNames.add("48"); - DescriptionElemNames.add("49"); - DescriptionElemNames.add("50"); - DescriptionElemNames.add("51"); - DescriptionElemNames.add("52"); - DescriptionElemNames.add("53"); - DescriptionElemNames.add("54"); - DescriptionElemNames.add("55"); - DescriptionElemNames.add("56"); - DescriptionElemNames.add("57"); - DescriptionElemNames.add("58"); - DescriptionElemNames.add("59"); - DescriptionElemNames.add("60"); - DescriptionElemNames.add("61"); - DescriptionElemNames.add("62"); - DescriptionElemNames.add("63"); - DescriptionElemNames.add("64"); - DescriptionElemNames.add("65"); - DescriptionElemNames.add("66"); - DescriptionElemNames.add("67"); - DescriptionElemNames.add("68"); - DescriptionElemNames.add("69"); - DescriptionElemNames.add("70"); - DescriptionElemNames.add("71"); - DescriptionElemNames.add("72"); - DescriptionElemNames.add("73"); - DescriptionElemNames.add("74"); - DescriptionElemNames.add("75"); - DescriptionElemNames.add("76"); - DescriptionElemNames.add("77"); - DescriptionElemNames.add("78"); - DescriptionElemNames.add("79"); - DescriptionElemNames.add("80"); - DescriptionElemNames.add("81"); - DescriptionElemNames.add("82"); - DescriptionElemNames.add("83"); - DescriptionElemNames.add("84"); - DescriptionElemNames.add("85"); - DescriptionElemNames.add("86"); - DescriptionElemNames.add("87"); - DescriptionElemNames.add("88"); - DescriptionElemNames.add("89"); - DescriptionElemNames.add("90"); - DescriptionElemNames.add("91"); - DescriptionElemNames.add("92"); - DescriptionElemNames.add("93"); - DescriptionElemNames.add("94"); - DescriptionElemNames.add("95"); - DescriptionElemNames.add("96"); - DescriptionElemNames.add("97"); - DescriptionElemNames.add("98"); - DescriptionElemNames.add("99"); fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); - List BoardRevisionElemNames = new ArrayList(); - BoardRevisionElemNames.add("0"); - fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); List BoardTypeElemNames = new ArrayList(); BoardTypeElemNames.add("0"); @@ -170,10 +129,6 @@ public class FirmwareIAPObj extends UAVDataObject { ArmResetElemNames.add("0"); fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); - List crcElemNames = new ArrayList(); - crcElemNames.add("0"); - fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -247,9 +202,9 @@ public class FirmwareIAPObj extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1A8ECC2; + protected static final int OBJID = 0x3CCDFB68; protected static final String NAME = "FirmwareIAPObj"; - protected static String DESCRIPTION = "Firmware IAP"; + protected static String DESCRIPTION = "Queries board for SN, model, revision, and sends reset command"; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java new file mode 100644 index 000000000..a3bc23eb3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -0,0 +1,177 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Flight Battery configuration. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Flight Battery configuration. + +generated from flightbatterysettings.xml + **/ +public class FlightBatterySettings extends UAVDataObject { + + public FlightBatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CapacityElemNames = new ArrayList(); + CapacityElemNames.add("0"); + fields.add( new UAVObjectField("Capacity", "mAh", UAVObjectField.FieldType.UINT32, CapacityElemNames, null) ); + + List VoltageThresholdsElemNames = new ArrayList(); + VoltageThresholdsElemNames.add("Warning"); + VoltageThresholdsElemNames.add("Alarm"); + fields.add( new UAVObjectField("VoltageThresholds", "V", UAVObjectField.FieldType.FLOAT32, VoltageThresholdsElemNames, null) ); + + List SensorCalibrationsElemNames = new ArrayList(); + SensorCalibrationsElemNames.add("VoltageFactor"); + SensorCalibrationsElemNames.add("CurrentFactor"); + fields.add( new UAVObjectField("SensorCalibrations", "", UAVObjectField.FieldType.FLOAT32, SensorCalibrationsElemNames, null) ); + + List TypeElemNames = new ArrayList(); + TypeElemNames.add("0"); + List TypeEnumOptions = new ArrayList(); + TypeEnumOptions.add("LiPo"); + TypeEnumOptions.add("A123"); + TypeEnumOptions.add("LiCo"); + TypeEnumOptions.add("LiFeSO4"); + TypeEnumOptions.add("None"); + fields.add( new UAVObjectField("Type", "", UAVObjectField.FieldType.ENUM, TypeElemNames, TypeEnumOptions) ); + + List NbCellsElemNames = new ArrayList(); + NbCellsElemNames.add("0"); + fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); + + List SensorTypeElemNames = new ArrayList(); + SensorTypeElemNames.add("0"); + List SensorTypeEnumOptions = new ArrayList(); + SensorTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Capacity").setValue(2200); + getField("VoltageThresholds").setValue(9.8,0); + getField("VoltageThresholds").setValue(9.2,1); + getField("SensorCalibrations").setValue(1,0); + getField("SensorCalibrations").setValue(1,1); + getField("Type").setValue("LiPo"); + getField("NbCells").setValue(3); + getField("SensorType").setValue("None"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatterySettings obj = new FlightBatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatterySettings)(objMngr.getObject(FlightBatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF172BB18; + protected static final String NAME = "FlightBatterySettings"; + protected static String DESCRIPTION = "Flight Battery configuration."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index d9fba1de5..82fcfae47 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -154,7 +154,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x791A50E; + protected static final int OBJID = 0x8C0D756; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index fdc5bfcb0..dbe959f96 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -133,7 +133,7 @@ public class FlightPlanControl extends UAVDataObject { } // Constants - protected static final int OBJID = 0x6B4FE6DA; + protected static final int OBJID = 0x53E3F180; protected static final String NAME = "FlightPlanControl"; protected static String DESCRIPTION = "Control the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 383e4aff0..6fc39a26e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -129,7 +129,7 @@ public class FlightPlanSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x85368422; + protected static final int OBJID = 0x92E9FF76; protected static final String NAME = "FlightPlanSettings"; protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 2303514c0..7b78bce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -51,6 +51,19 @@ public class FlightPlanStatus extends UAVDataObject { List fields = new ArrayList(); + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List DebugElemNames = new ArrayList(); + DebugElemNames.add("0"); + DebugElemNames.add("1"); + fields.add( new UAVObjectField("Debug", "", UAVObjectField.FieldType.FLOAT32, DebugElemNames, null) ); + List StatusElemNames = new ArrayList(); StatusElemNames.add("0"); List StatusEnumOptions = new ArrayList(); @@ -83,22 +96,6 @@ public class FlightPlanStatus extends UAVDataObject { ErrorTypeEnumOptions.add("UnknownError"); fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); - List ErrorFileIDElemNames = new ArrayList(); - ErrorFileIDElemNames.add("0"); - fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); - - List ErrorLineNumElemNames = new ArrayList(); - ErrorLineNumElemNames.add("0"); - fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); - - List Debug1ElemNames = new ArrayList(); - Debug1ElemNames.add("0"); - fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); - - List Debug2ElemNames = new ArrayList(); - Debug2ElemNames.add("0"); - fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -144,10 +141,10 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Debug").setValue(0,0); + getField("Debug").setValue(0,1); getField("Status").setValue("Stopped"); getField("ErrorType").setValue("None"); - getField("Debug1").setValue(0); - getField("Debug2").setValue(0); } @@ -176,7 +173,7 @@ public class FlightPlanStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9FC14812; + protected static final int OBJID = 0x2206EE46; protected static final String NAME = "FlightPlanStatus"; protected static String DESCRIPTION = "Status of the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java new file mode 100644 index 000000000..d775b21e7 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -0,0 +1,155 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains major flight status information for other modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains major flight status information for other modules. + +generated from flightstatus.xml + **/ +public class FlightStatus extends UAVDataObject { + + public FlightStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("Disarmed"); + ArmedEnumOptions.add("Arming"); + ArmedEnumOptions.add("Armed"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Armed").setValue("Disarmed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightStatus obj = new FlightStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightStatus)(objMngr.getObject(FlightStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x743DB13C; + protected static final String NAME = "FlightStatus"; + protected static String DESCRIPTION = "Contains major flight status information for other modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index b58fe6d46..403ea1d5e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -51,15 +51,6 @@ public class FlightTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class FlightTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class FlightTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x660C265E; + protected static final int OBJID = 0x2F7E2902; protected static final String NAME = "FlightTelemetryStats"; protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java new file mode 100644 index 000000000..3cb3811ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A receiver channel group carried over the telemetry link. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A receiver channel group carried over the telemetry link. + +generated from gcsreceiver.xml + **/ +public class GCSReceiver extends UAVDataObject { + + public GCSReceiver() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSReceiver obj = new GCSReceiver(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSReceiver GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSReceiver)(objMngr.getObject(GCSReceiver.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xCC7E2BBC; + protected static final String NAME = "GCSReceiver"; + protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index 0f304d45d..b32f551ce 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -51,15 +51,6 @@ public class GCSTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class GCSTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class GCSTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x771E1046; + protected static final int OBJID = 0xABC72744; protected static final String NAME = "GCSTelemetryStats"; protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 889091e0e..5f4e20b46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -51,15 +51,6 @@ public class GPSPosition extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("NoGPS"); - StatusEnumOptions.add("NoFix"); - StatusEnumOptions.add("Fix2D"); - StatusEnumOptions.add("Fix3D"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -84,10 +75,6 @@ public class GPSPosition extends UAVDataObject { GroundspeedElemNames.add("0"); fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); - List SatellitesElemNames = new ArrayList(); - SatellitesElemNames.add("0"); - fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); - List PDOPElemNames = new ArrayList(); PDOPElemNames.add("0"); fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); @@ -100,6 +87,19 @@ public class GPSPosition extends UAVDataObject { VDOPElemNames.add("0"); fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -173,7 +173,7 @@ public class GPSPosition extends UAVDataObject { } // Constants - protected static final int OBJID = 0xB5495042; + protected static final int OBJID = 0xE2A323B6; protected static final String NAME = "GPSPosition"; protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index fa1100207..bb331132d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -51,29 +51,6 @@ public class GPSSatellites extends UAVDataObject { List fields = new ArrayList(); - List SatsInViewElemNames = new ArrayList(); - SatsInViewElemNames.add("0"); - fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); - - List PRNElemNames = new ArrayList(); - PRNElemNames.add("0"); - PRNElemNames.add("1"); - PRNElemNames.add("2"); - PRNElemNames.add("3"); - PRNElemNames.add("4"); - PRNElemNames.add("5"); - PRNElemNames.add("6"); - PRNElemNames.add("7"); - PRNElemNames.add("8"); - PRNElemNames.add("9"); - PRNElemNames.add("10"); - PRNElemNames.add("11"); - PRNElemNames.add("12"); - PRNElemNames.add("13"); - PRNElemNames.add("14"); - PRNElemNames.add("15"); - fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); - List ElevationElemNames = new ArrayList(); ElevationElemNames.add("0"); ElevationElemNames.add("1"); @@ -112,6 +89,29 @@ public class GPSSatellites extends UAVDataObject { AzimuthElemNames.add("15"); fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + List SNRElemNames = new ArrayList(); SNRElemNames.add("0"); SNRElemNames.add("1"); @@ -204,7 +204,7 @@ public class GPSSatellites extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD62FA3AE; + protected static final int OBJID = 0x920D998; protected static final String NAME = "GPSSatellites"; protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5ff55cc2e..5aa4df7bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -51,6 +51,10 @@ public class GPSTime extends UAVDataObject { List fields = new ArrayList(); + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + List MonthElemNames = new ArrayList(); MonthElemNames.add("0"); fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); @@ -59,10 +63,6 @@ public class GPSTime extends UAVDataObject { DayElemNames.add("0"); fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); - List YearElemNames = new ArrayList(); - YearElemNames.add("0"); - fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); - List HourElemNames = new ArrayList(); HourElemNames.add("0"); fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); @@ -148,7 +148,7 @@ public class GPSTime extends UAVDataObject { } // Constants - protected static final int OBJID = 0x56FFF0A2; + protected static final int OBJID = 0xD4478084; protected static final String NAME = "GPSTime"; protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2fe8bb437..205384efe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -51,29 +51,24 @@ public class GuidanceSettings extends UAVDataObject { List fields = new ArrayList(); - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List HorizontalPElemNames = new ArrayList(); - HorizontalPElemNames.add("Kp"); - HorizontalPElemNames.add("Max"); - fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - List VerticalPElemNames = new ArrayList(); - VerticalPElemNames.add("Kp"); - VerticalPElemNames.add("Max"); - fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); List VerticalVelPIDElemNames = new ArrayList(); VerticalVelPIDElemNames.add("Kp"); @@ -82,13 +77,6 @@ public class GuidanceSettings extends UAVDataObject { VerticalVelPIDElemNames.add("ILimit"); fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - List MaxRollPitchElemNames = new ArrayList(); MaxRollPitchElemNames.add("0"); fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); @@ -97,6 +85,28 @@ public class GuidanceSettings extends UAVDataObject { UpdatePeriodElemNames.add("0"); fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -142,22 +152,26 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("HorizontalP").setValue(0.2,0); - getField("HorizontalP").setValue(150,1); - getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.001,1); + getField("HorizontalPosPI").setValue(300,2); + getField("HorizontalVelPID").setValue(0.05,0); getField("HorizontalVelPID").setValue(0.002,1); getField("HorizontalVelPID").setValue(0,2); getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalP").setValue(0.1,0); - getField("VerticalP").setValue(200,1); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); getField("VerticalVelPID").setValue(0.1,0); getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(300); + getField("VerticalVelMax").setValue(150); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); } @@ -186,7 +200,7 @@ public class GuidanceSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x74740AA2; + protected static final int OBJID = 0x6EA79FB4; protected static final String NAME = "GuidanceSettings"; protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 5941c069c..68abb3633 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -51,13 +51,6 @@ public class HomeLocation extends UAVDataObject { List fields = new ArrayList(); - List SetElemNames = new ArrayList(); - SetElemNames.add("0"); - List SetEnumOptions = new ArrayList(); - SetEnumOptions.add("FALSE"); - SetEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -94,6 +87,17 @@ public class HomeLocation extends UAVDataObject { BeElemNames.add("2"); fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + List g_eElemNames = new ArrayList(); + g_eElemNames.add("0"); + fields.add( new UAVObjectField("g_e", "m/s^2", UAVObjectField.FieldType.FLOAT32, g_eElemNames, null) ); + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -139,7 +143,6 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); @@ -158,6 +161,8 @@ public class HomeLocation extends UAVDataObject { getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); + getField("g_e").setValue(9.81); + getField("Set").setValue("FALSE"); } @@ -186,7 +191,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD6008ED2; + protected static final int OBJID = 0x5BB3AEFC; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java new file mode 100644 index 000000000..83b7ae7b6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -0,0 +1,291 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Selection of optional hardware configurations. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Selection of optional hardware configurations. + +generated from hwsettings.xml + **/ +public class HwSettings extends UAVDataObject { + + public HwSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CC_RcvrPortElemNames = new ArrayList(); + CC_RcvrPortElemNames.add("0"); + List CC_RcvrPortEnumOptions = new ArrayList(); + CC_RcvrPortEnumOptions.add("Disabled"); + CC_RcvrPortEnumOptions.add("PWM"); + CC_RcvrPortEnumOptions.add("PPM"); + CC_RcvrPortEnumOptions.add("PPM+Outputs"); + CC_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("CC_RcvrPort", "function", UAVObjectField.FieldType.ENUM, CC_RcvrPortElemNames, CC_RcvrPortEnumOptions) ); + + List CC_MainPortElemNames = new ArrayList(); + CC_MainPortElemNames.add("0"); + List CC_MainPortEnumOptions = new ArrayList(); + CC_MainPortEnumOptions.add("Disabled"); + CC_MainPortEnumOptions.add("Telemetry"); + CC_MainPortEnumOptions.add("GPS"); + CC_MainPortEnumOptions.add("S.Bus"); + CC_MainPortEnumOptions.add("DSM2"); + CC_MainPortEnumOptions.add("DSMX (10bit)"); + CC_MainPortEnumOptions.add("DSMX (11bit)"); + CC_MainPortEnumOptions.add("ComAux"); + CC_MainPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_MainPort", "function", UAVObjectField.FieldType.ENUM, CC_MainPortElemNames, CC_MainPortEnumOptions) ); + + List CC_FlexiPortElemNames = new ArrayList(); + CC_FlexiPortElemNames.add("0"); + List CC_FlexiPortEnumOptions = new ArrayList(); + CC_FlexiPortEnumOptions.add("Disabled"); + CC_FlexiPortEnumOptions.add("Telemetry"); + CC_FlexiPortEnumOptions.add("GPS"); + CC_FlexiPortEnumOptions.add("I2C"); + CC_FlexiPortEnumOptions.add("DSM2"); + CC_FlexiPortEnumOptions.add("DSMX (10bit)"); + CC_FlexiPortEnumOptions.add("DSMX (11bit)"); + CC_FlexiPortEnumOptions.add("ComAux"); + CC_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); + + List OP_RcvrPortElemNames = new ArrayList(); + OP_RcvrPortElemNames.add("0"); + List OP_RcvrPortEnumOptions = new ArrayList(); + OP_RcvrPortEnumOptions.add("Disabled"); + OP_RcvrPortEnumOptions.add("PWM"); + OP_RcvrPortEnumOptions.add("PPM"); + OP_RcvrPortEnumOptions.add("DSM2"); + OP_RcvrPortEnumOptions.add("DSMX (10bit)"); + OP_RcvrPortEnumOptions.add("DSMX (11bit)"); + OP_RcvrPortEnumOptions.add("Debug"); + fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + + List OP_MainPortElemNames = new ArrayList(); + OP_MainPortElemNames.add("0"); + List OP_MainPortEnumOptions = new ArrayList(); + OP_MainPortEnumOptions.add("Disabled"); + OP_MainPortEnumOptions.add("Telemetry"); + fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + + List OP_FlexiPortElemNames = new ArrayList(); + OP_FlexiPortElemNames.add("0"); + List OP_FlexiPortEnumOptions = new ArrayList(); + OP_FlexiPortEnumOptions.add("Disabled"); + OP_FlexiPortEnumOptions.add("GPS"); + fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List GPSSpeedElemNames = new ArrayList(); + GPSSpeedElemNames.add("0"); + List GPSSpeedEnumOptions = new ArrayList(); + GPSSpeedEnumOptions.add("2400"); + GPSSpeedEnumOptions.add("4800"); + GPSSpeedEnumOptions.add("9600"); + GPSSpeedEnumOptions.add("19200"); + GPSSpeedEnumOptions.add("38400"); + GPSSpeedEnumOptions.add("57600"); + GPSSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("GPSSpeed", "bps", UAVObjectField.FieldType.ENUM, GPSSpeedElemNames, GPSSpeedEnumOptions) ); + + List ComUsbBridgeSpeedElemNames = new ArrayList(); + ComUsbBridgeSpeedElemNames.add("0"); + List ComUsbBridgeSpeedEnumOptions = new ArrayList(); + ComUsbBridgeSpeedEnumOptions.add("2400"); + ComUsbBridgeSpeedEnumOptions.add("4800"); + ComUsbBridgeSpeedEnumOptions.add("9600"); + ComUsbBridgeSpeedEnumOptions.add("19200"); + ComUsbBridgeSpeedEnumOptions.add("38400"); + ComUsbBridgeSpeedEnumOptions.add("57600"); + ComUsbBridgeSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); + + List USB_DeviceTypeElemNames = new ArrayList(); + USB_DeviceTypeElemNames.add("0"); + List USB_DeviceTypeEnumOptions = new ArrayList(); + USB_DeviceTypeEnumOptions.add("HID-only"); + USB_DeviceTypeEnumOptions.add("HID+VCP"); + USB_DeviceTypeEnumOptions.add("VCP-only"); + fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); + + List USB_HIDPortElemNames = new ArrayList(); + USB_HIDPortElemNames.add("0"); + List USB_HIDPortEnumOptions = new ArrayList(); + USB_HIDPortEnumOptions.add("USBTelemetry"); + USB_HIDPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_HIDPort", "function", UAVObjectField.FieldType.ENUM, USB_HIDPortElemNames, USB_HIDPortEnumOptions) ); + + List USB_VCPPortElemNames = new ArrayList(); + USB_VCPPortElemNames.add("0"); + List USB_VCPPortEnumOptions = new ArrayList(); + USB_VCPPortEnumOptions.add("USBTelemetry"); + USB_VCPPortEnumOptions.add("ComBridge"); + USB_VCPPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_VCPPort", "function", UAVObjectField.FieldType.ENUM, USB_VCPPortElemNames, USB_VCPPortEnumOptions) ); + + List OptionalModulesElemNames = new ArrayList(); + OptionalModulesElemNames.add("CameraStab"); + OptionalModulesElemNames.add("GPS"); + OptionalModulesElemNames.add("ComUsbBridge"); + OptionalModulesElemNames.add("Fault"); + OptionalModulesElemNames.add("Altitude"); + List OptionalModulesEnumOptions = new ArrayList(); + OptionalModulesEnumOptions.add("Disabled"); + OptionalModulesEnumOptions.add("Enabled"); + fields.add( new UAVObjectField("OptionalModules", "", UAVObjectField.FieldType.ENUM, OptionalModulesElemNames, OptionalModulesEnumOptions) ); + + List DSMxBindElemNames = new ArrayList(); + DSMxBindElemNames.add("0"); + fields.add( new UAVObjectField("DSMxBind", "", UAVObjectField.FieldType.UINT8, DSMxBindElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("CC_RcvrPort").setValue("PWM"); + getField("CC_MainPort").setValue("Disabled"); + getField("CC_FlexiPort").setValue("Disabled"); + getField("OP_RcvrPort").setValue("PWM"); + getField("OP_MainPort").setValue("Telemetry"); + getField("OP_FlexiPort").setValue("GPS"); + getField("TelemetrySpeed").setValue("57600"); + getField("GPSSpeed").setValue("57600"); + getField("ComUsbBridgeSpeed").setValue("57600"); + getField("USB_DeviceType").setValue("HID-only"); + getField("USB_HIDPort").setValue("USBTelemetry"); + getField("USB_VCPPort").setValue("Disabled"); + getField("OptionalModules").setValue("Disabled",0); + getField("OptionalModules").setValue("Disabled",1); + getField("OptionalModules").setValue("Disabled",2); + getField("OptionalModules").setValue("Disabled",3); + getField("OptionalModules").setValue("Disabled",4); + getField("DSMxBind").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HwSettings obj = new HwSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HwSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (HwSettings)(objMngr.getObject(HwSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2EE6575A; + protected static final String NAME = "HwSettings"; + protected static String DESCRIPTION = "Selection of optional hardware configurations."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index fc68e2902..abd8f41f6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -51,6 +51,22 @@ public class I2CStats extends UAVDataObject { List fields = new ArrayList(); + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + List event_errorsElemNames = new ArrayList(); event_errorsElemNames.add("0"); fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); @@ -79,22 +95,6 @@ public class I2CStats extends UAVDataObject { last_error_typeEnumOptions.add("INTERRUPT"); fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); - List evirq_logElemNames = new ArrayList(); - evirq_logElemNames.add("0"); - evirq_logElemNames.add("1"); - evirq_logElemNames.add("2"); - evirq_logElemNames.add("3"); - evirq_logElemNames.add("4"); - fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); - - List erirq_logElemNames = new ArrayList(); - erirq_logElemNames.add("0"); - erirq_logElemNames.add("1"); - erirq_logElemNames.add("2"); - erirq_logElemNames.add("3"); - erirq_logElemNames.add("4"); - fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); - List event_logElemNames = new ArrayList(); event_logElemNames.add("0"); event_logElemNames.add("1"); @@ -227,7 +227,7 @@ public class I2CStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x23CE9E9C; + protected static final int OBJID = 0xB714823E; protected static final String NAME = "I2CStats"; protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 636f30946..6ac5a1b2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -51,19 +51,9 @@ public class ManualControlCommand extends UAVDataObject { List fields = new ArrayList(); - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - List ArmedElemNames = new ArrayList(); - ArmedElemNames.add("0"); - List ArmedEnumOptions = new ArrayList(); - ArmedEnumOptions.add("False"); - ArmedEnumOptions.add("True"); - fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); List RollElemNames = new ArrayList(); RollElemNames.add("0"); @@ -77,32 +67,9 @@ public class ManualControlCommand extends UAVDataObject { YawElemNames.add("0"); fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Manual"); - FlightModeEnumOptions.add("Stabilized1"); - FlightModeEnumOptions.add("Stabilized2"); - FlightModeEnumOptions.add("Stabilized3"); - FlightModeEnumOptions.add("VelocityControl"); - FlightModeEnumOptions.add("PositionHold"); - fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + List CollectiveElemNames = new ArrayList(); + CollectiveElemNames.add("0"); + fields.add( new UAVObjectField("Collective", "%", UAVObjectField.FieldType.FLOAT32, CollectiveElemNames, null) ); List ChannelElemNames = new ArrayList(); ChannelElemNames.add("0"); @@ -113,8 +80,16 @@ public class ManualControlCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -188,7 +163,7 @@ public class ManualControlCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0x926794; + protected static final int OBJID = 0x1E82C2D2; protected static final String NAME = "ManualControlCommand"; protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index 83697999a..bb846695d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,125 +51,77 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); - List InputModeElemNames = new ArrayList(); - InputModeElemNames.add("0"); - List InputModeEnumOptions = new ArrayList(); - InputModeEnumOptions.add("PWM"); - InputModeEnumOptions.add("PPM"); - InputModeEnumOptions.add("Spektrum"); - fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("Throttle"); + ChannelMinElemNames.add("Roll"); + ChannelMinElemNames.add("Pitch"); + ChannelMinElemNames.add("Yaw"); + ChannelMinElemNames.add("FlightMode"); + ChannelMinElemNames.add("Collective"); + ChannelMinElemNames.add("Accessory0"); + ChannelMinElemNames.add("Accessory1"); + ChannelMinElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - List RollEnumOptions = new ArrayList(); - RollEnumOptions.add("Channel1"); - RollEnumOptions.add("Channel2"); - RollEnumOptions.add("Channel3"); - RollEnumOptions.add("Channel4"); - RollEnumOptions.add("Channel5"); - RollEnumOptions.add("Channel6"); - RollEnumOptions.add("Channel7"); - RollEnumOptions.add("Channel8"); - RollEnumOptions.add("None"); - fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("Throttle"); + ChannelNeutralElemNames.add("Roll"); + ChannelNeutralElemNames.add("Pitch"); + ChannelNeutralElemNames.add("Yaw"); + ChannelNeutralElemNames.add("FlightMode"); + ChannelNeutralElemNames.add("Collective"); + ChannelNeutralElemNames.add("Accessory0"); + ChannelNeutralElemNames.add("Accessory1"); + ChannelNeutralElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - List PitchEnumOptions = new ArrayList(); - PitchEnumOptions.add("Channel1"); - PitchEnumOptions.add("Channel2"); - PitchEnumOptions.add("Channel3"); - PitchEnumOptions.add("Channel4"); - PitchEnumOptions.add("Channel5"); - PitchEnumOptions.add("Channel6"); - PitchEnumOptions.add("Channel7"); - PitchEnumOptions.add("Channel8"); - PitchEnumOptions.add("None"); - fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("Throttle"); + ChannelMaxElemNames.add("Roll"); + ChannelMaxElemNames.add("Pitch"); + ChannelMaxElemNames.add("Yaw"); + ChannelMaxElemNames.add("FlightMode"); + ChannelMaxElemNames.add("Collective"); + ChannelMaxElemNames.add("Accessory0"); + ChannelMaxElemNames.add("Accessory1"); + ChannelMaxElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - List YawEnumOptions = new ArrayList(); - YawEnumOptions.add("Channel1"); - YawEnumOptions.add("Channel2"); - YawEnumOptions.add("Channel3"); - YawEnumOptions.add("Channel4"); - YawEnumOptions.add("Channel5"); - YawEnumOptions.add("Channel6"); - YawEnumOptions.add("Channel7"); - YawEnumOptions.add("Channel8"); - YawEnumOptions.add("None"); - fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - List ThrottleEnumOptions = new ArrayList(); - ThrottleEnumOptions.add("Channel1"); - ThrottleEnumOptions.add("Channel2"); - ThrottleEnumOptions.add("Channel3"); - ThrottleEnumOptions.add("Channel4"); - ThrottleEnumOptions.add("Channel5"); - ThrottleEnumOptions.add("Channel6"); - ThrottleEnumOptions.add("Channel7"); - ThrottleEnumOptions.add("Channel8"); - ThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + List ChannelGroupsElemNames = new ArrayList(); + ChannelGroupsElemNames.add("Throttle"); + ChannelGroupsElemNames.add("Roll"); + ChannelGroupsElemNames.add("Pitch"); + ChannelGroupsElemNames.add("Yaw"); + ChannelGroupsElemNames.add("FlightMode"); + ChannelGroupsElemNames.add("Collective"); + ChannelGroupsElemNames.add("Accessory0"); + ChannelGroupsElemNames.add("Accessory1"); + ChannelGroupsElemNames.add("Accessory2"); + List ChannelGroupsEnumOptions = new ArrayList(); + ChannelGroupsEnumOptions.add("PWM"); + ChannelGroupsEnumOptions.add("PPM"); + ChannelGroupsEnumOptions.add("DSM (MainPort)"); + ChannelGroupsEnumOptions.add("DSM (FlexiPort)"); + ChannelGroupsEnumOptions.add("S.Bus"); + ChannelGroupsEnumOptions.add("GCS"); + ChannelGroupsEnumOptions.add("None"); + fields.add( new UAVObjectField("ChannelGroups", "Channel Group", UAVObjectField.FieldType.ENUM, ChannelGroupsElemNames, ChannelGroupsEnumOptions) ); - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Channel1"); - FlightModeEnumOptions.add("Channel2"); - FlightModeEnumOptions.add("Channel3"); - FlightModeEnumOptions.add("Channel4"); - FlightModeEnumOptions.add("Channel5"); - FlightModeEnumOptions.add("Channel6"); - FlightModeEnumOptions.add("Channel7"); - FlightModeEnumOptions.add("Channel8"); - FlightModeEnumOptions.add("None"); - fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - List Accessory1EnumOptions = new ArrayList(); - Accessory1EnumOptions.add("Channel1"); - Accessory1EnumOptions.add("Channel2"); - Accessory1EnumOptions.add("Channel3"); - Accessory1EnumOptions.add("Channel4"); - Accessory1EnumOptions.add("Channel5"); - Accessory1EnumOptions.add("Channel6"); - Accessory1EnumOptions.add("Channel7"); - Accessory1EnumOptions.add("Channel8"); - Accessory1EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - List Accessory2EnumOptions = new ArrayList(); - Accessory2EnumOptions.add("Channel1"); - Accessory2EnumOptions.add("Channel2"); - Accessory2EnumOptions.add("Channel3"); - Accessory2EnumOptions.add("Channel4"); - Accessory2EnumOptions.add("Channel5"); - Accessory2EnumOptions.add("Channel6"); - Accessory2EnumOptions.add("Channel7"); - Accessory2EnumOptions.add("Channel8"); - Accessory2EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - List Accessory3EnumOptions = new ArrayList(); - Accessory3EnumOptions.add("Channel1"); - Accessory3EnumOptions.add("Channel2"); - Accessory3EnumOptions.add("Channel3"); - Accessory3EnumOptions.add("Channel4"); - Accessory3EnumOptions.add("Channel5"); - Accessory3EnumOptions.add("Channel6"); - Accessory3EnumOptions.add("Channel7"); - Accessory3EnumOptions.add("Channel8"); - Accessory3EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + List ChannelNumberElemNames = new ArrayList(); + ChannelNumberElemNames.add("Throttle"); + ChannelNumberElemNames.add("Roll"); + ChannelNumberElemNames.add("Pitch"); + ChannelNumberElemNames.add("Yaw"); + ChannelNumberElemNames.add("FlightMode"); + ChannelNumberElemNames.add("Collective"); + ChannelNumberElemNames.add("Accessory0"); + ChannelNumberElemNames.add("Accessory1"); + ChannelNumberElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNumber", "channel", UAVObjectField.FieldType.UINT8, ChannelNumberElemNames, null) ); List ArmingElemNames = new ArrayList(); ArmingElemNames.add("0"); @@ -192,6 +144,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("None"); Stabilization1SettingsEnumOptions.add("Rate"); Stabilization1SettingsEnumOptions.add("Attitude"); + Stabilization1SettingsEnumOptions.add("AxisLock"); + Stabilization1SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -202,6 +156,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("None"); Stabilization2SettingsEnumOptions.add("Rate"); Stabilization2SettingsEnumOptions.add("Attitude"); + Stabilization2SettingsEnumOptions.add("AxisLock"); + Stabilization2SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -212,6 +168,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("None"); Stabilization3SettingsEnumOptions.add("Rate"); Stabilization3SettingsEnumOptions.add("Attitude"); + Stabilization3SettingsEnumOptions.add("AxisLock"); + Stabilization3SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -227,43 +185,6 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("PositionHold"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); - List ChannelMaxElemNames = new ArrayList(); - ChannelMaxElemNames.add("0"); - ChannelMaxElemNames.add("1"); - ChannelMaxElemNames.add("2"); - ChannelMaxElemNames.add("3"); - ChannelMaxElemNames.add("4"); - ChannelMaxElemNames.add("5"); - ChannelMaxElemNames.add("6"); - ChannelMaxElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - - List ChannelNeutralElemNames = new ArrayList(); - ChannelNeutralElemNames.add("0"); - ChannelNeutralElemNames.add("1"); - ChannelNeutralElemNames.add("2"); - ChannelNeutralElemNames.add("3"); - ChannelNeutralElemNames.add("4"); - ChannelNeutralElemNames.add("5"); - ChannelNeutralElemNames.add("6"); - ChannelNeutralElemNames.add("7"); - fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - - List ChannelMinElemNames = new ArrayList(); - ChannelMinElemNames.add("0"); - ChannelMinElemNames.add("1"); - ChannelMinElemNames.add("2"); - ChannelMinElemNames.add("3"); - ChannelMinElemNames.add("4"); - ChannelMinElemNames.add("5"); - ChannelMinElemNames.add("6"); - ChannelMinElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - - List ArmedTimeoutElemNames = new ArrayList(); - ArmedTimeoutElemNames.add("0"); - fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -309,44 +230,6 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue("PWM"); - getField("Roll").setValue("Channel1"); - getField("Pitch").setValue("Channel2"); - getField("Yaw").setValue("Channel3"); - getField("Throttle").setValue("Channel4"); - getField("FlightMode").setValue("Channel5"); - getField("Accessory1").setValue("None"); - getField("Accessory2").setValue("None"); - getField("Accessory3").setValue("None"); - getField("Arming").setValue("Always Disarmed"); - getField("Stabilization1Settings").setValue("Attitude",0); - getField("Stabilization1Settings").setValue("Attitude",1); - getField("Stabilization1Settings").setValue("Attitude",2); - getField("Stabilization2Settings").setValue("Attitude",0); - getField("Stabilization2Settings").setValue("Attitude",1); - getField("Stabilization2Settings").setValue("Attitude",2); - getField("Stabilization3Settings").setValue("Attitude",0); - getField("Stabilization3Settings").setValue("Attitude",1); - getField("Stabilization3Settings").setValue("Attitude",2); - getField("FlightModePosition").setValue("Manual",0); - getField("FlightModePosition").setValue("Manual",1); - getField("FlightModePosition").setValue("Manual",2); - getField("ChannelMax").setValue(2000,0); - getField("ChannelMax").setValue(2000,1); - getField("ChannelMax").setValue(2000,2); - getField("ChannelMax").setValue(2000,3); - getField("ChannelMax").setValue(2000,4); - getField("ChannelMax").setValue(2000,5); - getField("ChannelMax").setValue(2000,6); - getField("ChannelMax").setValue(2000,7); - getField("ChannelNeutral").setValue(1500,0); - getField("ChannelNeutral").setValue(1500,1); - getField("ChannelNeutral").setValue(1500,2); - getField("ChannelNeutral").setValue(1500,3); - getField("ChannelNeutral").setValue(1500,4); - getField("ChannelNeutral").setValue(1500,5); - getField("ChannelNeutral").setValue(1500,6); - getField("ChannelNeutral").setValue(1500,7); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -355,7 +238,57 @@ public class ManualControlSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelNeutral").setValue(1500,8); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelMax").setValue(2000,8); getField("ArmedTimeout").setValue(30000); + getField("ChannelGroups").setValue("None",0); + getField("ChannelGroups").setValue("None",1); + getField("ChannelGroups").setValue("None",2); + getField("ChannelGroups").setValue("None",3); + getField("ChannelGroups").setValue("None",4); + getField("ChannelGroups").setValue("None",5); + getField("ChannelGroups").setValue("None",6); + getField("ChannelGroups").setValue("None",7); + getField("ChannelGroups").setValue("None",8); + getField("ChannelNumber").setValue(0,0); + getField("ChannelNumber").setValue(0,1); + getField("ChannelNumber").setValue(0,2); + getField("ChannelNumber").setValue(0,3); + getField("ChannelNumber").setValue(0,4); + getField("ChannelNumber").setValue(0,5); + getField("ChannelNumber").setValue(0,6); + getField("ChannelNumber").setValue(0,7); + getField("ChannelNumber").setValue(0,8); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Rate",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Rate",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Rate",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Stabilized1",1); + getField("FlightModePosition").setValue("Stabilized2",2); } @@ -384,7 +317,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2B82102; + protected static final int OBJID = 0x24959BB0; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 9aa87d49e..76841d8ff 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -83,12 +83,37 @@ public class MixerSettings extends UAVDataObject { ThrottleCurve2ElemNames.add("100"); fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + List Curve2SourceElemNames = new ArrayList(); + Curve2SourceElemNames.add("0"); + List Curve2SourceEnumOptions = new ArrayList(); + Curve2SourceEnumOptions.add("Throttle"); + Curve2SourceEnumOptions.add("Roll"); + Curve2SourceEnumOptions.add("Pitch"); + Curve2SourceEnumOptions.add("Yaw"); + Curve2SourceEnumOptions.add("Collective"); + Curve2SourceEnumOptions.add("Accessory0"); + Curve2SourceEnumOptions.add("Accessory1"); + Curve2SourceEnumOptions.add("Accessory2"); + Curve2SourceEnumOptions.add("Accessory3"); + Curve2SourceEnumOptions.add("Accessory4"); + Curve2SourceEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Curve2Source", "", UAVObjectField.FieldType.ENUM, Curve2SourceElemNames, Curve2SourceEnumOptions) ); + List Mixer1TypeElemNames = new ArrayList(); Mixer1TypeElemNames.add("0"); List Mixer1TypeEnumOptions = new ArrayList(); Mixer1TypeEnumOptions.add("Disabled"); Mixer1TypeEnumOptions.add("Motor"); Mixer1TypeEnumOptions.add("Servo"); + Mixer1TypeEnumOptions.add("CameraRoll"); + Mixer1TypeEnumOptions.add("CameraPitch"); + Mixer1TypeEnumOptions.add("CameraYaw"); + Mixer1TypeEnumOptions.add("Accessory0"); + Mixer1TypeEnumOptions.add("Accessory1"); + Mixer1TypeEnumOptions.add("Accessory2"); + Mixer1TypeEnumOptions.add("Accessory3"); + Mixer1TypeEnumOptions.add("Accessory4"); + Mixer1TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); List Mixer1VectorElemNames = new ArrayList(); @@ -105,6 +130,15 @@ public class MixerSettings extends UAVDataObject { Mixer2TypeEnumOptions.add("Disabled"); Mixer2TypeEnumOptions.add("Motor"); Mixer2TypeEnumOptions.add("Servo"); + Mixer2TypeEnumOptions.add("CameraRoll"); + Mixer2TypeEnumOptions.add("CameraPitch"); + Mixer2TypeEnumOptions.add("CameraYaw"); + Mixer2TypeEnumOptions.add("Accessory0"); + Mixer2TypeEnumOptions.add("Accessory1"); + Mixer2TypeEnumOptions.add("Accessory2"); + Mixer2TypeEnumOptions.add("Accessory3"); + Mixer2TypeEnumOptions.add("Accessory4"); + Mixer2TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); List Mixer2VectorElemNames = new ArrayList(); @@ -121,6 +155,15 @@ public class MixerSettings extends UAVDataObject { Mixer3TypeEnumOptions.add("Disabled"); Mixer3TypeEnumOptions.add("Motor"); Mixer3TypeEnumOptions.add("Servo"); + Mixer3TypeEnumOptions.add("CameraRoll"); + Mixer3TypeEnumOptions.add("CameraPitch"); + Mixer3TypeEnumOptions.add("CameraYaw"); + Mixer3TypeEnumOptions.add("Accessory0"); + Mixer3TypeEnumOptions.add("Accessory1"); + Mixer3TypeEnumOptions.add("Accessory2"); + Mixer3TypeEnumOptions.add("Accessory3"); + Mixer3TypeEnumOptions.add("Accessory4"); + Mixer3TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); List Mixer3VectorElemNames = new ArrayList(); @@ -137,6 +180,15 @@ public class MixerSettings extends UAVDataObject { Mixer4TypeEnumOptions.add("Disabled"); Mixer4TypeEnumOptions.add("Motor"); Mixer4TypeEnumOptions.add("Servo"); + Mixer4TypeEnumOptions.add("CameraRoll"); + Mixer4TypeEnumOptions.add("CameraPitch"); + Mixer4TypeEnumOptions.add("CameraYaw"); + Mixer4TypeEnumOptions.add("Accessory0"); + Mixer4TypeEnumOptions.add("Accessory1"); + Mixer4TypeEnumOptions.add("Accessory2"); + Mixer4TypeEnumOptions.add("Accessory3"); + Mixer4TypeEnumOptions.add("Accessory4"); + Mixer4TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); List Mixer4VectorElemNames = new ArrayList(); @@ -153,6 +205,15 @@ public class MixerSettings extends UAVDataObject { Mixer5TypeEnumOptions.add("Disabled"); Mixer5TypeEnumOptions.add("Motor"); Mixer5TypeEnumOptions.add("Servo"); + Mixer5TypeEnumOptions.add("CameraRoll"); + Mixer5TypeEnumOptions.add("CameraPitch"); + Mixer5TypeEnumOptions.add("CameraYaw"); + Mixer5TypeEnumOptions.add("Accessory0"); + Mixer5TypeEnumOptions.add("Accessory1"); + Mixer5TypeEnumOptions.add("Accessory2"); + Mixer5TypeEnumOptions.add("Accessory3"); + Mixer5TypeEnumOptions.add("Accessory4"); + Mixer5TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); List Mixer5VectorElemNames = new ArrayList(); @@ -169,6 +230,15 @@ public class MixerSettings extends UAVDataObject { Mixer6TypeEnumOptions.add("Disabled"); Mixer6TypeEnumOptions.add("Motor"); Mixer6TypeEnumOptions.add("Servo"); + Mixer6TypeEnumOptions.add("CameraRoll"); + Mixer6TypeEnumOptions.add("CameraPitch"); + Mixer6TypeEnumOptions.add("CameraYaw"); + Mixer6TypeEnumOptions.add("Accessory0"); + Mixer6TypeEnumOptions.add("Accessory1"); + Mixer6TypeEnumOptions.add("Accessory2"); + Mixer6TypeEnumOptions.add("Accessory3"); + Mixer6TypeEnumOptions.add("Accessory4"); + Mixer6TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); List Mixer6VectorElemNames = new ArrayList(); @@ -185,6 +255,15 @@ public class MixerSettings extends UAVDataObject { Mixer7TypeEnumOptions.add("Disabled"); Mixer7TypeEnumOptions.add("Motor"); Mixer7TypeEnumOptions.add("Servo"); + Mixer7TypeEnumOptions.add("CameraRoll"); + Mixer7TypeEnumOptions.add("CameraPitch"); + Mixer7TypeEnumOptions.add("CameraYaw"); + Mixer7TypeEnumOptions.add("Accessory0"); + Mixer7TypeEnumOptions.add("Accessory1"); + Mixer7TypeEnumOptions.add("Accessory2"); + Mixer7TypeEnumOptions.add("Accessory3"); + Mixer7TypeEnumOptions.add("Accessory4"); + Mixer7TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); List Mixer7VectorElemNames = new ArrayList(); @@ -201,6 +280,15 @@ public class MixerSettings extends UAVDataObject { Mixer8TypeEnumOptions.add("Disabled"); Mixer8TypeEnumOptions.add("Motor"); Mixer8TypeEnumOptions.add("Servo"); + Mixer8TypeEnumOptions.add("CameraRoll"); + Mixer8TypeEnumOptions.add("CameraPitch"); + Mixer8TypeEnumOptions.add("CameraYaw"); + Mixer8TypeEnumOptions.add("Accessory0"); + Mixer8TypeEnumOptions.add("Accessory1"); + Mixer8TypeEnumOptions.add("Accessory2"); + Mixer8TypeEnumOptions.add("Accessory3"); + Mixer8TypeEnumOptions.add("Accessory4"); + Mixer8TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); List Mixer8VectorElemNames = new ArrayList(); @@ -211,6 +299,56 @@ public class MixerSettings extends UAVDataObject { Mixer8VectorElemNames.add("Yaw"); fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + List Mixer9TypeElemNames = new ArrayList(); + Mixer9TypeElemNames.add("0"); + List Mixer9TypeEnumOptions = new ArrayList(); + Mixer9TypeEnumOptions.add("Disabled"); + Mixer9TypeEnumOptions.add("Motor"); + Mixer9TypeEnumOptions.add("Servo"); + Mixer9TypeEnumOptions.add("CameraRoll"); + Mixer9TypeEnumOptions.add("CameraPitch"); + Mixer9TypeEnumOptions.add("CameraYaw"); + Mixer9TypeEnumOptions.add("Accessory0"); + Mixer9TypeEnumOptions.add("Accessory1"); + Mixer9TypeEnumOptions.add("Accessory2"); + Mixer9TypeEnumOptions.add("Accessory3"); + Mixer9TypeEnumOptions.add("Accessory4"); + Mixer9TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer9Type", "", UAVObjectField.FieldType.ENUM, Mixer9TypeElemNames, Mixer9TypeEnumOptions) ); + + List Mixer9VectorElemNames = new ArrayList(); + Mixer9VectorElemNames.add("ThrottleCurve1"); + Mixer9VectorElemNames.add("ThrottleCurve2"); + Mixer9VectorElemNames.add("Roll"); + Mixer9VectorElemNames.add("Pitch"); + Mixer9VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer9Vector", "", UAVObjectField.FieldType.INT8, Mixer9VectorElemNames, null) ); + + List Mixer10TypeElemNames = new ArrayList(); + Mixer10TypeElemNames.add("0"); + List Mixer10TypeEnumOptions = new ArrayList(); + Mixer10TypeEnumOptions.add("Disabled"); + Mixer10TypeEnumOptions.add("Motor"); + Mixer10TypeEnumOptions.add("Servo"); + Mixer10TypeEnumOptions.add("CameraRoll"); + Mixer10TypeEnumOptions.add("CameraPitch"); + Mixer10TypeEnumOptions.add("CameraYaw"); + Mixer10TypeEnumOptions.add("Accessory0"); + Mixer10TypeEnumOptions.add("Accessory1"); + Mixer10TypeEnumOptions.add("Accessory2"); + Mixer10TypeEnumOptions.add("Accessory3"); + Mixer10TypeEnumOptions.add("Accessory4"); + Mixer10TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer10Type", "", UAVObjectField.FieldType.ENUM, Mixer10TypeElemNames, Mixer10TypeEnumOptions) ); + + List Mixer10VectorElemNames = new ArrayList(); + Mixer10VectorElemNames.add("ThrottleCurve1"); + Mixer10VectorElemNames.add("ThrottleCurve2"); + Mixer10VectorElemNames.add("Roll"); + Mixer10VectorElemNames.add("Pitch"); + Mixer10VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer10Vector", "", UAVObjectField.FieldType.INT8, Mixer10VectorElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -261,15 +399,16 @@ public class MixerSettings extends UAVDataObject { getField("AccelTime").setValue(0); getField("DecelTime").setValue(0); getField("ThrottleCurve1").setValue(0,0); - getField("ThrottleCurve1").setValue(0.25,1); - getField("ThrottleCurve1").setValue(0.5,2); - getField("ThrottleCurve1").setValue(0.75,3); - getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve1").setValue(0,1); + getField("ThrottleCurve1").setValue(0,2); + getField("ThrottleCurve1").setValue(0,3); + getField("ThrottleCurve1").setValue(0,4); getField("ThrottleCurve2").setValue(0,0); getField("ThrottleCurve2").setValue(0.25,1); getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); + getField("Curve2Source").setValue("Throttle"); getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); @@ -318,6 +457,18 @@ public class MixerSettings extends UAVDataObject { getField("Mixer8Vector").setValue(0,2); getField("Mixer8Vector").setValue(0,3); getField("Mixer8Vector").setValue(0,4); + getField("Mixer9Type").setValue("Disabled"); + getField("Mixer9Vector").setValue(0,0); + getField("Mixer9Vector").setValue(0,1); + getField("Mixer9Vector").setValue(0,2); + getField("Mixer9Vector").setValue(0,3); + getField("Mixer9Vector").setValue(0,4); + getField("Mixer10Type").setValue("Disabled"); + getField("Mixer10Vector").setValue(0,0); + getField("Mixer10Vector").setValue(0,1); + getField("Mixer10Vector").setValue(0,2); + getField("Mixer10Vector").setValue(0,3); + getField("Mixer10Vector").setValue(0,4); } @@ -346,7 +497,7 @@ public class MixerSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4FAE374E; + protected static final int OBJID = 0x5D16D6C4; protected static final String NAME = "MixerSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index fbd405b40..106220a8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -156,7 +156,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF6A33F10; + protected static final int OBJID = 0x11CFB4E6; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index f16ddd199..3b09dd1f8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -136,7 +136,7 @@ public class NedAccel extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8E852CE8; + protected static final int OBJID = 0x7C7F5BC0; protected static final String NAME = "NedAccel"; protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index 2a09c2b40..dccd85d36 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -51,12 +51,23 @@ public class ObjectPersistence extends UAVDataObject { List fields = new ArrayList(); + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + List OperationElemNames = new ArrayList(); OperationElemNames.add("0"); List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("NOP"); OperationEnumOptions.add("Load"); OperationEnumOptions.add("Save"); OperationEnumOptions.add("Delete"); + OperationEnumOptions.add("FullErase"); + OperationEnumOptions.add("Completed"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -68,14 +79,6 @@ public class ObjectPersistence extends UAVDataObject { SelectionEnumOptions.add("AllObjects"); fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); - List ObjectIDElemNames = new ArrayList(); - ObjectIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); - - List InstanceIDElemNames = new ArrayList(); - InstanceIDElemNames.add("0"); - fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -106,7 +109,7 @@ public class ObjectPersistence extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; @@ -149,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0x22216832; + protected static final int OBJID = 0xF69AD8B8; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 444009f90..ac30ad4f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE0739636; + protected static final int OBJID = 0xF9691DA4; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 5cf51df71..2ff5a5586 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2FC4E5BA; + protected static final int OBJID = 0x33C9EAB4; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index 7164c0957..ddeacd8d4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -136,7 +136,7 @@ public class RateDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xBA41B51C; + protected static final int OBJID = 0xCE8C826; protected static final String NAME = "RateDesired"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java similarity index 61% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index 6af673930..a40b27e38 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Battery configuration information. + * Monitors which receiver channels have been active within the last second. * * @see The GNU Public License (GPL) Version 3 * @@ -39,40 +39,33 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Battery configuration information. +Monitors which receiver channels have been active within the last second. -generated from batterysettings.xml +generated from receiveractivity.xml **/ -public class BatterySettings extends UAVDataObject { +public class ReceiverActivity extends UAVDataObject { - public BatterySettings() { + public ReceiverActivity() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List BatteryVoltageElemNames = new ArrayList(); - BatteryVoltageElemNames.add("0"); - fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + List ActiveGroupElemNames = new ArrayList(); + ActiveGroupElemNames.add("0"); + List ActiveGroupEnumOptions = new ArrayList(); + ActiveGroupEnumOptions.add("PWM"); + ActiveGroupEnumOptions.add("PPM"); + ActiveGroupEnumOptions.add("DSM (MainPort)"); + ActiveGroupEnumOptions.add("DSM (FlexiPort)"); + ActiveGroupEnumOptions.add("S.Bus"); + ActiveGroupEnumOptions.add("GCS"); + ActiveGroupEnumOptions.add("None"); + fields.add( new UAVObjectField("ActiveGroup", "Channel Group", UAVObjectField.FieldType.ENUM, ActiveGroupElemNames, ActiveGroupEnumOptions) ); - List BatteryCapacityElemNames = new ArrayList(); - BatteryCapacityElemNames.add("0"); - fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); - - List BatteryTypeElemNames = new ArrayList(); - BatteryTypeElemNames.add("0"); - List BatteryTypeEnumOptions = new ArrayList(); - BatteryTypeEnumOptions.add("LiPo"); - BatteryTypeEnumOptions.add("A123"); - BatteryTypeEnumOptions.add("LiCo"); - BatteryTypeEnumOptions.add("LiFeSO4"); - BatteryTypeEnumOptions.add("None"); - fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); - - List CalibrationsElemNames = new ArrayList(); - CalibrationsElemNames.add("Voltage"); - CalibrationsElemNames.add("Current"); - fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + List ActiveChannelElemNames = new ArrayList(); + ActiveChannelElemNames.add("0"); + fields.add( new UAVObjectField("ActiveChannel", "channel", UAVObjectField.FieldType.UINT8, ActiveChannelElemNames, null) ); // Compute the number of bytes for this object @@ -97,13 +90,13 @@ public class BatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; metadata.gcsTelemetryUpdatePeriod = 0; metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; @@ -119,11 +112,8 @@ public class BatterySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("BatteryVoltage").setValue(11.1); - getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue("LiPo"); - getField("Calibrations").setValue(1,0); - getField("Calibrations").setValue(1,1); + getField("ActiveGroup").setValue("None"); + getField("ActiveChannel").setValue(255); } @@ -135,7 +125,7 @@ public class BatterySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - BatterySettings obj = new BatterySettings(); + ReceiverActivity obj = new ReceiverActivity(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -146,17 +136,17 @@ public class BatterySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + public ReceiverActivity GetInstance(UAVObjectManager objMngr, int instID) { - return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + return (ReceiverActivity)(objMngr.getObject(ReceiverActivity.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA5FF1D9A; - protected static final String NAME = "BatterySettings"; - protected static String DESCRIPTION = "Battery configuration information."; + protected static final int OBJID = 0x1E7C53DA; + protected static final String NAME = "ReceiverActivity"; + protected static String DESCRIPTION = "Monitors which receiver channels have been active within the last second."; protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 4e9f0b8b8..18cf6f4d6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -128,7 +128,7 @@ public class SonarAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1FDD844C; + protected static final int OBJID = 0x6C5A0CBC; protected static final String NAME = "SonarAltitude"; protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 8cba8a54c..32d2c735c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -75,6 +75,8 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("None"); StabilizationModeEnumOptions.add("Rate"); StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + StabilizationModeEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -150,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x41AA9DC2; + protected static final int OBJID = 0xDB8FFC3C; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index 74c480e1c..ab78bdc74 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -51,18 +51,6 @@ public class StabilizationSettings extends UAVDataObject { List fields = new ArrayList(); - List RollMaxElemNames = new ArrayList(); - RollMaxElemNames.add("0"); - fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); - - List PitchMaxElemNames = new ArrayList(); - PitchMaxElemNames.add("0"); - fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); - - List YawMaxElemNames = new ArrayList(); - YawMaxElemNames.add("0"); - fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); - List ManualRateElemNames = new ArrayList(); ManualRateElemNames.add("Roll"); ManualRateElemNames.add("Pitch"); @@ -75,23 +63,26 @@ public class StabilizationSettings extends UAVDataObject { MaximumRateElemNames.add("Yaw"); fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); - List RollRatePIElemNames = new ArrayList(); - RollRatePIElemNames.add("Kp"); - RollRatePIElemNames.add("Ki"); - RollRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + List RollRatePIDElemNames = new ArrayList(); + RollRatePIDElemNames.add("Kp"); + RollRatePIDElemNames.add("Ki"); + RollRatePIDElemNames.add("Kd"); + RollRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePID", "", UAVObjectField.FieldType.FLOAT32, RollRatePIDElemNames, null) ); - List PitchRatePIElemNames = new ArrayList(); - PitchRatePIElemNames.add("Kp"); - PitchRatePIElemNames.add("Ki"); - PitchRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + List PitchRatePIDElemNames = new ArrayList(); + PitchRatePIDElemNames.add("Kp"); + PitchRatePIDElemNames.add("Ki"); + PitchRatePIDElemNames.add("Kd"); + PitchRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePID", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIDElemNames, null) ); - List YawRatePIElemNames = new ArrayList(); - YawRatePIElemNames.add("Kp"); - YawRatePIElemNames.add("Ki"); - YawRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + List YawRatePIDElemNames = new ArrayList(); + YawRatePIDElemNames.add("Kp"); + YawRatePIDElemNames.add("Ki"); + YawRatePIDElemNames.add("Kd"); + YawRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePID", "", UAVObjectField.FieldType.FLOAT32, YawRatePIDElemNames, null) ); List RollPIElemNames = new ArrayList(); RollPIElemNames.add("Kp"); @@ -111,6 +102,45 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List GyroTauElemNames = new ArrayList(); + GyroTauElemNames.add("0"); + fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); + + List WeakLevelingKpElemNames = new ArrayList(); + WeakLevelingKpElemNames.add("0"); + fields.add( new UAVObjectField("WeakLevelingKp", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, WeakLevelingKpElemNames, null) ); + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List MaxAxisLockElemNames = new ArrayList(); + MaxAxisLockElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxAxisLockRateElemNames, null) ); + + List MaxWeakLevelingRateElemNames = new ArrayList(); + MaxWeakLevelingRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxWeakLevelingRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxWeakLevelingRateElemNames, null) ); + + List LowThrottleZeroIntegralElemNames = new ArrayList(); + LowThrottleZeroIntegralElemNames.add("0"); + List LowThrottleZeroIntegralEnumOptions = new ArrayList(); + LowThrottleZeroIntegralEnumOptions.add("FALSE"); + LowThrottleZeroIntegralEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LowThrottleZeroIntegral", "", UAVObjectField.FieldType.ENUM, LowThrottleZeroIntegralElemNames, LowThrottleZeroIntegralEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,24 +186,24 @@ public class StabilizationSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("RollMax").setValue(35); - getField("PitchMax").setValue(35); - getField("YawMax").setValue(35); getField("ManualRate").setValue(150,0); getField("ManualRate").setValue(150,1); getField("ManualRate").setValue(150,2); getField("MaximumRate").setValue(300,0); getField("MaximumRate").setValue(300,1); getField("MaximumRate").setValue(300,2); - getField("RollRatePI").setValue(0.0015,0); - getField("RollRatePI").setValue(0,1); - getField("RollRatePI").setValue(0.3,2); - getField("PitchRatePI").setValue(0.0015,0); - getField("PitchRatePI").setValue(0,1); - getField("PitchRatePI").setValue(0.3,2); - getField("YawRatePI").setValue(0.003,0); - getField("YawRatePI").setValue(0,1); - getField("YawRatePI").setValue(0.3,2); + getField("RollRatePID").setValue(0.002,0); + getField("RollRatePID").setValue(0,1); + getField("RollRatePID").setValue(0,2); + getField("RollRatePID").setValue(0.3,3); + getField("PitchRatePID").setValue(0.002,0); + getField("PitchRatePID").setValue(0,1); + getField("PitchRatePID").setValue(0,2); + getField("PitchRatePID").setValue(0.3,3); + getField("YawRatePID").setValue(0.0035,0); + getField("YawRatePID").setValue(0.0035,1); + getField("YawRatePID").setValue(0,2); + getField("YawRatePID").setValue(0.3,3); getField("RollPI").setValue(2,0); getField("RollPI").setValue(0,1); getField("RollPI").setValue(50,2); @@ -183,6 +213,15 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("GyroTau").setValue(0.005); + getField("WeakLevelingKp").setValue(0.1); + getField("RollMax").setValue(55); + getField("PitchMax").setValue(55); + getField("YawMax").setValue(35); + getField("MaxAxisLock").setValue(15); + getField("MaxAxisLockRate").setValue(2); + getField("MaxWeakLevelingRate").setValue(5); + getField("LowThrottleZeroIntegral").setValue("TRUE"); } @@ -211,7 +250,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE2147404; + protected static final int OBJID = 0x5F78C51E; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index e9313472c..458dd9d10 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -68,6 +68,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); + AlarmElemNames.add("BootFault"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -106,8 +107,8 @@ public class SystemAlarms extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 4000; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; metadata.loggingUpdatePeriod = 1000; @@ -137,6 +138,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",13); getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); + getField("Alarm").setValue("Uninitialised",16); } @@ -165,7 +167,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x89C3DCB2; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index 99bceb6ba..e3c2cf0b0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -51,6 +51,11 @@ public class SystemSettings extends UAVDataObject { List fields = new ArrayList(); + List GUIConfigDataElemNames = new ArrayList(); + GUIConfigDataElemNames.add("0"); + GUIConfigDataElemNames.add("1"); + fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); + List AirframeTypeElemNames = new ArrayList(); AirframeTypeElemNames.add("0"); List AirframeTypeEnumOptions = new ArrayList(); @@ -117,6 +122,8 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GUIConfigData").setValue(0,0); + getField("GUIConfigData").setValue(0,1); getField("AirframeType").setValue("FixedWing"); } @@ -146,7 +153,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x3875CEE; + protected static final int OBJID = 0x30BD5D7C; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 7c34360e9..d1c51d43f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -59,6 +59,10 @@ public class SystemStats extends UAVDataObject { HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + List IRQStackRemainingElemNames = new ArrayList(); + IRQStackRemainingElemNames.add("0"); + fields.add( new UAVObjectField("IRQStackRemaining", "bytes", UAVObjectField.FieldType.UINT16, IRQStackRemainingElemNames, null) ); + List CPULoadElemNames = new ArrayList(); CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); @@ -140,7 +144,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xAA26FFFA; + protected static final int OBJID = 0xD610A0F0; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 3ad065b5c..54825fafe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -65,6 +65,8 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("Com2UsbBridge"); + StackRemainingElemNames.add("Usb2ComBridge"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); @@ -81,11 +83,31 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("Stabilization"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("Com2UsbBridge"); + RunningElemNames.add("Usb2ComBridge"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("System"); + RunningTimeElemNames.add("Actuator"); + RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("TelemetryTx"); + RunningTimeElemNames.add("TelemetryTxPri"); + RunningTimeElemNames.add("TelemetryRx"); + RunningTimeElemNames.add("GPS"); + RunningTimeElemNames.add("ManualControl"); + RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("AHRSComms"); + RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("Guidance"); + RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("Com2UsbBridge"); + RunningTimeElemNames.add("Usb2ComBridge"); + fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -159,7 +181,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x50F599F0; + protected static final int OBJID = 0xE34A7C32; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index d1d47aebb..c2cf64d49 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,13 +28,14 @@ package org.openpilot.uavtalk.uavobjects; -//import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); @@ -45,19 +46,25 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); - objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new CameraDesired() ); + objMngr.registerObject( new CameraStabSettings() ); + objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); objMngr.registerObject( new FlightPlanSettings() ); objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightStatus() ); objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSReceiver() ); objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); @@ -68,6 +75,7 @@ public class UAVObjectsInitialize { objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new ReceiverActivity() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); @@ -75,7 +83,6 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); objMngr.registerObject( new TaskInfo() ); - objMngr.registerObject( new TelemetrySettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 649e6c122..97d038cfe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x48009C88; + protected static final int OBJID = 0x43007EB0; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 27f290898..f39fbd6de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x122F5E3A; + protected static final int OBJID = 0x25139D1A; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index 3adcad96b..acbdb43d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -132,7 +132,7 @@ public class WatchdogStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD646E910; + protected static final int OBJID = 0xA207FA7C; protected static final String NAME = "WatchdogStatus"; protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index e942b238f..dc593fd5f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -258,7 +258,7 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) outCode.replace(QString("$(INITFIELDS)"), initfields); // Write the java code - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->name + ".java", outCode ); if (!res) { cout << "Error: Could not write gcs output files" << endl; return false; From 92764ebc67b4240928dfeef5682442bb534c2ca6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 5 Apr 2012 23:35:04 -0500 Subject: [PATCH 089/165] Small upgrades to teh android install --- androidgcs/.classpath | 1 + androidgcs/proguard.cfg | 2 +- androidgcs/res/layout/gcs_home.xml | 50 ++++++++---- .../androidgcs/OPTelemetryService.java | 79 ++++++++++++++++++- 4 files changed, 114 insertions(+), 18 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index eb33e4360..c88f96260 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -5,5 +5,6 @@ + diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg index 12dd0392c..ec78e7622 100644 --- a/androidgcs/proguard.cfg +++ b/androidgcs/proguard.cfg @@ -14,7 +14,7 @@ -keep public class * extends android.preference.Preference -keep public class com.android.vending.licensing.ILicensingService --keepclasseswithmembernames class * { +-keepclasseswithmembers class * { native ; } diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index e07f5b003..0ff427bcd 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -1,15 +1,37 @@ - - - - + + + + + + + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index ce90f5a48..bc711560d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -71,21 +71,25 @@ public class OPTelemetryService extends Service { stopSelf(msg.arg2); break; case MSG_CONNECT: - Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - //int connection_type = Integer.decode(prefs.getString("connection_type", "")); - int connection_type = 1; + int connection_type = Integer.decode(prefs.getString("connection_type", "")); switch(connection_type) { case 0: // No connection return; case 1: + Toast.makeText(getApplicationContext(), "Attempting fake connection", Toast.LENGTH_SHORT).show(); activeTelem = new FakeTelemetryThread(); break; case 2: + Toast.makeText(getApplicationContext(), "Attempting BT connection", Toast.LENGTH_SHORT).show(); activeTelem = new BTTelemetryThread(); break; case 3: + Toast.makeText(getApplicationContext(), "Attempting TCP connection", Toast.LENGTH_SHORT).show(); + activeTelem = new TcpTelemetryThread(); + break; + default: throw new Error("Unsupported"); } activeTelem.start(); @@ -329,6 +333,75 @@ public class OPTelemetryService extends Service { }; + private class TcpTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + TcpTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); + + TcpUAVTalk tcp = new TcpUAVTalk(OPTelemetryService.this); + for( int i = 0; i < 10; i++ ) { + if (DEBUG) Log.d(TAG, "Attempting network Connection"); + + tcp.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( tcp.getConnected() ) + break; + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } + } + if( ! tcp.getConnected() ) { + return; + } + + + if (DEBUG) Log.d(TAG, "Connected via network"); + + uavTalk = tcp.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while( !terminate ) { + if( !uavTalk.processInputStream() ) + break; + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); From c1c12ed57e1356e5f16a3452389d89fdcfa91746 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 10:22:38 -0500 Subject: [PATCH 090/165] Add TCP UAVTalk interface for android --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 84 +++++++++++++++++++ 1 file changed, 84 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java new file mode 100644 index 000000000..ad503757e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -0,0 +1,84 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.net.InetAddress; +import java.net.Socket; +import java.net.UnknownHostException; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.content.Context; +import android.util.Log; + +public class TcpUAVTalk { + private final String TAG = "TcpUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String IP_ADDRESS = "127.0.0.1"; + public final static int PORT = 9001; + + private UAVTalk uavTalk; + private boolean connected; + + public TcpUAVTalk(Context caller) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + + connected = false; + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !openTelemetryTcp(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + + private boolean openTelemetryTcp(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + + InetAddress serverAddr = null; + try { + serverAddr = InetAddress.getByName(IP_ADDRESS); + } catch (UnknownHostException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + Socket socket = null; + try { + socket = new Socket(serverAddr,PORT); + } catch (IOException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} From 9d7c15fb7f625dd928e4a7b4fd1ea040436983cd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 11:59:50 -0500 Subject: [PATCH 091/165] Enable some debugging statements --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 4 ++-- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 3 ++- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 +++++++++++------- 4 files changed, 16 insertions(+), 11 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index ad503757e..47074f968 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -17,7 +17,7 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "127.0.0.1"; + public final static String IP_ADDRESS = "10.21.18.120"; public final static int PORT = 9001; private UAVTalk uavTalk; @@ -47,7 +47,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); InetAddress serverAddr = null; try { diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..11e6cb2ca 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index daedcc85b..903b6b29f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -185,7 +185,8 @@ public class TelemetryMonitor extends Observable{ // Force update if not yet connected gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - + if (DEBUG) Log.d(TAG,"GCS Status: " + gcsStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"Flight Status: " + flightStatsObj.getField("Status").getValue()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 39c1f6ee7..5a3a9a1a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -433,6 +433,7 @@ public class UAVTalk extends Observable { rxCSPacket = rxbyte; if (rxCS != rxCSPacket) { // packet error - faulty CRC + if (DEBUG) Log.d(TAG,"Bad crc"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -441,11 +442,14 @@ public class UAVTalk extends Observable { if (rxPacketLength != (packetSize + 1)) { // packet error - // mismatched packet // size + if (DEBUG) Log.d(TAG,"Bad size"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } + if (DEBUG) Log.d(TAG,"Received"); + rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; @@ -500,8 +504,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - // System.out.println("Received object ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -517,8 +521,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - // System.out.println("Received object request: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object request: " + objId + " " + + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); } else { @@ -534,8 +538,8 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - // System.out.println("Received ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From 097ae637bfa8f2dfe0fd64613c8ba9a6d2cf7eff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 12:06:36 -0500 Subject: [PATCH 092/165] Remove the TCHAIN_PREFIX flag from the OSX Makefile. No clue how that got merged in. --- flight/Revolution/Makefile.osx | 3 --- 1 file changed, 3 deletions(-) diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index e2c8ea694..a38bced0d 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -40,9 +40,6 @@ USE_BOOTLOADER ?= NO # Set to YES when using Code Sourcery toolchain CODE_SOURCERY ?= NO -# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- - # Remove command is different for Code Sourcery on Windows REMOVE_CMD ?= rm From 2257bc59531981d37b2330da7b0168e153fef62a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:42:19 -0500 Subject: [PATCH 093/165] Fix an insidious bug in the Android UAVObjectField unpack method for enums that was exposed by shuffling field orders. There goes 5 hours, FML. --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ad70630..286859e63 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -226,9 +226,9 @@ public class UAVObjectField { } case ENUM: { - List l = (List) data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - l.set(index, dataIn.get(index)); + l.set(index, dataIn.get()); } break; } From 902dbd9269799022bd59ca54f29a4507f9773a65 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:49:57 -0500 Subject: [PATCH 094/165] Update objects and delete old UAVObjects --- .../uavtalk/uavobjects/AHRSCalibration.java | 252 ------------------ .../uavtalk/uavobjects/AHRSSettings.java | 178 ------------- .../uavtalk/uavobjects/AhrsStatus.java | 201 -------------- .../uavtalk/uavobjects/AttitudeRaw.java | 158 ----------- .../uavtalk/uavobjects/FlightStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 8 +- .../uavtalk/uavobjects/HomeLocation.java | 32 +-- .../uavtalk/uavobjects/HwSettings.java | 98 +++++-- .../uavobjects/ManualControlSettings.java | 4 +- .../uavtalk/uavobjects/MixerStatus.java | 10 +- .../uavtalk/uavobjects/NedAccel.java | 6 +- .../uavtalk/uavobjects/PositionActual.java | 8 +- .../uavtalk/uavobjects/PositionDesired.java | 8 +- .../uavtalk/uavobjects/SystemAlarms.java | 4 +- .../uavtalk/uavobjects/SystemStats.java | 14 +- .../uavtalk/uavobjects/TaskInfo.java | 17 +- .../uavobjects/UAVObjectsInitialize.java | 18 +- .../uavtalk/uavobjects/VelocityActual.java | 8 +- .../uavtalk/uavobjects/VelocityDesired.java | 8 +- 19 files changed, 153 insertions(+), 883 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java deleted file mode 100644 index 47d42991e..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ /dev/null @@ -1,252 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the calibration settings for the @ref AHRSCommsModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the calibration settings for the @ref AHRSCommsModule - -generated from ahrscalibration.xml - **/ -public class AHRSCalibration extends UAVDataObject { - - public AHRSCalibration() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List accel_biasElemNames = new ArrayList(); - accel_biasElemNames.add("X"); - accel_biasElemNames.add("Y"); - accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); - - List accel_scaleElemNames = new ArrayList(); - accel_scaleElemNames.add("X"); - accel_scaleElemNames.add("Y"); - accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); - - List accel_orthoElemNames = new ArrayList(); - accel_orthoElemNames.add("XY"); - accel_orthoElemNames.add("XZ"); - accel_orthoElemNames.add("YZ"); - fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); - - List accel_varElemNames = new ArrayList(); - accel_varElemNames.add("X"); - accel_varElemNames.add("Y"); - accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); - - List gyro_biasElemNames = new ArrayList(); - gyro_biasElemNames.add("X"); - gyro_biasElemNames.add("Y"); - gyro_biasElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); - - List gyro_scaleElemNames = new ArrayList(); - gyro_scaleElemNames.add("X"); - gyro_scaleElemNames.add("Y"); - gyro_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); - - List gyro_varElemNames = new ArrayList(); - gyro_varElemNames.add("X"); - gyro_varElemNames.add("Y"); - gyro_varElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); - - List gyro_tempcompfactorElemNames = new ArrayList(); - gyro_tempcompfactorElemNames.add("X"); - gyro_tempcompfactorElemNames.add("Y"); - gyro_tempcompfactorElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); - - List mag_biasElemNames = new ArrayList(); - mag_biasElemNames.add("X"); - mag_biasElemNames.add("Y"); - mag_biasElemNames.add("Z"); - fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); - - List mag_scaleElemNames = new ArrayList(); - mag_scaleElemNames.add("X"); - mag_scaleElemNames.add("Y"); - mag_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); - - List mag_varElemNames = new ArrayList(); - mag_varElemNames.add("X"); - mag_varElemNames.add("Y"); - mag_varElemNames.add("Z"); - fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); - - List vel_varElemNames = new ArrayList(); - vel_varElemNames.add("0"); - fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); - - List pos_varElemNames = new ArrayList(); - pos_varElemNames.add("0"); - fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); - - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("accel_bias").setValue(-73.5,0); - getField("accel_bias").setValue(-73.5,1); - getField("accel_bias").setValue(73.5,2); - getField("accel_scale").setValue(0.0359,0); - getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(0.0359,2); - getField("accel_ortho").setValue(0,0); - getField("accel_ortho").setValue(0,1); - getField("accel_ortho").setValue(0,2); - getField("accel_var").setValue(0.0005,0); - getField("accel_var").setValue(0.0005,1); - getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(28,0); - getField("gyro_bias").setValue(-28,1); - getField("gyro_bias").setValue(28,2); - getField("gyro_scale").setValue(-0.017,0); - getField("gyro_scale").setValue(0.017,1); - getField("gyro_scale").setValue(-0.017,2); - getField("gyro_var").setValue(0.0001,0); - getField("gyro_var").setValue(0.0001,1); - getField("gyro_var").setValue(0.0001,2); - getField("gyro_tempcompfactor").setValue(0,0); - getField("gyro_tempcompfactor").setValue(0,1); - getField("gyro_tempcompfactor").setValue(0,2); - getField("mag_bias").setValue(0,0); - getField("mag_bias").setValue(0,1); - getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(1,0); - getField("mag_scale").setValue(1,1); - getField("mag_scale").setValue(1,2); - getField("mag_var").setValue(50,0); - getField("mag_var").setValue(50,1); - getField("mag_var").setValue(50,2); - getField("vel_var").setValue(10); - getField("pos_var").setValue(0.04); - getField("measure_var").setValue("SET"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSCalibration obj = new AHRSCalibration(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xFD0EDFC4; - protected static final String NAME = "AHRSCalibration"; - protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java deleted file mode 100644 index 032dae775..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ /dev/null @@ -1,178 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - -generated from ahrssettings.xml - **/ -public class AHRSSettings extends UAVDataObject { - - public AHRSSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - - List AlgorithmElemNames = new ArrayList(); - AlgorithmElemNames.add("0"); - List AlgorithmEnumOptions = new ArrayList(); - AlgorithmEnumOptions.add("SIMPLE"); - AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); - AlgorithmEnumOptions.add("INSGPS_INDOOR"); - AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); - fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); - - List DownsamplingElemNames = new ArrayList(); - DownsamplingElemNames.add("0"); - fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); - - List BiasCorrectedRawElemNames = new ArrayList(); - BiasCorrectedRawElemNames.add("0"); - List BiasCorrectedRawEnumOptions = new ArrayList(); - BiasCorrectedRawEnumOptions.add("TRUE"); - BiasCorrectedRawEnumOptions.add("FALSE"); - fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); - getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); - getField("Downsampling").setValue(20); - getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue("TRUE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSSettings obj = new AHRSSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xF8591ED8; - protected static final String NAME = "AHRSSettings"; - protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java deleted file mode 100644 index 82e447a70..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ /dev/null @@ -1,201 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status for the @ref AHRSCommsModule, including communication errors - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status for the @ref AHRSCommsModule, including communication errors - -generated from ahrsstatus.xml - **/ -public class AhrsStatus extends UAVDataObject { - - public AhrsStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - - List SerialNumberElemNames = new ArrayList(); - SerialNumberElemNames.add("0"); - SerialNumberElemNames.add("1"); - SerialNumberElemNames.add("2"); - SerialNumberElemNames.add("3"); - SerialNumberElemNames.add("4"); - SerialNumberElemNames.add("5"); - SerialNumberElemNames.add("6"); - SerialNumberElemNames.add("7"); - fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); - - List CPULoadElemNames = new ArrayList(); - CPULoadElemNames.add("0"); - fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - - List IdleTimePerCyleElemNames = new ArrayList(); - IdleTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); - - List RunningTimePerCyleElemNames = new ArrayList(); - RunningTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); - - List DroppedUpdatesElemNames = new ArrayList(); - DroppedUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); - - List LinkRunningElemNames = new ArrayList(); - LinkRunningElemNames.add("0"); - List LinkRunningEnumOptions = new ArrayList(); - LinkRunningEnumOptions.add("FALSE"); - LinkRunningEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); - - List AhrsKickstartsElemNames = new ArrayList(); - AhrsKickstartsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); - - List AhrsCrcErrorsElemNames = new ArrayList(); - AhrsCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); - - List AhrsRetriesElemNames = new ArrayList(); - AhrsRetriesElemNames.add("0"); - fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); - - List AhrsInvalidPacketsElemNames = new ArrayList(); - AhrsInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); - - List OpCrcErrorsElemNames = new ArrayList(); - OpCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); - - List OpRetriesElemNames = new ArrayList(); - OpRetriesElemNames.add("0"); - fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); - - List OpInvalidPacketsElemNames = new ArrayList(); - OpInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AhrsStatus obj = new AhrsStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) - { - return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x706D1AB8; - protected static final String NAME = "AhrsStatus"; - protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java deleted file mode 100644 index b8c3aacb4..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - -generated from attituderaw.xml - **/ -public class AttitudeRaw extends UAVDataObject { - - public AttitudeRaw() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List gyrosElemNames = new ArrayList(); - gyrosElemNames.add("X"); - gyrosElemNames.add("Y"); - gyrosElemNames.add("Z"); - fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - - List accelsElemNames = new ArrayList(); - accelsElemNames.add("X"); - accelsElemNames.add("Y"); - accelsElemNames.add("Z"); - fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); - - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeRaw obj = new AttitudeRaw(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) - { - return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xDB722974; - protected static final String NAME = "AttitudeRaw"; - protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index d775b21e7..ac3812aa6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -66,8 +66,10 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("Stabilized1"); FlightModeEnumOptions.add("Stabilized2"); FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("AltitudeHold"); FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); + FlightModeEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -144,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x743DB13C; + protected static final int OBJID = 0x19B92D8; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 205384efe..5510a901d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -55,14 +55,14 @@ public class GuidanceSettings extends UAVDataObject { HorizontalPosPIElemNames.add("Kp"); HorizontalPosPIElemNames.add("Ki"); HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); List VerticalPosPIElemNames = new ArrayList(); VerticalPosPIElemNames.add("Kp"); @@ -87,11 +87,11 @@ public class GuidanceSettings extends UAVDataObject { List HorizontalVelMaxElemNames = new ArrayList(); HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); List VerticalVelMaxElemNames = new ArrayList(); VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); List GuidanceModeElemNames = new ArrayList(); GuidanceModeElemNames.add("0"); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 68abb3633..3f3b3d8dd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -63,24 +63,6 @@ public class HomeLocation extends UAVDataObject { AltitudeElemNames.add("0"); fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - List ECEFElemNames = new ArrayList(); - ECEFElemNames.add("0"); - ECEFElemNames.add("1"); - ECEFElemNames.add("2"); - fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); - - List RNEElemNames = new ArrayList(); - RNEElemNames.add("0"); - RNEElemNames.add("1"); - RNEElemNames.add("2"); - RNEElemNames.add("3"); - RNEElemNames.add("4"); - RNEElemNames.add("5"); - RNEElemNames.add("6"); - RNEElemNames.add("7"); - RNEElemNames.add("8"); - fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); - List BeElemNames = new ArrayList(); BeElemNames.add("0"); BeElemNames.add("1"); @@ -146,18 +128,6 @@ public class HomeLocation extends UAVDataObject { getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); - getField("ECEF").setValue(0,0); - getField("ECEF").setValue(0,1); - getField("ECEF").setValue(0,2); - getField("RNE").setValue(0,0); - getField("RNE").setValue(0,1); - getField("RNE").setValue(0,2); - getField("RNE").setValue(0,3); - getField("RNE").setValue(0,4); - getField("RNE").setValue(0,5); - getField("RNE").setValue(0,6); - getField("RNE").setValue(0,7); - getField("RNE").setValue(0,8); getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); @@ -191,7 +161,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5BB3AEFC; + protected static final int OBJID = 0x6185DC6E; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index 83b7ae7b6..f56982e69 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -89,31 +89,70 @@ public class HwSettings extends UAVDataObject { CC_FlexiPortEnumOptions.add("ComBridge"); fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); - List OP_RcvrPortElemNames = new ArrayList(); - OP_RcvrPortElemNames.add("0"); - List OP_RcvrPortEnumOptions = new ArrayList(); - OP_RcvrPortEnumOptions.add("Disabled"); - OP_RcvrPortEnumOptions.add("PWM"); - OP_RcvrPortEnumOptions.add("PPM"); - OP_RcvrPortEnumOptions.add("DSM2"); - OP_RcvrPortEnumOptions.add("DSMX (10bit)"); - OP_RcvrPortEnumOptions.add("DSMX (11bit)"); - OP_RcvrPortEnumOptions.add("Debug"); - fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + List RV_RcvrPortElemNames = new ArrayList(); + RV_RcvrPortElemNames.add("0"); + List RV_RcvrPortEnumOptions = new ArrayList(); + RV_RcvrPortEnumOptions.add("Disabled"); + RV_RcvrPortEnumOptions.add("PWM"); + RV_RcvrPortEnumOptions.add("PPM"); + RV_RcvrPortEnumOptions.add("PPM+Outputs"); + RV_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("RV_RcvrPort", "function", UAVObjectField.FieldType.ENUM, RV_RcvrPortElemNames, RV_RcvrPortEnumOptions) ); - List OP_MainPortElemNames = new ArrayList(); - OP_MainPortElemNames.add("0"); - List OP_MainPortEnumOptions = new ArrayList(); - OP_MainPortEnumOptions.add("Disabled"); - OP_MainPortEnumOptions.add("Telemetry"); - fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + List RV_AuxPortElemNames = new ArrayList(); + RV_AuxPortElemNames.add("0"); + List RV_AuxPortEnumOptions = new ArrayList(); + RV_AuxPortEnumOptions.add("Disabled"); + RV_AuxPortEnumOptions.add("Telemetry"); + RV_AuxPortEnumOptions.add("DSM2"); + RV_AuxPortEnumOptions.add("DSMX (10bit)"); + RV_AuxPortEnumOptions.add("DSMX (11bit)"); + RV_AuxPortEnumOptions.add("ComAux"); + RV_AuxPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxPortElemNames, RV_AuxPortEnumOptions) ); - List OP_FlexiPortElemNames = new ArrayList(); - OP_FlexiPortElemNames.add("0"); - List OP_FlexiPortEnumOptions = new ArrayList(); - OP_FlexiPortEnumOptions.add("Disabled"); - OP_FlexiPortEnumOptions.add("GPS"); - fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + List RV_AuxSBusPortElemNames = new ArrayList(); + RV_AuxSBusPortElemNames.add("0"); + List RV_AuxSBusPortEnumOptions = new ArrayList(); + RV_AuxSBusPortEnumOptions.add("Disabled"); + RV_AuxSBusPortEnumOptions.add("S.Bus"); + RV_AuxSBusPortEnumOptions.add("DSM2"); + RV_AuxSBusPortEnumOptions.add("DSMX (10bit)"); + RV_AuxSBusPortEnumOptions.add("DSMX (11bit)"); + RV_AuxSBusPortEnumOptions.add("ComAux"); + RV_AuxSBusPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxSBusPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxSBusPortElemNames, RV_AuxSBusPortEnumOptions) ); + + List RV_FlexiPortElemNames = new ArrayList(); + RV_FlexiPortElemNames.add("0"); + List RV_FlexiPortEnumOptions = new ArrayList(); + RV_FlexiPortEnumOptions.add("Disabled"); + RV_FlexiPortEnumOptions.add("I2C"); + RV_FlexiPortEnumOptions.add("DSM2"); + RV_FlexiPortEnumOptions.add("DSMX (10bit)"); + RV_FlexiPortEnumOptions.add("DSMX (11bit)"); + RV_FlexiPortEnumOptions.add("ComAux"); + RV_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_FlexiPort", "function", UAVObjectField.FieldType.ENUM, RV_FlexiPortElemNames, RV_FlexiPortEnumOptions) ); + + List RV_TelemetryPortElemNames = new ArrayList(); + RV_TelemetryPortElemNames.add("0"); + List RV_TelemetryPortEnumOptions = new ArrayList(); + RV_TelemetryPortEnumOptions.add("Disabled"); + RV_TelemetryPortEnumOptions.add("Telemetry"); + RV_TelemetryPortEnumOptions.add("ComAux"); + RV_TelemetryPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_TelemetryPort", "function", UAVObjectField.FieldType.ENUM, RV_TelemetryPortElemNames, RV_TelemetryPortEnumOptions) ); + + List RV_GPSPortElemNames = new ArrayList(); + RV_GPSPortElemNames.add("0"); + List RV_GPSPortEnumOptions = new ArrayList(); + RV_GPSPortEnumOptions.add("Disabled"); + RV_GPSPortEnumOptions.add("Telemetry"); + RV_GPSPortEnumOptions.add("GPS"); + RV_GPSPortEnumOptions.add("ComAux"); + RV_GPSPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_GPSPort", "function", UAVObjectField.FieldType.ENUM, RV_GPSPortElemNames, RV_GPSPortEnumOptions) ); List TelemetrySpeedElemNames = new ArrayList(); TelemetrySpeedElemNames.add("0"); @@ -180,6 +219,7 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("TxPID"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -237,9 +277,12 @@ public class HwSettings extends UAVDataObject { getField("CC_RcvrPort").setValue("PWM"); getField("CC_MainPort").setValue("Disabled"); getField("CC_FlexiPort").setValue("Disabled"); - getField("OP_RcvrPort").setValue("PWM"); - getField("OP_MainPort").setValue("Telemetry"); - getField("OP_FlexiPort").setValue("GPS"); + getField("RV_RcvrPort").setValue("PWM"); + getField("RV_AuxPort").setValue("Disabled"); + getField("RV_AuxSBusPort").setValue("Disabled"); + getField("RV_FlexiPort").setValue("Disabled"); + getField("RV_TelemetryPort").setValue("Telemetry"); + getField("RV_GPSPort").setValue("GPS"); getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); @@ -251,6 +294,7 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",2); getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); + getField("OptionalModules").setValue("Disabled",5); getField("DSMxBind").setValue(0); } @@ -280,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2EE6575A; + protected static final int OBJID = 0x4730375C; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index bb846695d..c8f460bc4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -181,8 +181,10 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("Stabilized1"); FlightModePositionEnumOptions.add("Stabilized2"); FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("AltitudeHold"); FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); + FlightModePositionEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); @@ -317,7 +319,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x24959BB0; + protected static final int OBJID = 0x59C4551C; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 106220a8c..80e3b15bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -83,6 +83,14 @@ public class MixerStatus extends UAVDataObject { Mixer8ElemNames.add("0"); fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + List Mixer9ElemNames = new ArrayList(); + Mixer9ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer9", "", UAVObjectField.FieldType.FLOAT32, Mixer9ElemNames, null) ); + + List Mixer10ElemNames = new ArrayList(); + Mixer10ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer10", "", UAVObjectField.FieldType.FLOAT32, Mixer10ElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,7 +164,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x11CFB4E6; + protected static final int OBJID = 0x124E28A; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 3b09dd1f8..1629a19d2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -53,15 +53,15 @@ public class NedAccel extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index ac30ad4f5..184098a16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -53,15 +53,15 @@ public class PositionActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF9691DA4; + protected static final int OBJID = 0xFA9E2D42; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 2ff5a5586..123ca58af 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -53,15 +53,15 @@ public class PositionDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x33C9EAB4; + protected static final int OBJID = 0x778DBE24; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 458dd9d10..bc4bf0625 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -61,6 +61,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); AlarmElemNames.add("AHRSComms"); @@ -139,6 +140,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); + getField("Alarm").setValue("Uninitialised",17); } @@ -167,7 +169,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x737ADCF2; + protected static final int OBJID = 0x9C7CBFE; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index d1c51d43f..26d01f2a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -55,6 +55,18 @@ public class SystemStats extends UAVDataObject { FlightTimeElemNames.add("0"); fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + List EventSystemWarningIDElemNames = new ArrayList(); + EventSystemWarningIDElemNames.add("0"); + fields.add( new UAVObjectField("EventSystemWarningID", "uavoid", UAVObjectField.FieldType.UINT32, EventSystemWarningIDElemNames, null) ); + + List ObjectManagerCallbackIDElemNames = new ArrayList(); + ObjectManagerCallbackIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerCallbackID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerCallbackIDElemNames, null) ); + + List ObjectManagerQueueIDElemNames = new ArrayList(); + ObjectManagerQueueIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerQueueID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerQueueIDElemNames, null) ); + List HeapRemainingElemNames = new ArrayList(); HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); @@ -144,7 +156,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD610A0F0; + protected static final int OBJID = 0x364D1406; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 54825fafe..eefcef6d9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -55,36 +55,42 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("System"); StackRemainingElemNames.add("Actuator"); StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("Sensors"); StackRemainingElemNames.add("TelemetryTx"); StackRemainingElemNames.add("TelemetryTxPri"); StackRemainingElemNames.add("TelemetryRx"); StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); - StackRemainingElemNames.add("AHRSComms"); StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("AltitudeHold"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("PathPlanner"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); + StackRemainingElemNames.add("OveroSync"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); RunningElemNames.add("System"); RunningElemNames.add("Actuator"); RunningElemNames.add("Attitude"); + RunningElemNames.add("Sensors"); RunningElemNames.add("TelemetryTx"); RunningElemNames.add("TelemetryTxPri"); RunningElemNames.add("TelemetryRx"); RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); - RunningElemNames.add("AHRSComms"); RunningElemNames.add("Stabilization"); + RunningElemNames.add("AltitudeHold"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("PathPlanner"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); + RunningElemNames.add("OveroSync"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); @@ -94,18 +100,21 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("System"); RunningTimeElemNames.add("Actuator"); RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("Sensors"); RunningTimeElemNames.add("TelemetryTx"); RunningTimeElemNames.add("TelemetryTxPri"); RunningTimeElemNames.add("TelemetryRx"); RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); - RunningTimeElemNames.add("AHRSComms"); RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("AltitudeHold"); RunningTimeElemNames.add("Guidance"); RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("PathPlanner"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); + RunningTimeElemNames.add("OveroSync"); fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); @@ -181,7 +190,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE34A7C32; + protected static final int OBJID = 0x498F54BA; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index c2cf64d49..823643130 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -35,15 +35,15 @@ public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new Accels() ); objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); - objMngr.registerObject( new AHRSCalibration() ); - objMngr.registerObject( new AHRSSettings() ); - objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AltHoldSmoothed() ); + objMngr.registerObject( new AltitudeHoldDesired() ); + objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); - objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); @@ -62,16 +62,23 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GPSVelocity() ); + objMngr.registerObject( new Gyros() ); + objMngr.registerObject( new GyrosBias() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PathDesired() ); objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); @@ -82,10 +89,13 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); + objMngr.registerObject( new Waypoint() ); + objMngr.registerObject( new WaypointActive() ); } catch (Exception e) { e.printStackTrace(); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 97d038cfe..2a8cd3754 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -53,15 +53,15 @@ public class VelocityActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x43007EB0; + protected static final int OBJID = 0x5A08F61A; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index f39fbd6de..436ef6448 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -53,15 +53,15 @@ public class VelocityDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x25139D1A; + protected static final int OBJID = 0x9E946992; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; From 0e6cffaaf68647f586f16ebccdf7b65004e585f9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:12:45 -0500 Subject: [PATCH 095/165] Update fake telemetry object --- .../org/openpilot/androidgcs/OPTelemetryService.java | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index bc711560d..074049d79 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -222,18 +222,6 @@ public class OPTelemetryService extends Service { homeLocation.getField("Latitude").setDouble(379420315); homeLocation.getField("Longitude").setDouble(-88330078); - homeLocation.getField("ECEF").setDouble(497665694,0); - homeLocation.getField("ECEF").setDouble(-77336320,1); - homeLocation.getField("ECEF").setDouble(390037169,2); - homeLocation.getField("RNE").setDouble(-0.60757166,0); - homeLocation.getField("RNE").setDouble(0.09441550,1); - homeLocation.getField("RNE").setDouble(0.78863323,2); - homeLocation.getField("RNE").setDouble(0.15355512,3); - homeLocation.getField("RNE").setDouble(0.98814011,4); - homeLocation.getField("RNE").setDouble(0,5); - homeLocation.getField("RNE").setDouble(-0.77928013,6); - homeLocation.getField("RNE").setDouble(0.12109867,7); - homeLocation.getField("RNE").setDouble(-0.61486387,8); homeLocation.getField("Be").setDouble(26702.78710938,0); homeLocation.getField("Be").setDouble(-1468.33605957,1); homeLocation.getField("Be").setDouble(34181.78515625,2); From cd89d97bbb99e5ca498a3720b6eadb188a3332dc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:38:49 -0500 Subject: [PATCH 096/165] Lower all the debugging levels again --- .../org/openpilot/androidgcs/OPTelemetryService.java | 2 +- androidgcs/src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../src/org/openpilot/uavtalk/TelemetryMonitor.java | 10 ++++++++-- androidgcs/src/org/openpilot/uavtalk/UAVTalk.java | 10 ++++------ 4 files changed, 14 insertions(+), 10 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 074049d79..1a4b61eb8 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -33,7 +33,7 @@ public class OPTelemetryService extends Service { // Logging settings private final String TAG = "OPTelemetryService"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 11e6cb2ca..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 903b6b29f..87a0cdc70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -13,7 +13,7 @@ import android.util.Log; public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -204,6 +204,8 @@ public class TelemetryMonitor extends Observable{ Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats reset"); + // Update stats object gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); @@ -214,6 +216,8 @@ public class TelemetryMonitor extends Observable{ field = gcsStatsObj.getField("TxRetries"); field.setDouble(field.getDouble() + telStats.txRetries); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats updated"); + // Check for a connection timeout boolean connectionTimeout; if ( telStats.rxObjects > 0 ) @@ -296,8 +300,10 @@ public class TelemetryMonitor extends Observable{ objects_updated = false; setChanged(); } + + if (DEBUG) Log.d(TAG, "processStatsUpdates() - before notify"); notifyObservers(); - + if (DEBUG) Log.d(TAG, "processStatsUpdates() - after notify"); } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 5a3a9a1a5..9cdd11ccb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -504,8 +504,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -521,7 +520,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - System.out.println("Received object request: " + objId + " " + + if (DEBUG) Log.d(TAG,"Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -538,8 +537,7 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From c736488c3bd80a9e423261adc146ed284cc5ddbd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 11:04:35 -0500 Subject: [PATCH 097/165] First step to fixing metat data representation for android --- .../org/openpilot/uavtalk/UAVMetaObject.java | 46 ++++-------- .../src/org/openpilot/uavtalk/UAVObject.java | 70 +++++++------------ .../org/openpilot/uavtalk/UAVObjectField.java | 48 ++++++++++++- 3 files changed, 85 insertions(+), 79 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 7aab176ef..c57b6c2fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -13,43 +13,25 @@ public class UAVMetaObject extends UAVObject { ownMetadata = new Metadata(); - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flags = 0; // TODO: Fix flags ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; ownMetadata.loggingUpdatePeriod = 0; - // Setup fields - List boolEnum = new ArrayList(); - boolEnum.add("False"); - boolEnum.add("True"); - List updateModeEnum = new ArrayList(); - updateModeEnum.add("Periodic"); - updateModeEnum.add("On Change"); - updateModeEnum.add("Manual"); - updateModeEnum.add("Never"); + List modesBitField = new ArrayList(); + modesBitField.add("FlightReadOnly"); + modesBitField.add("GCSReadOnly"); + modesBitField.add("FlightTelemetryAcked"); + modesBitField.add("GCSTelemetryAcked"); + modesBitField.add("FlightUpdatePeriodic"); + modesBitField.add("FlightUpdateOnChange"); + modesBitField.add("GCSUpdatePeriodic"); + modesBitField.add("GCSUpdateOnChange"); - List accessModeEnum = new ArrayList(); - accessModeEnum.add("Read/Write"); - accessModeEnum.add("Read Only"); - - List fields = new ArrayList(); - fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); - fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); - fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("Logging Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); int numBytes = 0; ListIterator li = fields.listIterator(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 940b076a5..20d4cb02a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -120,17 +120,10 @@ public abstract class UAVObject { * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** - * Automatically update object at periodic - * intervals - */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** - * Manually update object, by calling the updated() - * function - */ - UPDATEMODE_NEVER - /** Object is never updated */ + UPDATEMODE_THROTTLED /** Object is updated on change, but not more often than the interval time */ }; /** @@ -140,47 +133,32 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - /** - * Access mode - */ - public enum Acked { - FALSE, TRUE - }; - public final class Metadata { - public AccessMode flightAccess; /** - * Defines the access level for the local flight transactions (readonly - * and readwrite) + * Object metadata, each object has a meta object that holds its metadata. The metadata define + * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ - public AccessMode gcsAccess; - /** - * Defines the access level for the local GCS transactions (readonly and - * readwrite) - */ - public Acked flightTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode flightTelemetryUpdateMode; - /** Update mode used by the autopilot (UpdateMode) */ + public int flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + + /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ public int flightTelemetryUpdatePeriod; - /** - * Update period used by the autopilot (only if telemetry mode is - * PERIODIC) - */ - public Acked gcsTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode gcsTelemetryUpdateMode; - /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; + + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; - /** Update mode used by the logging module (UpdateMode) */ public int loggingUpdatePeriod; /** * Update period used by the logging module (only if logging mode is diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 286859e63..c2965f6cc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -7,7 +7,7 @@ import java.util.List; public class UAVObjectField { - public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, BITFIELD, STRING }; public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { List elementNames = new ArrayList(); @@ -56,6 +56,8 @@ public class UAVObjectField { return "float32"; case ENUM: return "enum"; + case BITFIELD: + return "bitfield"; case STRING: return "string"; default: @@ -144,6 +146,11 @@ public class UAVObjectField { for (int index = 0; index < numElements; ++index) dataOut.put((Byte) l.get(index)); break; + case BITFIELD: + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } case STRING: // TODO: Implement strings throw new Error("Strings not yet implemented"); @@ -224,6 +231,16 @@ public class UAVObjectField { } break; } + case BITFIELD: + { + List l = (List) this.data; + for (int index = 0 ; index < numElements; ++index) { + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); + } + break; + } case ENUM: { List l = (List) this.data; @@ -275,6 +292,9 @@ public class UAVObjectField { return options.get(val); } + case BITFIELD: + return ((List) data).get(index).intValue(); + case STRING: { //throw new Exception("Shit I should do this"); @@ -354,6 +374,12 @@ public class UAVObjectField { l.set(index, val); break; } + case BITFIELD: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case STRING: { //throw new Exception("Sorry I haven't implemented strings yet"); @@ -404,6 +430,8 @@ public class UAVObjectField { return true; case ENUM: return false; + case BITFIELD: + return true; case STRING: return false; default: @@ -430,6 +458,8 @@ public class UAVObjectField { return false; case ENUM: return true; + case BITFIELD: + return false; case STRING: return true; default: @@ -493,6 +523,12 @@ public class UAVObjectField { ((ArrayList) data).add((float) 0); } break; + case BITFIELD: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case ENUM: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { @@ -549,6 +585,10 @@ public class UAVObjectField { data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; + case BITFIELD: + data = (Object) new ArrayList(this.numElements); + numBytesPerElement = 1; + break; case STRING: data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; @@ -614,6 +654,12 @@ public class UAVObjectField { if(num > 4294967295L) return 4294967295L; return num; + case BITFIELD: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; } return num; From 9960411ead0ae7176cef4b2c3b0e3cf3345908f1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 12:49:34 -0500 Subject: [PATCH 098/165] Finish porting the meta data changes from GCS and update all the UAVOs --- .../src/org/openpilot/uavtalk/Telemetry.java | 29 +- .../openpilot/uavtalk/TelemetryMonitor.java | 37 ++- .../src/org/openpilot/uavtalk/UAVObject.java | 194 +++++++++++- .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../uavtalk/uavobjects/AccessoryDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorCommand.java | 23 +- .../uavtalk/uavobjects/ActuatorDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorSettings.java | 280 +----------------- .../uavtalk/uavobjects/AttitudeActual.java | 23 +- .../uavtalk/uavobjects/AttitudeSettings.java | 23 +- .../uavtalk/uavobjects/BaroAltitude.java | 23 +- .../uavtalk/uavobjects/CameraDesired.java | 23 +- .../uavobjects/CameraStabSettings.java | 23 +- .../uavtalk/uavobjects/FaultSettings.java | 23 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 23 +- .../uavobjects/FlightBatterySettings.java | 36 ++- .../uavobjects/FlightBatteryState.java | 30 +- .../uavtalk/uavobjects/FlightPlanControl.java | 23 +- .../uavobjects/FlightPlanSettings.java | 23 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 23 +- .../uavtalk/uavobjects/FlightStatus.java | 26 +- .../uavobjects/FlightTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GCSReceiver.java | 27 +- .../uavtalk/uavobjects/GCSTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GPSPosition.java | 23 +- .../uavtalk/uavobjects/GPSSatellites.java | 23 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 23 +- .../uavtalk/uavobjects/GuidanceSettings.java | 211 ------------- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 44 +-- .../uavtalk/uavobjects/I2CStats.java | 23 +- .../uavobjects/ManualControlCommand.java | 23 +- .../uavobjects/ManualControlSettings.java | 48 ++- .../uavtalk/uavobjects/MixerSettings.java | 23 +- .../uavtalk/uavobjects/MixerStatus.java | 23 +- .../uavtalk/uavobjects/NedAccel.java | 23 +- .../uavtalk/uavobjects/ObjectPersistence.java | 26 +- .../uavtalk/uavobjects/PositionActual.java | 23 +- .../uavtalk/uavobjects/PositionDesired.java | 147 --------- .../uavtalk/uavobjects/RateDesired.java | 23 +- .../uavtalk/uavobjects/ReceiverActivity.java | 23 +- .../uavtalk/uavobjects/SonarAltitude.java | 23 +- .../uavobjects/StabilizationDesired.java | 26 +- .../uavobjects/StabilizationSettings.java | 78 ++++- .../uavtalk/uavobjects/SystemAlarms.java | 29 +- .../uavtalk/uavobjects/SystemSettings.java | 34 ++- .../uavtalk/uavobjects/SystemStats.java | 23 +- .../uavtalk/uavobjects/TaskInfo.java | 40 +-- .../uavobjects/UAVObjectsInitialize.java | 21 +- .../uavtalk/uavobjects/VelocityActual.java | 23 +- .../uavtalk/uavobjects/VelocityDesired.java | 23 +- .../uavtalk/uavobjects/WatchdogStatus.java | 23 +- .../templates/uavobjecttemplate.java | 23 +- 53 files changed, 880 insertions(+), 1244 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..2ee5ab9a4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -10,8 +10,6 @@ import java.util.Queue; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.UAVObject.Acked; - import android.util.Log; public class Telemetry { @@ -20,7 +18,7 @@ public class Telemetry { public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -50,7 +48,7 @@ public class Telemetry { boolean allInstances; boolean objRequest; int retriesRemaining; - Acked acked; + boolean acked; } ; /** @@ -249,7 +247,7 @@ public class Telemetry { // Setup object depending on update mode int eventMask; - if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) { // Set update period setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); @@ -260,7 +258,7 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) { // Set update period setUpdatePeriod(obj, 0); @@ -271,7 +269,11 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_THROTTLED ) + { + // TODO + } + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) { // Set update period setUpdatePeriod(obj, 0); @@ -282,13 +284,6 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) - { - // Set update period - setUpdatePeriod(obj, 0); - // Disconnect from object - connectToObjectInstances(obj, 0); - } } /** @@ -360,10 +355,10 @@ public class Telemetry { } else { - utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + utalk.sendObject(transInfo.obj, transInfo.acked, transInfo.allInstances); } // Start timer if a response is expected - if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + if ( transInfo.objRequest || transInfo.acked ) { transTimerSetPeriod(REQ_TIMEOUT_MS); } @@ -476,7 +471,7 @@ public class Telemetry { transInfo.obj = objInfo.obj; transInfo.allInstances = objInfo.allInstances; transInfo.retriesRemaining = MAX_RETRIES; - transInfo.acked = metadata.gcsTelemetryAcked; + transInfo.acked = metadata.GetGcsTelemetryAcked(); if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) { transInfo.objRequest = false; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 87a0cdc70..d1d7a9c44 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -76,27 +76,24 @@ public class TelemetryMonitor extends Observable{ List instList = objListIterator.next(); UAVObject obj = instList.get(0); UAVObject.Metadata mdata = obj.getMetadata(); - if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + if ( obj.isMetadata() ) { - if ( obj.isMetadata() ) - { - queue.add(obj); - } - else /* Data object */ - { - UAVDataObject dobj = (UAVDataObject) obj; - if ( dobj.isSettings() ) - { - queue.add(obj); - } - else - { - if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) - { - queue.add(obj); - } - } - } + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.GetFlightTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } } } // Start retrieving diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 20d4cb02a..28c279040 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -133,7 +133,15 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - public final class Metadata { + public final static int UAVOBJ_ACCESS_SHIFT = 0; + public final static int UAVOBJ_GCS_ACCESS_SHIFT = 1; + public final static int UAVOBJ_TELEMETRY_ACKED_SHIFT = 2; + public final static int UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT = 3; + public final static int UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT = 4; + public final static int UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT = 6; + public final static int UAVOBJ_UPDATE_MODE_MASK = 0x3; + + public final static class Metadata { /** * Object metadata, each object has a meta object that holds its metadata. The metadata define * properties for each object and can be used by multiple modules (e.g. telemetry and logger) @@ -164,6 +172,190 @@ public abstract class UAVObject { * Update period used by the logging module (only if logging mode is * PERIODIC) */ + + /** + * @brief Helper method for metadata accessors + * @param var The starting value + * @param shift The offset of these bits + * @param value The new value + * @param mask The mask of these bits + * @return + */ + private void SET_BITS(int shift, int value, int mask) { + this.flags = (this.flags & ~(mask << shift)) | (value << shift); + } + + /** + * Get the UAVObject metadata access member + * \return the access type + */ + public AccessMode GetFlightAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata access member + * \param[in] mode The access mode + */ + public void SetFlightAccess(Metadata metadata, AccessMode mode) + { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata GCS access member + * \return the GCS access type + */ + public AccessMode GetGcsAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata GCS access member + * \param[in] mode The access mode + */ + public void SetGcsAccess(Metadata metadata, AccessMode mode) { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_GCS_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetFlightTelemetryAcked() { + return (((this.flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1) == 1); + } + + /** + * Set the UAVObject metadata telemetry acked member + * \param[in] val The telemetry acked boolean + */ + public void SetFlightTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Get the UAVObject metadata GCS telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetGcsTelemetryAcked() { + return ((this.flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1) == 1; + } + + /** + * Set the UAVObject metadata GCS telemetry acked member + * \param[in] val The GCS telemetry acked boolean + */ + public void SetGcsTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static AccessMode AccessModeEnum(int num) { + switch(num) { + case 0: + return AccessMode.ACCESS_READONLY; + case 1: + return AccessMode.ACCESS_READWRITE; + } + return AccessMode.ACCESS_READONLY; + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int AccessModeNum(AccessMode e) { + switch(e) { + case ACCESS_READONLY: + return 0; + case ACCESS_READWRITE: + return 1; + } + return 0; + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static UpdateMode UpdateModeEnum(int num) { + switch(num) { + case 0: + return UpdateMode.UPDATEMODE_MANUAL; + case 1: + return UpdateMode.UPDATEMODE_PERIODIC; + case 2: + return UpdateMode.UPDATEMODE_ONCHANGE; + default: + return UpdateMode.UPDATEMODE_THROTTLED; + } + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int UpdateModeNum(UpdateMode e) { + switch(e) { + case UPDATEMODE_MANUAL: + return 0; + case UPDATEMODE_PERIODIC: + return 1; + case UPDATEMODE_ONCHANGE: + return 2; + case UPDATEMODE_THROTTLED: + return 3; + } + return 0; + } + + /** + * Get the UAVObject metadata telemetry update mode + * \return the telemetry update mode + */ + public UpdateMode GetFlightTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The telemetry update mode + */ + public void SetFlightTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Get the UAVObject metadata GCS telemetry update mode + * \param[in] metadata The metadata object + * \return the GCS telemetry update mode + */ + public UpdateMode GetGcsTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata GCS telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry update mode + */ + public void SetGcsTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + }; public UAVObject(int objID, Boolean isSingleInst, String name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c2965f6cc..3ed221079 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -314,7 +314,7 @@ public class UAVObjectField { // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.GetGcsAccess() == UAVObject.AccessMode.ACCESS_READWRITE ) { switch (type) { diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java index 13c63dfdd..4b7c875a7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -78,18 +78,17 @@ public class AccessoryDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index 08f2ebefe..0120e0ce7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -99,18 +99,17 @@ public class ActuatorCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index 03ff1985c..a00517906 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -98,18 +98,17 @@ public class ActuatorDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 71b0bb49f..2257da346 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -97,246 +97,6 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("Channel9"); - FixedWingRoll1EnumOptions.add("Channel10"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("Channel9"); - FixedWingRoll2EnumOptions.add("Channel10"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("Channel9"); - FixedWingPitch1EnumOptions.add("Channel10"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("Channel9"); - FixedWingPitch2EnumOptions.add("Channel10"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYaw1ElemNames = new ArrayList(); - FixedWingYaw1ElemNames.add("0"); - List FixedWingYaw1EnumOptions = new ArrayList(); - FixedWingYaw1EnumOptions.add("Channel1"); - FixedWingYaw1EnumOptions.add("Channel2"); - FixedWingYaw1EnumOptions.add("Channel3"); - FixedWingYaw1EnumOptions.add("Channel4"); - FixedWingYaw1EnumOptions.add("Channel5"); - FixedWingYaw1EnumOptions.add("Channel6"); - FixedWingYaw1EnumOptions.add("Channel7"); - FixedWingYaw1EnumOptions.add("Channel8"); - FixedWingYaw1EnumOptions.add("Channel9"); - FixedWingYaw1EnumOptions.add("Channel10"); - FixedWingYaw1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); - - List FixedWingYaw2ElemNames = new ArrayList(); - FixedWingYaw2ElemNames.add("0"); - List FixedWingYaw2EnumOptions = new ArrayList(); - FixedWingYaw2EnumOptions.add("Channel1"); - FixedWingYaw2EnumOptions.add("Channel2"); - FixedWingYaw2EnumOptions.add("Channel3"); - FixedWingYaw2EnumOptions.add("Channel4"); - FixedWingYaw2EnumOptions.add("Channel5"); - FixedWingYaw2EnumOptions.add("Channel6"); - FixedWingYaw2EnumOptions.add("Channel7"); - FixedWingYaw2EnumOptions.add("Channel8"); - FixedWingYaw2EnumOptions.add("Channel9"); - FixedWingYaw2EnumOptions.add("Channel10"); - FixedWingYaw2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("Channel9"); - FixedWingThrottleEnumOptions.add("Channel10"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("Channel9"); - VTOLMotorNEnumOptions.add("Channel10"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("Channel9"); - VTOLMotorNEEnumOptions.add("Channel10"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("Channel9"); - VTOLMotorEEnumOptions.add("Channel10"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("Channel9"); - VTOLMotorSEEnumOptions.add("Channel10"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("Channel9"); - VTOLMotorSEnumOptions.add("Channel10"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("Channel9"); - VTOLMotorSWEnumOptions.add("Channel10"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("Channel9"); - VTOLMotorWEnumOptions.add("Channel10"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("Channel9"); - VTOLMotorNWEnumOptions.add("Channel10"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -398,18 +158,17 @@ public class ActuatorSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -454,21 +213,6 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,7); getField("ChannelMin").setValue(1000,8); getField("ChannelMin").setValue(1000,9); - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw1").setValue("None"); - getField("FixedWingYaw2").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -518,7 +262,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF2875746; + protected static final int OBJID = 0x7D555646; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 7c9272cad..b117e501a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -102,18 +102,17 @@ public class AttitudeActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 100; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 3034a99ad..9bcce7bf3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -130,18 +130,17 @@ public class AttitudeSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index ecde53985..cd649f84c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -86,18 +86,17 @@ public class BaroAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java index 7a36ec1ea..34c23e612 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -86,18 +86,17 @@ public class CameraDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java index a8e03df32..0b2f3b3f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -125,18 +125,17 @@ public class CameraStabSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index b22b8185e..8da58f793 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -85,18 +85,17 @@ public class FaultSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 71c681bd2..58fadcee5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -152,18 +152,17 @@ public class FirmwareIAPObj extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java index a3bc23eb3..850f64103 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -80,9 +80,12 @@ public class FlightBatterySettings extends UAVDataObject { fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); List SensorTypeElemNames = new ArrayList(); - SensorTypeElemNames.add("0"); + SensorTypeElemNames.add("BatteryCurrent"); + SensorTypeElemNames.add("BatteryVoltage"); + SensorTypeElemNames.add("BoardVoltage"); List SensorTypeEnumOptions = new ArrayList(); - SensorTypeEnumOptions.add("None"); + SensorTypeEnumOptions.add("Disabled"); + SensorTypeEnumOptions.add("Enabled"); fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); @@ -108,18 +111,17 @@ public class FlightBatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -137,7 +139,9 @@ public class FlightBatterySettings extends UAVDataObject { getField("SensorCalibrations").setValue(1,1); getField("Type").setValue("LiPo"); getField("NbCells").setValue(3); - getField("SensorType").setValue("None"); + getField("SensorType").setValue("Disabled",0); + getField("SensorType").setValue("Disabled",1); + getField("SensorType").setValue("Disabled",2); } @@ -166,7 +170,7 @@ public class FlightBatterySettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF172BB18; + protected static final int OBJID = 0x94AC6AD2; protected static final String NAME = "FlightBatterySettings"; protected static String DESCRIPTION = "Flight Battery configuration."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index 82fcfae47..d54648ad5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -59,6 +59,10 @@ public class FlightBatteryState extends UAVDataObject { CurrentElemNames.add("0"); fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + List BoardSupplyVoltageElemNames = new ArrayList(); + BoardSupplyVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BoardSupplyVoltage", "V", UAVObjectField.FieldType.FLOAT32, BoardSupplyVoltageElemNames, null) ); + List PeakCurrentElemNames = new ArrayList(); PeakCurrentElemNames.add("0"); fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); @@ -98,18 +102,17 @@ public class FlightBatteryState extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -122,6 +125,7 @@ public class FlightBatteryState extends UAVDataObject { { getField("Voltage").setValue(0); getField("Current").setValue(0); + getField("BoardSupplyVoltage").setValue(0); getField("PeakCurrent").setValue(0); getField("AvgCurrent").setValue(0); getField("ConsumedEnergy").setValue(0); @@ -154,7 +158,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8C0D756; + protected static final int OBJID = 0xD2083596; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index dbe959f96..cdea28a0f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -82,18 +82,17 @@ public class FlightPlanControl extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 6fc39a26e..184bbd1b7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -78,18 +78,17 @@ public class FlightPlanSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 7b78bce71..8aa152789 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -119,18 +119,17 @@ public class FlightPlanStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index ac3812aa6..38697e573 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -70,6 +70,7 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); FlightModeEnumOptions.add("PathPlanner"); + FlightModeEnumOptions.add("RTH"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -95,18 +96,17 @@ public class FlightStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -146,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x19B92D8; + protected static final int OBJID = 0x884FEF66; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index 403ea1d5e..3a042f52e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -103,18 +103,17 @@ public class FlightTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java index 3cb3811ae..05fa87efb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -58,6 +58,8 @@ public class GCSReceiver extends UAVDataObject { ChannelElemNames.add("3"); ChannelElemNames.add("4"); ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); @@ -83,18 +85,17 @@ public class GCSReceiver extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -133,7 +134,7 @@ public class GCSReceiver extends UAVDataObject { } // Constants - protected static final int OBJID = 0xCC7E2BBC; + protected static final int OBJID = 0xCC7E1470; protected static final String NAME = "GCSReceiver"; protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index b32f551ce..754272c8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -103,18 +103,17 @@ public class GCSTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.gcsTelemetryUpdatePeriod = 5000; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 5000; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 5f4e20b46..c2c8544a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -123,18 +123,17 @@ public class GPSPosition extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index bb331132d..0f5b0161a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -154,18 +154,17 @@ public class GPSSatellites extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5aa4df7bf..7095aa18e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -98,18 +98,17 @@ public class GPSTime extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java deleted file mode 100644 index 5510a901d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ /dev/null @@ -1,211 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref GuidanceModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref GuidanceModule - -generated from guidancesettings.xml - **/ -public class GuidanceSettings extends UAVDataObject { - - public GuidanceSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List HorizontalPosPIElemNames = new ArrayList(); - HorizontalPosPIElemNames.add("Kp"); - HorizontalPosPIElemNames.add("Ki"); - HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); - - List HorizontalVelPIDElemNames = new ArrayList(); - HorizontalVelPIDElemNames.add("Kp"); - HorizontalVelPIDElemNames.add("Ki"); - HorizontalVelPIDElemNames.add("Kd"); - HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - - List VerticalPosPIElemNames = new ArrayList(); - VerticalPosPIElemNames.add("Kp"); - VerticalPosPIElemNames.add("Ki"); - VerticalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); - - List VerticalVelPIDElemNames = new ArrayList(); - VerticalVelPIDElemNames.add("Kp"); - VerticalVelPIDElemNames.add("Ki"); - VerticalVelPIDElemNames.add("Kd"); - VerticalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - - List MaxRollPitchElemNames = new ArrayList(); - MaxRollPitchElemNames.add("0"); - fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - List HorizontalVelMaxElemNames = new ArrayList(); - HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); - - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("HorizontalPosPI").setValue(0.1,0); - getField("HorizontalPosPI").setValue(0.001,1); - getField("HorizontalPosPI").setValue(300,2); - getField("HorizontalVelPID").setValue(0.05,0); - getField("HorizontalVelPID").setValue(0.002,1); - getField("HorizontalVelPID").setValue(0,2); - getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalPosPI").setValue(0.1,0); - getField("VerticalPosPI").setValue(0.001,1); - getField("VerticalPosPI").setValue(200,2); - getField("VerticalVelPID").setValue(0.1,0); - getField("VerticalVelPID").setValue(0,1); - getField("VerticalVelPID").setValue(0,2); - getField("VerticalVelPID").setValue(0,3); - getField("MaxRollPitch").setValue(10); - getField("UpdatePeriod").setValue(100); - getField("HorizontalVelMax").setValue(300); - getField("VerticalVelMax").setValue(150); - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("ThrottleControl").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - GuidanceSettings obj = new GuidanceSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x6EA79FB4; - protected static final String NAME = "GuidanceSettings"; - protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 3f3b3d8dd..0cd45db1b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -103,18 +103,17 @@ public class HomeLocation extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index f56982e69..9d8113846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -190,14 +190,6 @@ public class HwSettings extends UAVDataObject { ComUsbBridgeSpeedEnumOptions.add("115200"); fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); - List USB_DeviceTypeElemNames = new ArrayList(); - USB_DeviceTypeElemNames.add("0"); - List USB_DeviceTypeEnumOptions = new ArrayList(); - USB_DeviceTypeEnumOptions.add("HID-only"); - USB_DeviceTypeEnumOptions.add("HID+VCP"); - USB_DeviceTypeEnumOptions.add("VCP-only"); - fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); - List USB_HIDPortElemNames = new ArrayList(); USB_HIDPortElemNames.add("0"); List USB_HIDPortEnumOptions = new ArrayList(); @@ -219,7 +211,12 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("Airspeed"); OptionalModulesElemNames.add("TxPID"); + OptionalModulesElemNames.add("VtolPathFollower"); + OptionalModulesElemNames.add("FixedWingPathFollower"); + OptionalModulesElemNames.add("Battery"); + OptionalModulesElemNames.add("Overo"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -252,18 +249,17 @@ public class HwSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -286,7 +282,6 @@ public class HwSettings extends UAVDataObject { getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); - getField("USB_DeviceType").setValue("HID-only"); getField("USB_HIDPort").setValue("USBTelemetry"); getField("USB_VCPPort").setValue("Disabled"); getField("OptionalModules").setValue("Disabled",0); @@ -295,6 +290,11 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); getField("OptionalModules").setValue("Disabled",5); + getField("OptionalModules").setValue("Disabled",6); + getField("OptionalModules").setValue("Disabled",7); + getField("OptionalModules").setValue("Disabled",8); + getField("OptionalModules").setValue("Disabled",9); + getField("OptionalModules").setValue("Disabled",10); getField("DSMxBind").setValue(0); } @@ -324,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4730375C; + protected static final int OBJID = 0x5D950E50; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index abd8f41f6..a09e4404d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -177,18 +177,17 @@ public class I2CStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 6ac5a1b2c..5ce51c245 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -113,18 +113,17 @@ public class ManualControlCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c8f460bc4..47ebbc230 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,6 +51,10 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); + List DeadbandElemNames = new ArrayList(); + DeadbandElemNames.add("0"); + fields.add( new UAVObjectField("Deadband", "%", UAVObjectField.FieldType.FLOAT32, DeadbandElemNames, null) ); + List ChannelMinElemNames = new ArrayList(); ChannelMinElemNames.add("Throttle"); ChannelMinElemNames.add("Roll"); @@ -146,6 +150,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("Attitude"); Stabilization1SettingsEnumOptions.add("AxisLock"); Stabilization1SettingsEnumOptions.add("WeakLeveling"); + Stabilization1SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -158,6 +163,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("Attitude"); Stabilization2SettingsEnumOptions.add("AxisLock"); Stabilization2SettingsEnumOptions.add("WeakLeveling"); + Stabilization2SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -170,6 +176,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("Attitude"); Stabilization3SettingsEnumOptions.add("AxisLock"); Stabilization3SettingsEnumOptions.add("WeakLeveling"); + Stabilization3SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -185,8 +192,21 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); FlightModePositionEnumOptions.add("PathPlanner"); + FlightModePositionEnumOptions.add("RTH"); + FlightModePositionEnumOptions.add("Land"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + List FlightModeNumberElemNames = new ArrayList(); + FlightModeNumberElemNames.add("0"); + fields.add( new UAVObjectField("FlightModeNumber", "", UAVObjectField.FieldType.UINT8, FlightModeNumberElemNames, null) ); + + List FailsafeBehaviorElemNames = new ArrayList(); + FailsafeBehaviorElemNames.add("0"); + List FailsafeBehaviorEnumOptions = new ArrayList(); + FailsafeBehaviorEnumOptions.add("None"); + FailsafeBehaviorEnumOptions.add("RTH"); + fields.add( new UAVObjectField("FailsafeBehavior", "", UAVObjectField.FieldType.ENUM, FailsafeBehaviorElemNames, FailsafeBehaviorEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -210,18 +230,17 @@ public class ManualControlSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -232,6 +251,7 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Deadband").setValue(0); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -291,6 +311,8 @@ public class ManualControlSettings extends UAVDataObject { getField("FlightModePosition").setValue("Manual",0); getField("FlightModePosition").setValue("Stabilized1",1); getField("FlightModePosition").setValue("Stabilized2",2); + getField("FlightModeNumber").setValue(3); + getField("FailsafeBehavior").setValue("None"); } @@ -319,7 +341,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x59C4551C; + protected static final int OBJID = 0x6C188320; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 76841d8ff..094d91545 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -372,18 +372,17 @@ public class MixerSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 80e3b15bf..1f767c5ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -114,18 +114,17 @@ public class MixerStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 1629a19d2..6d09a799e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -86,18 +86,17 @@ public class NedAccel extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10001; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10001; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index dccd85d36..42a65e3ab 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -68,6 +68,7 @@ public class ObjectPersistence extends UAVDataObject { OperationEnumOptions.add("Delete"); OperationEnumOptions.add("FullErase"); OperationEnumOptions.add("Completed"); + OperationEnumOptions.add("Error"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -102,18 +103,17 @@ public class ObjectPersistence extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF69AD8B8; + protected static final int OBJID = 0x99C63292; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 184098a16..1c87c21c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -86,18 +86,17 @@ public class PositionActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 1000; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java deleted file mode 100644 index 123ca58af..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ /dev/null @@ -1,147 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - -generated from positiondesired.xml - **/ -public class PositionDesired extends UAVDataObject { - - public PositionDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - PositionDesired obj = new PositionDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) - { - return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x778DBE24; - protected static final String NAME = "PositionDesired"; - protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index ddeacd8d4..51f7faa7d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -86,18 +86,17 @@ public class RateDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index a40b27e38..15391ce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -90,18 +90,17 @@ public class ReceiverActivity extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 18cf6f4d6..1a5679d6a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -78,18 +78,17 @@ public class SonarAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 32d2c735c..8ca5df722 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -77,6 +77,7 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("Attitude"); StabilizationModeEnumOptions.add("AxisLock"); StabilizationModeEnumOptions.add("WeakLeveling"); + StabilizationModeEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -102,18 +103,17 @@ public class StabilizationDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDB8FFC3C; + protected static final int OBJID = 0xDE1EAAD6; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index ab78bdc74..cc2c69e8f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -102,6 +102,31 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List VbarSensitivityElemNames = new ArrayList(); + VbarSensitivityElemNames.add("Roll"); + VbarSensitivityElemNames.add("Pitch"); + VbarSensitivityElemNames.add("Yaw"); + fields.add( new UAVObjectField("VbarSensitivity", "frac", UAVObjectField.FieldType.FLOAT32, VbarSensitivityElemNames, null) ); + + List VbarRollPIElemNames = new ArrayList(); + VbarRollPIElemNames.add("Kp"); + VbarRollPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarRollPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarRollPIElemNames, null) ); + + List VbarPitchPIElemNames = new ArrayList(); + VbarPitchPIElemNames.add("Kp"); + VbarPitchPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarPitchPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarPitchPIElemNames, null) ); + + List VbarYawPIElemNames = new ArrayList(); + VbarYawPIElemNames.add("Kp"); + VbarYawPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarYawPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarYawPIElemNames, null) ); + + List VbarTauElemNames = new ArrayList(); + VbarTauElemNames.add("0"); + fields.add( new UAVObjectField("VbarTau", "sec", UAVObjectField.FieldType.FLOAT32, VbarTauElemNames, null) ); + List GyroTauElemNames = new ArrayList(); GyroTauElemNames.add("0"); fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); @@ -122,6 +147,21 @@ public class StabilizationSettings extends UAVDataObject { YawMaxElemNames.add("0"); fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + List VbarGyroSuppressElemNames = new ArrayList(); + VbarGyroSuppressElemNames.add("0"); + fields.add( new UAVObjectField("VbarGyroSuppress", "%", UAVObjectField.FieldType.INT8, VbarGyroSuppressElemNames, null) ); + + List VbarPiroCompElemNames = new ArrayList(); + VbarPiroCompElemNames.add("0"); + List VbarPiroCompEnumOptions = new ArrayList(); + VbarPiroCompEnumOptions.add("FALSE"); + VbarPiroCompEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("VbarPiroComp", "", UAVObjectField.FieldType.ENUM, VbarPiroCompElemNames, VbarPiroCompEnumOptions) ); + + List VbarMaxAngleElemNames = new ArrayList(); + VbarMaxAngleElemNames.add("0"); + fields.add( new UAVObjectField("VbarMaxAngle", "deg", UAVObjectField.FieldType.UINT8, VbarMaxAngleElemNames, null) ); + List MaxAxisLockElemNames = new ArrayList(); MaxAxisLockElemNames.add("0"); fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); @@ -164,18 +204,17 @@ public class StabilizationSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -213,11 +252,24 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("VbarSensitivity").setValue(0.5,0); + getField("VbarSensitivity").setValue(0.5,1); + getField("VbarSensitivity").setValue(0.5,2); + getField("VbarRollPI").setValue(0.005,0); + getField("VbarRollPI").setValue(0.002,1); + getField("VbarPitchPI").setValue(0.005,0); + getField("VbarPitchPI").setValue(0.002,1); + getField("VbarYawPI").setValue(0.005,0); + getField("VbarYawPI").setValue(0.002,1); + getField("VbarTau").setValue(0.5); getField("GyroTau").setValue(0.005); getField("WeakLevelingKp").setValue(0.1); getField("RollMax").setValue(55); getField("PitchMax").setValue(55); getField("YawMax").setValue(35); + getField("VbarGyroSuppress").setValue(30); + getField("VbarPiroComp").setValue("FALSE"); + getField("VbarMaxAngle").setValue(10); getField("MaxAxisLock").setValue(15); getField("MaxAxisLockRate").setValue(2); getField("MaxWeakLevelingRate").setValue(5); @@ -250,7 +302,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5F78C51E; + protected static final int OBJID = 0xBBC337D4; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index bc4bf0625..3b34763fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -56,7 +56,6 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("StackOverflow"); AlarmElemNames.add("CPUOverload"); AlarmElemNames.add("EventSystem"); - AlarmElemNames.add("SDCard"); AlarmElemNames.add("Telemetry"); AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); @@ -64,12 +63,12 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); - AlarmElemNames.add("AHRSComms"); AlarmElemNames.add("Battery"); AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); AlarmElemNames.add("BootFault"); + AlarmElemNames.add("Power"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -101,18 +100,17 @@ public class SystemAlarms extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -140,7 +138,6 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); - getField("Alarm").setValue("Uninitialised",17); } @@ -169,7 +166,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9C7CBFE; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index e3c2cf0b0..bffbced31 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -54,6 +54,8 @@ public class SystemSettings extends UAVDataObject { List GUIConfigDataElemNames = new ArrayList(); GUIConfigDataElemNames.add("0"); GUIConfigDataElemNames.add("1"); + GUIConfigDataElemNames.add("2"); + GUIConfigDataElemNames.add("3"); fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); List AirframeTypeElemNames = new ArrayList(); @@ -75,6 +77,9 @@ public class SystemSettings extends UAVDataObject { AirframeTypeEnumOptions.add("OctoCoaxX"); AirframeTypeEnumOptions.add("HexaCoax"); AirframeTypeEnumOptions.add("Tri"); + AirframeTypeEnumOptions.add("GroundVehicleCar"); + AirframeTypeEnumOptions.add("GroundVehicleDifferential"); + AirframeTypeEnumOptions.add("GroundVehicleMotorcycle"); fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); @@ -100,18 +105,17 @@ public class SystemSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -124,7 +128,9 @@ public class SystemSettings extends UAVDataObject { { getField("GUIConfigData").setValue(0,0); getField("GUIConfigData").setValue(0,1); - getField("AirframeType").setValue("FixedWing"); + getField("GUIConfigData").setValue(0,2); + getField("GUIConfigData").setValue(0,3); + getField("AirframeType").setValue("QuadX"); } @@ -153,7 +159,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30BD5D7C; + protected static final int OBJID = 0xC72A326E; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 26d01f2a0..888474261 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -106,18 +106,17 @@ public class SystemStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index eefcef6d9..9f530e6a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -62,11 +62,12 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("Airspeed"); StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("AltitudeHold"); - StackRemainingElemNames.add("Guidance"); - StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("PathPlanner"); + StackRemainingElemNames.add("PathFollower"); + StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); StackRemainingElemNames.add("OveroSync"); @@ -83,11 +84,12 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); + RunningElemNames.add("Airspeed"); RunningElemNames.add("Stabilization"); RunningElemNames.add("AltitudeHold"); - RunningElemNames.add("Guidance"); - RunningElemNames.add("FlightPlan"); RunningElemNames.add("PathPlanner"); + RunningElemNames.add("PathFollower"); + RunningElemNames.add("FlightPlan"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); RunningElemNames.add("OveroSync"); @@ -107,11 +109,12 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("Airspeed"); RunningTimeElemNames.add("Stabilization"); RunningTimeElemNames.add("AltitudeHold"); - RunningTimeElemNames.add("Guidance"); - RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("PathPlanner"); + RunningTimeElemNames.add("PathFollower"); + RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); RunningTimeElemNames.add("OveroSync"); @@ -140,18 +143,17 @@ public class TaskInfo extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -190,7 +192,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x498F54BA; + protected static final int OBJID = 0xB81CD2AE; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 823643130..7968c37c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -45,11 +45,15 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new AttitudeSimulated() ); + objMngr.registerObject( new BaroAirspeed() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); objMngr.registerObject( new CameraStabSettings() ); objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FixedWingPathFollowerSettings() ); + objMngr.registerObject( new FixedWingPathFollowerStatus() ); objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); @@ -61,38 +65,45 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSSettings() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GPSVelocity() ); objMngr.registerObject( new Gyros() ); objMngr.registerObject( new GyrosBias() ); - objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); - objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new MagBias() ); objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); - objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new OveroSyncSettings() ); + objMngr.registerObject( new OveroSyncStats() ); objMngr.registerObject( new PathDesired() ); + objMngr.registerObject( new PathPlannerSettings() ); + objMngr.registerObject( new PipXSettings() ); + objMngr.registerObject( new PipXStatus() ); objMngr.registerObject( new PositionActual() ); - objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); objMngr.registerObject( new ReceiverActivity() ); + objMngr.registerObject( new RevoCalibration() ); + objMngr.registerObject( new RevoSettings() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); - objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new VtolPathFollowerSettings() ); objMngr.registerObject( new WatchdogStatus() ); objMngr.registerObject( new Waypoint() ); objMngr.registerObject( new WaypointActive() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 2a8cd3754..a545bca16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -86,18 +86,17 @@ public class VelocityActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 436ef6448..f506a594c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -86,18 +86,17 @@ public class VelocityDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index acbdb43d1..94e85f57b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -82,18 +82,17 @@ public class WatchdogStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 64e2461f5..1283f03cb 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -74,18 +74,17 @@ $(FIELDSINIT) */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - - metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - - metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(FLIGHTACCESS)) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(GCSACCESS)) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE)) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE)) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; } From 32ec48412d8a2178f7e82be24dfde4bef16c3f89 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 13:08:47 -0500 Subject: [PATCH 099/165] Forgot to initialize the fields for metadata --- androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index c57b6c2fe..98a3bf8df 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -27,7 +27,8 @@ public class UAVMetaObject extends UAVObject { modesBitField.add("FlightUpdateOnChange"); modesBitField.add("GCSUpdatePeriodic"); modesBitField.add("GCSUpdateOnChange"); - + + List fields = new ArrayList(); fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); From 95218802daf0b496d71c68359894308de842ba46 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 13:49:16 -0500 Subject: [PATCH 100/165] Catch invalid number decoding to cover cases where there is no IP address. --- .../src/org/openpilot/androidgcs/OPTelemetryService.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 1a4b61eb8..917dfb116 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -72,8 +72,14 @@ public class OPTelemetryService extends Service { break; case MSG_CONNECT: terminate = false; + int connection_type; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + try { + connection_type = Integer.decode(prefs.getString("connection_type", "")); + } catch (NumberFormatException e) { + connection_type = 0; + } + switch(connection_type) { case 0: // No connection return; From 65861b4b8d7be00b4ae05c666a65a5a5190c3dca Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 01:35:49 -0500 Subject: [PATCH 101/165] Update the UAVO files --- .../openpilot/uavtalk/uavobjects/Accels.java | 150 ++++++++ .../uavtalk/uavobjects/AltHoldSmoothed.java | 146 ++++++++ .../uavobjects/AltitudeHoldDesired.java | 150 ++++++++ .../uavobjects/AltitudeHoldSettings.java | 169 +++++++++ .../uavtalk/uavobjects/AttitudeSimulated.java | 174 ++++++++++ .../uavtalk/uavobjects/BaroAirspeed.java | 153 ++++++++ .../FixedWingPathFollowerSettings.java | 239 +++++++++++++ .../FixedWingPathFollowerStatus.java | 164 +++++++++ .../uavtalk/uavobjects/GPSSettings.java | 142 ++++++++ .../uavtalk/uavobjects/GPSVelocity.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/Gyros.java | 150 ++++++++ .../uavtalk/uavobjects/GyrosBias.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/MagBias.java | 146 ++++++++ .../uavtalk/uavobjects/Magnetometer.java | 146 ++++++++ .../uavtalk/uavobjects/NEDPosition.java | 146 ++++++++ .../uavtalk/uavobjects/OveroSyncSettings.java | 143 ++++++++ .../uavtalk/uavobjects/OveroSyncStats.java | 165 +++++++++ .../uavtalk/uavobjects/PathDesired.java | 162 +++++++++ .../uavobjects/PathPlannerSettings.java | 151 ++++++++ .../uavtalk/uavobjects/PipXSettings.java | 326 ++++++++++++++++++ .../uavtalk/uavobjects/PipXStatus.java | 301 ++++++++++++++++ .../uavtalk/uavobjects/RevoCalibration.java | 249 +++++++++++++ .../uavtalk/uavobjects/RevoSettings.java | 143 ++++++++ .../uavtalk/uavobjects/TxPIDSettings.java | 225 ++++++++++++ .../uavobjects/VtolPathFollowerSettings.java | 232 +++++++++++++ .../uavtalk/uavobjects/Waypoint.java | 159 +++++++++ .../uavtalk/uavobjects/WaypointActive.java | 138 ++++++++ 27 files changed, 4761 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java new file mode 100644 index 000000000..32437e63e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The accel data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The accel data. + +generated from accels.xml + **/ +public class Accels extends UAVDataObject { + + public Accels() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "m/s^2", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "m/s^2", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "m/s^2", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Accels obj = new Accels(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Accels GetInstance(UAVObjectManager objMngr, int instID) + { + return (Accels)(objMngr.getObject(Accels.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDD9D5FC0; + protected static final String NAME = "Accels"; + protected static String DESCRIPTION = "The accel data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java new file mode 100644 index 000000000..46d03a544 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output on the kalman filter on altitude. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output on the kalman filter on altitude. + +generated from altholdsmoothed.xml + **/ +public class AltHoldSmoothed extends UAVDataObject { + + public AltHoldSmoothed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("0"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List AccelElemNames = new ArrayList(); + AccelElemNames.add("0"); + fields.add( new UAVObjectField("Accel", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltHoldSmoothed obj = new AltHoldSmoothed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltHoldSmoothed GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltHoldSmoothed)(objMngr.getObject(AltHoldSmoothed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2BC6B9D2; + protected static final String NAME = "AltHoldSmoothed"; + protected static String DESCRIPTION = "The output on the kalman filter on altitude."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java new file mode 100644 index 000000000..efe860340 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Holds the desired altitude (from manual control) as well as the desired attitude to pass through + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Holds the desired altitude (from manual control) as well as the desired attitude to pass through + +generated from altitudeholddesired.xml + **/ +public class AltitudeHoldDesired extends UAVDataObject { + + public AltitudeHoldDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldDesired obj = new AltitudeHoldDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldDesired)(objMngr.getObject(AltitudeHoldDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x495BAD6E; + protected static final String NAME = "AltitudeHoldDesired"; + protected static String DESCRIPTION = "Holds the desired altitude (from manual control) as well as the desired attitude to pass through"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java new file mode 100644 index 000000000..77b6774b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AltitudeHold module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AltitudeHold module + +generated from altitudeholdsettings.xml + **/ +public class AltitudeHoldSettings extends UAVDataObject { + + public AltitudeHoldSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List KpElemNames = new ArrayList(); + KpElemNames.add("0"); + fields.add( new UAVObjectField("Kp", "throttle/m", UAVObjectField.FieldType.FLOAT32, KpElemNames, null) ); + + List KiElemNames = new ArrayList(); + KiElemNames.add("0"); + fields.add( new UAVObjectField("Ki", "throttle/m", UAVObjectField.FieldType.FLOAT32, KiElemNames, null) ); + + List KdElemNames = new ArrayList(); + KdElemNames.add("0"); + fields.add( new UAVObjectField("Kd", "throttle/m", UAVObjectField.FieldType.FLOAT32, KdElemNames, null) ); + + List KaElemNames = new ArrayList(); + KaElemNames.add("0"); + fields.add( new UAVObjectField("Ka", "throttle/(m/s^2)", UAVObjectField.FieldType.FLOAT32, KaElemNames, null) ); + + List PressureNoiseElemNames = new ArrayList(); + PressureNoiseElemNames.add("0"); + fields.add( new UAVObjectField("PressureNoise", "m", UAVObjectField.FieldType.FLOAT32, PressureNoiseElemNames, null) ); + + List AccelNoiseElemNames = new ArrayList(); + AccelNoiseElemNames.add("0"); + fields.add( new UAVObjectField("AccelNoise", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelNoiseElemNames, null) ); + + List AccelDriftElemNames = new ArrayList(); + AccelDriftElemNames.add("0"); + fields.add( new UAVObjectField("AccelDrift", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelDriftElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Kp").setValue(0.03); + getField("Ki").setValue(0); + getField("Kd").setValue(0.03); + getField("Ka").setValue(0.005); + getField("PressureNoise").setValue(0.4); + getField("AccelNoise").setValue(5); + getField("AccelDrift").setValue(0.001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldSettings obj = new AltitudeHoldSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldSettings)(objMngr.getObject(AltitudeHoldSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFEC55B42; + protected static final String NAME = "AltitudeHoldSettings"; + protected static String DESCRIPTION = "Settings for the @ref AltitudeHold module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java new file mode 100644 index 000000000..3a713ab04 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java @@ -0,0 +1,174 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The simulated Attitude estimation from @ref Sensors. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The simulated Attitude estimation from @ref Sensors. + +generated from attitudesimulated.xml + **/ +public class AttitudeSimulated extends UAVDataObject { + + public AttitudeSimulated() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSimulated obj = new AttitudeSimulated(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSimulated GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSimulated)(objMngr.getObject(AttitudeSimulated.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9266CE74; + protected static final String NAME = "AttitudeSimulated"; + protected static String DESCRIPTION = "The simulated Attitude estimation from @ref Sensors."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java new file mode 100644 index 000000000..439915741 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java @@ -0,0 +1,153 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + +generated from baroairspeed.xml + **/ +public class BaroAirspeed extends UAVDataObject { + + public BaroAirspeed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirspeedElemNames = new ArrayList(); + AirspeedElemNames.add("0"); + fields.add( new UAVObjectField("Airspeed", "m/s", UAVObjectField.FieldType.FLOAT32, AirspeedElemNames, null) ); + + List SensorValueElemNames = new ArrayList(); + SensorValueElemNames.add("0"); + fields.add( new UAVObjectField("SensorValue", "raw", UAVObjectField.FieldType.UINT16, SensorValueElemNames, null) ); + + List ZeroPointElemNames = new ArrayList(); + ZeroPointElemNames.add("0"); + fields.add( new UAVObjectField("ZeroPoint", "raw", UAVObjectField.FieldType.UINT16, ZeroPointElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAirspeed obj = new BaroAirspeed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAirspeed GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAirspeed)(objMngr.getObject(BaroAirspeed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x169EA4A; + protected static final String NAME = "BaroAirspeed"; + protected static String DESCRIPTION = "The raw data from the dynamic pressure sensor with pressure, temperature and airspeed."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java new file mode 100644 index 000000000..00419bc4c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java @@ -0,0 +1,239 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref FixedWingPathFollowerModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref FixedWingPathFollowerModule + +generated from fixedwingpathfollowersettings.xml + **/ +public class FixedWingPathFollowerSettings extends UAVDataObject { + + public FixedWingPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirSpeedMaxElemNames = new ArrayList(); + AirSpeedMaxElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMax", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMaxElemNames, null) ); + + List AirSpeedMinElemNames = new ArrayList(); + AirSpeedMinElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMin", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMinElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.FLOAT32, VerticalVelMaxElemNames, null) ); + + List HorizontalPosPElemNames = new ArrayList(); + HorizontalPosPElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPElemNames, null) ); + + List VerticalPosPElemNames = new ArrayList(); + VerticalPosPElemNames.add("0"); + fields.add( new UAVObjectField("VerticalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, VerticalPosPElemNames, null) ); + + List CoursePIElemNames = new ArrayList(); + CoursePIElemNames.add("Kp"); + CoursePIElemNames.add("Ki"); + CoursePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("CoursePI", "deg/deg", UAVObjectField.FieldType.FLOAT32, CoursePIElemNames, null) ); + + List SpeedPElemNames = new ArrayList(); + SpeedPElemNames.add("Kp"); + SpeedPElemNames.add("Max"); + fields.add( new UAVObjectField("SpeedP", "(m/s^2) / ((m/s)/(m/s)", UAVObjectField.FieldType.FLOAT32, SpeedPElemNames, null) ); + + List AccelPIElemNames = new ArrayList(); + AccelPIElemNames.add("Kp"); + AccelPIElemNames.add("Ki"); + AccelPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("AccelPI", "deg / (m/s^2)", UAVObjectField.FieldType.FLOAT32, AccelPIElemNames, null) ); + + List VerticalToPitchCrossFeedElemNames = new ArrayList(); + VerticalToPitchCrossFeedElemNames.add("Kp"); + VerticalToPitchCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalToPitchCrossFeed", "deg / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, VerticalToPitchCrossFeedElemNames, null) ); + + List AirspeedToVerticalCrossFeedElemNames = new ArrayList(); + AirspeedToVerticalCrossFeedElemNames.add("Kp"); + AirspeedToVerticalCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("AirspeedToVerticalCrossFeed", "(m/s) / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, AirspeedToVerticalCrossFeedElemNames, null) ); + + List PowerPIElemNames = new ArrayList(); + PowerPIElemNames.add("Kp"); + PowerPIElemNames.add("Ki"); + PowerPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PowerPI", "1/(m/s)", UAVObjectField.FieldType.FLOAT32, PowerPIElemNames, null) ); + + List RollLimitElemNames = new ArrayList(); + RollLimitElemNames.add("Min"); + RollLimitElemNames.add("Neutral"); + RollLimitElemNames.add("Max"); + fields.add( new UAVObjectField("RollLimit", "deg", UAVObjectField.FieldType.FLOAT32, RollLimitElemNames, null) ); + + List PitchLimitElemNames = new ArrayList(); + PitchLimitElemNames.add("Min"); + PitchLimitElemNames.add("Neutral"); + PitchLimitElemNames.add("Max"); + fields.add( new UAVObjectField("PitchLimit", "deg", UAVObjectField.FieldType.FLOAT32, PitchLimitElemNames, null) ); + + List ThrottleLimitElemNames = new ArrayList(); + ThrottleLimitElemNames.add("Min"); + ThrottleLimitElemNames.add("Neutral"); + ThrottleLimitElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleLimit", "", UAVObjectField.FieldType.FLOAT32, ThrottleLimitElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirSpeedMax").setValue(15); + getField("AirSpeedMin").setValue(10); + getField("VerticalVelMax").setValue(10); + getField("HorizontalPosP").setValue(0.05); + getField("VerticalPosP").setValue(0.05); + getField("CoursePI").setValue(0.2,0); + getField("CoursePI").setValue(0,1); + getField("CoursePI").setValue(0,2); + getField("SpeedP").setValue(10,0); + getField("SpeedP").setValue(10,1); + getField("AccelPI").setValue(1.5,0); + getField("AccelPI").setValue(1.5,1); + getField("AccelPI").setValue(20,2); + getField("VerticalToPitchCrossFeed").setValue(50,0); + getField("VerticalToPitchCrossFeed").setValue(5,1); + getField("AirspeedToVerticalCrossFeed").setValue(100,0); + getField("AirspeedToVerticalCrossFeed").setValue(100,1); + getField("PowerPI").setValue(0.01,0); + getField("PowerPI").setValue(0.01,1); + getField("PowerPI").setValue(0.8,2); + getField("RollLimit").setValue(-35,0); + getField("RollLimit").setValue(0,1); + getField("RollLimit").setValue(35,2); + getField("PitchLimit").setValue(-10,0); + getField("PitchLimit").setValue(5,1); + getField("PitchLimit").setValue(20,2); + getField("ThrottleLimit").setValue(0.1,0); + getField("ThrottleLimit").setValue(0.5,1); + getField("ThrottleLimit").setValue(0.9,2); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerSettings obj = new FixedWingPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerSettings)(objMngr.getObject(FixedWingPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8A3F1E02; + protected static final String NAME = "FixedWingPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref FixedWingPathFollowerModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java new file mode 100644 index 000000000..a40be35cf --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Object Storing Debugging Information on PID internals + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Object Storing Debugging Information on PID internals + +generated from fixedwingpathfollowerstatus.xml + **/ +public class FixedWingPathFollowerStatus extends UAVDataObject { + + public FixedWingPathFollowerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List EElemNames = new ArrayList(); + EElemNames.add("Course"); + EElemNames.add("Speed"); + EElemNames.add("Accel"); + EElemNames.add("Power"); + fields.add( new UAVObjectField("E", "", UAVObjectField.FieldType.FLOAT32, EElemNames, null) ); + + List AElemNames = new ArrayList(); + AElemNames.add("Course"); + AElemNames.add("Speed"); + AElemNames.add("Accel"); + AElemNames.add("Power"); + fields.add( new UAVObjectField("A", "", UAVObjectField.FieldType.FLOAT32, AElemNames, null) ); + + List CElemNames = new ArrayList(); + CElemNames.add("Course"); + CElemNames.add("Speed"); + CElemNames.add("Accel"); + CElemNames.add("Power"); + fields.add( new UAVObjectField("C", "", UAVObjectField.FieldType.FLOAT32, CElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("Wind"); + ErrorsElemNames.add("Lowspeed"); + ErrorsElemNames.add("Highspeed"); + ErrorsElemNames.add("Lowpower"); + ErrorsElemNames.add("Highpower"); + ErrorsElemNames.add("Pitchcontrol"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT8, ErrorsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 500; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerStatus obj = new FixedWingPathFollowerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerStatus)(objMngr.getObject(FixedWingPathFollowerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA0D6F6D4; + protected static final String NAME = "FixedWingPathFollowerStatus"; + protected static String DESCRIPTION = "Object Storing Debugging Information on PID internals"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java new file mode 100644 index 000000000..f534fc89c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the GPS + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the GPS + +generated from gpssettings.xml + **/ +public class GPSSettings extends UAVDataObject { + + public GPSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List DataProtocolElemNames = new ArrayList(); + DataProtocolElemNames.add("0"); + List DataProtocolEnumOptions = new ArrayList(); + DataProtocolEnumOptions.add("NMEA"); + DataProtocolEnumOptions.add("UBX"); + fields.add( new UAVObjectField("DataProtocol", "", UAVObjectField.FieldType.ENUM, DataProtocolElemNames, DataProtocolEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("DataProtocol").setValue("NMEA"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSettings obj = new GPSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSettings)(objMngr.getObject(GPSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAC5F6370; + protected static final String NAME = "GPSSettings"; + protected static String DESCRIPTION = "Settings for the GPS"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java new file mode 100644 index 000000000..2ce4a3c62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. + +generated from gpsvelocity.xml + **/ +public class GPSVelocity extends UAVDataObject { + + public GPSVelocity() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSVelocity obj = new GPSVelocity(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSVelocity GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSVelocity)(objMngr.getObject(GPSVelocity.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8245DC80; + protected static final String NAME = "GPSVelocity"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java new file mode 100644 index 000000000..5c960d2e6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyros.xml + **/ +public class Gyros extends UAVDataObject { + + public Gyros() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Gyros obj = new Gyros(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Gyros GetInstance(UAVObjectManager objMngr, int instID) + { + return (Gyros)(objMngr.getObject(Gyros.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4228AF6; + protected static final String NAME = "Gyros"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java new file mode 100644 index 000000000..00bc7da2d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyrosbias.xml + **/ +public class GyrosBias extends UAVDataObject { + + public GyrosBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GyrosBias obj = new GyrosBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GyrosBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (GyrosBias)(objMngr.getObject(GyrosBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE4B6F980; + protected static final String NAME = "GyrosBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java new file mode 100644 index 000000000..398f455d5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from magbias.xml + **/ +public class MagBias extends UAVDataObject { + + public MagBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGau", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGau", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGau", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MagBias obj = new MagBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MagBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (MagBias)(objMngr.getObject(MagBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5043E510; + protected static final String NAME = "MagBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java new file mode 100644 index 000000000..583817cca --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The mag data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The mag data. + +generated from magnetometer.xml + **/ +public class Magnetometer extends UAVDataObject { + + public Magnetometer() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGa", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGa", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGa", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Magnetometer obj = new Magnetometer(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Magnetometer GetInstance(UAVObjectManager objMngr, int instID) + { + return (Magnetometer)(objMngr.getObject(Magnetometer.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x813B55DE; + protected static final String NAME = "Magnetometer"; + protected static String DESCRIPTION = "The mag data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java new file mode 100644 index 000000000..0aa67862e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from nedposition.xml + **/ +public class NEDPosition extends UAVDataObject { + + public NEDPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NEDPosition obj = new NEDPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NEDPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (NEDPosition)(objMngr.getObject(NEDPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FB15A00; + protected static final String NAME = "NEDPosition"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java new file mode 100644 index 000000000..c680d230c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to control the behavior of the overo sync module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to control the behavior of the overo sync module + +generated from overosyncsettings.xml + **/ +public class OveroSyncSettings extends UAVDataObject { + + public OveroSyncSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List LogOnElemNames = new ArrayList(); + LogOnElemNames.add("0"); + List LogOnEnumOptions = new ArrayList(); + LogOnEnumOptions.add("Never"); + LogOnEnumOptions.add("Always"); + LogOnEnumOptions.add("Armed"); + fields.add( new UAVObjectField("LogOn", "", UAVObjectField.FieldType.ENUM, LogOnElemNames, LogOnEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("LogOn").setValue("Armed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncSettings obj = new OveroSyncSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncSettings)(objMngr.getObject(OveroSyncSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA1ABC278; + protected static final String NAME = "OveroSyncSettings"; + protected static String DESCRIPTION = "Settings to control the behavior of the overo sync module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java new file mode 100644 index 000000000..4c31f21dd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains statistics on transfer rate to and from over + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains statistics on transfer rate to and from over + +generated from overosyncstats.xml + **/ +public class OveroSyncStats extends UAVDataObject { + + public OveroSyncStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SendElemNames = new ArrayList(); + SendElemNames.add("0"); + fields.add( new UAVObjectField("Send", "B/s", UAVObjectField.FieldType.UINT32, SendElemNames, null) ); + + List ReceivedElemNames = new ArrayList(); + ReceivedElemNames.add("0"); + fields.add( new UAVObjectField("Received", "B/s", UAVObjectField.FieldType.UINT32, ReceivedElemNames, null) ); + + List FramesyncErrorsElemNames = new ArrayList(); + FramesyncErrorsElemNames.add("0"); + fields.add( new UAVObjectField("FramesyncErrors", "count", UAVObjectField.FieldType.UINT32, FramesyncErrorsElemNames, null) ); + + List UnderrunErrorsElemNames = new ArrayList(); + UnderrunErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UnderrunErrors", "count", UAVObjectField.FieldType.UINT32, UnderrunErrorsElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "", UAVObjectField.FieldType.UINT32, DroppedUpdatesElemNames, null) ); + + List PacketsElemNames = new ArrayList(); + PacketsElemNames.add("0"); + fields.add( new UAVObjectField("Packets", "", UAVObjectField.FieldType.UINT32, PacketsElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncStats obj = new OveroSyncStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncStats)(objMngr.getObject(OveroSyncStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD2085FAC; + protected static final String NAME = "OveroSyncStats"; + protected static String DESCRIPTION = "Maintains statistics on transfer rate to and from over"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java new file mode 100644 index 000000000..38e710477 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + +generated from pathdesired.xml + **/ +public class PathDesired extends UAVDataObject { + + public PathDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StartElemNames = new ArrayList(); + StartElemNames.add("North"); + StartElemNames.add("East"); + StartElemNames.add("Down"); + fields.add( new UAVObjectField("Start", "m", UAVObjectField.FieldType.FLOAT32, StartElemNames, null) ); + + List EndElemNames = new ArrayList(); + EndElemNames.add("North"); + EndElemNames.add("East"); + EndElemNames.add("Down"); + fields.add( new UAVObjectField("End", "m", UAVObjectField.FieldType.FLOAT32, EndElemNames, null) ); + + List StartingVelocityElemNames = new ArrayList(); + StartingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("StartingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, StartingVelocityElemNames, null) ); + + List EndingVelocityElemNames = new ArrayList(); + EndingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("EndingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, EndingVelocityElemNames, null) ); + + List ModeElemNames = new ArrayList(); + ModeElemNames.add("0"); + List ModeEnumOptions = new ArrayList(); + ModeEnumOptions.add("Endpoint"); + ModeEnumOptions.add("Path"); + ModeEnumOptions.add("Land"); + fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathDesired obj = new PathDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathDesired)(objMngr.getObject(PathDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5A4DC71A; + protected static final String NAME = "PathDesired"; + protected static String DESCRIPTION = "The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java new file mode 100644 index 000000000..fb6b66e19 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref PathPlanner Module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref PathPlanner Module + +generated from pathplannersettings.xml + **/ +public class PathPlannerSettings extends UAVDataObject { + + public PathPlannerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PathModeElemNames = new ArrayList(); + PathModeElemNames.add("0"); + List PathModeEnumOptions = new ArrayList(); + PathModeEnumOptions.add("ENDPOINT"); + PathModeEnumOptions.add("PATH"); + fields.add( new UAVObjectField("PathMode", "", UAVObjectField.FieldType.ENUM, PathModeElemNames, PathModeEnumOptions) ); + + List PreprogrammedPathElemNames = new ArrayList(); + PreprogrammedPathElemNames.add("0"); + List PreprogrammedPathEnumOptions = new ArrayList(); + PreprogrammedPathEnumOptions.add("NONE"); + PreprogrammedPathEnumOptions.add("10M_BOX"); + PreprogrammedPathEnumOptions.add("LOGO"); + fields.add( new UAVObjectField("PreprogrammedPath", "", UAVObjectField.FieldType.ENUM, PreprogrammedPathElemNames, PreprogrammedPathEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PathMode").setValue("PATH"); + getField("PreprogrammedPath").setValue("NONE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathPlannerSettings obj = new PathPlannerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathPlannerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathPlannerSettings)(objMngr.getObject(PathPlannerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x290E45DA; + protected static final String NAME = "PathPlannerSettings"; + protected static String DESCRIPTION = "Settings for the @ref PathPlanner Module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java new file mode 100644 index 000000000..aa5387148 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java @@ -0,0 +1,326 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme configurations options. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme configurations options. + +generated from pipxsettings.xml + **/ +public class PipXSettings extends UAVDataObject { + + public PipXSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PairIDElemNames = new ArrayList(); + PairIDElemNames.add("0"); + fields.add( new UAVObjectField("PairID", "", UAVObjectField.FieldType.UINT32, PairIDElemNames, null) ); + + List FrequencyElemNames = new ArrayList(); + FrequencyElemNames.add("0"); + fields.add( new UAVObjectField("Frequency", "", UAVObjectField.FieldType.UINT32, FrequencyElemNames, null) ); + + List SendTimeoutElemNames = new ArrayList(); + SendTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("SendTimeout", "ms", UAVObjectField.FieldType.UINT16, SendTimeoutElemNames, null) ); + + List TelemetryConfigElemNames = new ArrayList(); + TelemetryConfigElemNames.add("0"); + List TelemetryConfigEnumOptions = new ArrayList(); + TelemetryConfigEnumOptions.add("Disabled"); + TelemetryConfigEnumOptions.add("Serial"); + TelemetryConfigEnumOptions.add("UAVTalk"); + TelemetryConfigEnumOptions.add("GCS"); + TelemetryConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("TelemetryConfig", "function", UAVObjectField.FieldType.ENUM, TelemetryConfigElemNames, TelemetryConfigEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List FlexiConfigElemNames = new ArrayList(); + FlexiConfigElemNames.add("0"); + List FlexiConfigEnumOptions = new ArrayList(); + FlexiConfigEnumOptions.add("Disabled"); + FlexiConfigEnumOptions.add("Serial"); + FlexiConfigEnumOptions.add("UAVTalk"); + FlexiConfigEnumOptions.add("GCS"); + FlexiConfigEnumOptions.add("PPM_In"); + FlexiConfigEnumOptions.add("PPM_Out"); + FlexiConfigEnumOptions.add("RSSI"); + FlexiConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("FlexiConfig", "function", UAVObjectField.FieldType.ENUM, FlexiConfigElemNames, FlexiConfigEnumOptions) ); + + List FlexiSpeedElemNames = new ArrayList(); + FlexiSpeedElemNames.add("0"); + List FlexiSpeedEnumOptions = new ArrayList(); + FlexiSpeedEnumOptions.add("2400"); + FlexiSpeedEnumOptions.add("4800"); + FlexiSpeedEnumOptions.add("9600"); + FlexiSpeedEnumOptions.add("19200"); + FlexiSpeedEnumOptions.add("38400"); + FlexiSpeedEnumOptions.add("57600"); + FlexiSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("FlexiSpeed", "bps", UAVObjectField.FieldType.ENUM, FlexiSpeedElemNames, FlexiSpeedEnumOptions) ); + + List VCPConfigElemNames = new ArrayList(); + VCPConfigElemNames.add("0"); + List VCPConfigEnumOptions = new ArrayList(); + VCPConfigEnumOptions.add("Disabled"); + VCPConfigEnumOptions.add("Serial"); + VCPConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("VCPConfig", "function", UAVObjectField.FieldType.ENUM, VCPConfigElemNames, VCPConfigEnumOptions) ); + + List VCPSpeedElemNames = new ArrayList(); + VCPSpeedElemNames.add("0"); + List VCPSpeedEnumOptions = new ArrayList(); + VCPSpeedEnumOptions.add("2400"); + VCPSpeedEnumOptions.add("4800"); + VCPSpeedEnumOptions.add("9600"); + VCPSpeedEnumOptions.add("19200"); + VCPSpeedEnumOptions.add("38400"); + VCPSpeedEnumOptions.add("57600"); + VCPSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("VCPSpeed", "bps", UAVObjectField.FieldType.ENUM, VCPSpeedElemNames, VCPSpeedEnumOptions) ); + + List RFSpeedElemNames = new ArrayList(); + RFSpeedElemNames.add("0"); + List RFSpeedEnumOptions = new ArrayList(); + RFSpeedEnumOptions.add("2400"); + RFSpeedEnumOptions.add("4800"); + RFSpeedEnumOptions.add("9600"); + RFSpeedEnumOptions.add("19200"); + RFSpeedEnumOptions.add("38400"); + RFSpeedEnumOptions.add("57600"); + RFSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("RFSpeed", "bps", UAVObjectField.FieldType.ENUM, RFSpeedElemNames, RFSpeedEnumOptions) ); + + List MaxRFPowerElemNames = new ArrayList(); + MaxRFPowerElemNames.add("0"); + List MaxRFPowerEnumOptions = new ArrayList(); + MaxRFPowerEnumOptions.add("1.25"); + MaxRFPowerEnumOptions.add("1.6"); + MaxRFPowerEnumOptions.add("3.16"); + MaxRFPowerEnumOptions.add("6.3"); + MaxRFPowerEnumOptions.add("12.6"); + MaxRFPowerEnumOptions.add("25"); + MaxRFPowerEnumOptions.add("50"); + MaxRFPowerEnumOptions.add("100"); + fields.add( new UAVObjectField("MaxRFPower", "mW", UAVObjectField.FieldType.ENUM, MaxRFPowerElemNames, MaxRFPowerEnumOptions) ); + + List MinPacketSizeElemNames = new ArrayList(); + MinPacketSizeElemNames.add("0"); + fields.add( new UAVObjectField("MinPacketSize", "bytes", UAVObjectField.FieldType.UINT8, MinPacketSizeElemNames, null) ); + + List FrequencyCalibrationElemNames = new ArrayList(); + FrequencyCalibrationElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyCalibration", "", UAVObjectField.FieldType.UINT8, FrequencyCalibrationElemNames, null) ); + + List AESKeyElemNames = new ArrayList(); + AESKeyElemNames.add("0"); + AESKeyElemNames.add("1"); + AESKeyElemNames.add("2"); + AESKeyElemNames.add("3"); + AESKeyElemNames.add("4"); + AESKeyElemNames.add("5"); + AESKeyElemNames.add("6"); + AESKeyElemNames.add("7"); + AESKeyElemNames.add("8"); + AESKeyElemNames.add("9"); + AESKeyElemNames.add("10"); + AESKeyElemNames.add("11"); + AESKeyElemNames.add("12"); + AESKeyElemNames.add("13"); + AESKeyElemNames.add("14"); + AESKeyElemNames.add("15"); + AESKeyElemNames.add("16"); + AESKeyElemNames.add("17"); + AESKeyElemNames.add("18"); + AESKeyElemNames.add("19"); + AESKeyElemNames.add("20"); + AESKeyElemNames.add("21"); + AESKeyElemNames.add("22"); + AESKeyElemNames.add("23"); + AESKeyElemNames.add("24"); + AESKeyElemNames.add("25"); + AESKeyElemNames.add("26"); + AESKeyElemNames.add("27"); + AESKeyElemNames.add("28"); + AESKeyElemNames.add("29"); + AESKeyElemNames.add("30"); + AESKeyElemNames.add("31"); + fields.add( new UAVObjectField("AESKey", "", UAVObjectField.FieldType.UINT8, AESKeyElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PairID").setValue(0); + getField("Frequency").setValue(434000000); + getField("SendTimeout").setValue(50); + getField("TelemetryConfig").setValue("UAVTalk"); + getField("TelemetrySpeed").setValue("57600"); + getField("FlexiConfig").setValue("Disabled"); + getField("FlexiSpeed").setValue("57600"); + getField("VCPConfig").setValue("Disabled"); + getField("VCPSpeed").setValue("57600"); + getField("RFSpeed").setValue("115200"); + getField("MaxRFPower").setValue("100"); + getField("MinPacketSize").setValue(50); + getField("FrequencyCalibration").setValue(127); + getField("AESKey").setValue(0,0); + getField("AESKey").setValue(0,1); + getField("AESKey").setValue(0,2); + getField("AESKey").setValue(0,3); + getField("AESKey").setValue(0,4); + getField("AESKey").setValue(0,5); + getField("AESKey").setValue(0,6); + getField("AESKey").setValue(0,7); + getField("AESKey").setValue(0,8); + getField("AESKey").setValue(0,9); + getField("AESKey").setValue(0,10); + getField("AESKey").setValue(0,11); + getField("AESKey").setValue(0,12); + getField("AESKey").setValue(0,13); + getField("AESKey").setValue(0,14); + getField("AESKey").setValue(0,15); + getField("AESKey").setValue(0,16); + getField("AESKey").setValue(0,17); + getField("AESKey").setValue(0,18); + getField("AESKey").setValue(0,19); + getField("AESKey").setValue(0,20); + getField("AESKey").setValue(0,21); + getField("AESKey").setValue(0,22); + getField("AESKey").setValue(0,23); + getField("AESKey").setValue(0,24); + getField("AESKey").setValue(0,25); + getField("AESKey").setValue(0,26); + getField("AESKey").setValue(0,27); + getField("AESKey").setValue(0,28); + getField("AESKey").setValue(0,29); + getField("AESKey").setValue(0,30); + getField("AESKey").setValue(0,31); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXSettings obj = new PipXSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXSettings)(objMngr.getObject(PipXSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA192BCA; + protected static final String NAME = "PipXSettings"; + protected static String DESCRIPTION = "PipXtreme configurations options."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java new file mode 100644 index 000000000..fb6a91e33 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java @@ -0,0 +1,301 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme device status. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme device status. + +generated from pipxstatus.xml + **/ +public class PipXStatus extends UAVDataObject { + + public PipXStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MinFrequencyElemNames = new ArrayList(); + MinFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MinFrequency", "Hz", UAVObjectField.FieldType.UINT32, MinFrequencyElemNames, null) ); + + List MaxFrequencyElemNames = new ArrayList(); + MaxFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MaxFrequency", "Hz", UAVObjectField.FieldType.UINT32, MaxFrequencyElemNames, null) ); + + List FrequencyStepSizeElemNames = new ArrayList(); + FrequencyStepSizeElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyStepSize", "", UAVObjectField.FieldType.FLOAT32, FrequencyStepSizeElemNames, null) ); + + List DeviceIDElemNames = new ArrayList(); + DeviceIDElemNames.add("0"); + fields.add( new UAVObjectField("DeviceID", "", UAVObjectField.FieldType.UINT32, DeviceIDElemNames, null) ); + + List AFCElemNames = new ArrayList(); + AFCElemNames.add("0"); + fields.add( new UAVObjectField("AFC", "", UAVObjectField.FieldType.INT32, AFCElemNames, null) ); + + List PairIDsElemNames = new ArrayList(); + PairIDsElemNames.add("0"); + PairIDsElemNames.add("1"); + PairIDsElemNames.add("2"); + PairIDsElemNames.add("3"); + fields.add( new UAVObjectField("PairIDs", "", UAVObjectField.FieldType.UINT32, PairIDsElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List RetriesElemNames = new ArrayList(); + RetriesElemNames.add("0"); + fields.add( new UAVObjectField("Retries", "", UAVObjectField.FieldType.UINT16, RetriesElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("0"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT16, ErrorsElemNames, null) ); + + List UAVTalkErrorsElemNames = new ArrayList(); + UAVTalkErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UAVTalkErrors", "", UAVObjectField.FieldType.UINT16, UAVTalkErrorsElemNames, null) ); + + List DroppedElemNames = new ArrayList(); + DroppedElemNames.add("0"); + fields.add( new UAVObjectField("Dropped", "", UAVObjectField.FieldType.UINT16, DroppedElemNames, null) ); + + List ResetsElemNames = new ArrayList(); + ResetsElemNames.add("0"); + fields.add( new UAVObjectField("Resets", "", UAVObjectField.FieldType.UINT16, ResetsElemNames, null) ); + + List TXRateElemNames = new ArrayList(); + TXRateElemNames.add("0"); + fields.add( new UAVObjectField("TXRate", "Bps", UAVObjectField.FieldType.UINT16, TXRateElemNames, null) ); + + List RXRateElemNames = new ArrayList(); + RXRateElemNames.add("0"); + fields.add( new UAVObjectField("RXRate", "Bps", UAVObjectField.FieldType.UINT16, RXRateElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List FrequencyBandElemNames = new ArrayList(); + FrequencyBandElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyBand", "", UAVObjectField.FieldType.UINT8, FrequencyBandElemNames, null) ); + + List RSSIElemNames = new ArrayList(); + RSSIElemNames.add("0"); + fields.add( new UAVObjectField("RSSI", "dBm", UAVObjectField.FieldType.INT8, RSSIElemNames, null) ); + + List LinkStateElemNames = new ArrayList(); + LinkStateElemNames.add("0"); + List LinkStateEnumOptions = new ArrayList(); + LinkStateEnumOptions.add("Disconnected"); + LinkStateEnumOptions.add("Connecting"); + LinkStateEnumOptions.add("Connected"); + fields.add( new UAVObjectField("LinkState", "function", UAVObjectField.FieldType.ENUM, LinkStateElemNames, LinkStateEnumOptions) ); + + List PairSignalStrengthsElemNames = new ArrayList(); + PairSignalStrengthsElemNames.add("0"); + PairSignalStrengthsElemNames.add("1"); + PairSignalStrengthsElemNames.add("2"); + PairSignalStrengthsElemNames.add("3"); + fields.add( new UAVObjectField("PairSignalStrengths", "dBm", UAVObjectField.FieldType.INT8, PairSignalStrengthsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MinFrequency").setValue(0); + getField("MaxFrequency").setValue(0); + getField("FrequencyStepSize").setValue(0); + getField("DeviceID").setValue(0); + getField("AFC").setValue(0); + getField("PairIDs").setValue(0,0); + getField("PairIDs").setValue(0,1); + getField("PairIDs").setValue(0,2); + getField("PairIDs").setValue(0,3); + getField("Retries").setValue(0); + getField("Errors").setValue(0); + getField("UAVTalkErrors").setValue(0); + getField("Dropped").setValue(0); + getField("Resets").setValue(0); + getField("TXRate").setValue(0); + getField("RXRate").setValue(0); + getField("FrequencyBand").setValue(0); + getField("RSSI").setValue(0); + getField("LinkState").setValue("Disconnected"); + getField("PairSignalStrengths").setValue(-127,0); + getField("PairSignalStrengths").setValue(-127,1); + getField("PairSignalStrengths").setValue(-127,2); + getField("PairSignalStrengths").setValue(-127,3); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXStatus obj = new PipXStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXStatus)(objMngr.getObject(PipXStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3FC68A86; + protected static final String NAME = "PipXStatus"; + protected static String DESCRIPTION = "PipXtreme device status."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java new file mode 100644 index 000000000..940f78875 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java @@ -0,0 +1,249 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the INS to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the INS to control the algorithm and what is updated + +generated from revocalibration.xml + **/ +public class RevoCalibration extends UAVDataObject { + + public RevoCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "gain", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "deg/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "gain", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(deg/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcoeffElemNames = new ArrayList(); + gyro_tempcoeffElemNames.add("X"); + gyro_tempcoeffElemNames.add("Y"); + gyro_tempcoeffElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcoeff", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, gyro_tempcoeffElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "gain", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List gps_varElemNames = new ArrayList(); + gps_varElemNames.add("Pos"); + gps_varElemNames.add("Vel"); + fields.add( new UAVObjectField("gps_var", "m^2", UAVObjectField.FieldType.FLOAT32, gps_varElemNames, null) ); + + List baro_varElemNames = new ArrayList(); + baro_varElemNames.add("0"); + fields.add( new UAVObjectField("baro_var", "m^2", UAVObjectField.FieldType.FLOAT32, baro_varElemNames, null) ); + + List MagBiasNullingRateElemNames = new ArrayList(); + MagBiasNullingRateElemNames.add("0"); + fields.add( new UAVObjectField("MagBiasNullingRate", "", UAVObjectField.FieldType.FLOAT32, MagBiasNullingRateElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("FALSE"); + BiasCorrectedRawEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("accel_bias").setValue(0,0); + getField("accel_bias").setValue(0,1); + getField("accel_bias").setValue(0,2); + getField("accel_scale").setValue(1,0); + getField("accel_scale").setValue(1,1); + getField("accel_scale").setValue(1,2); + getField("accel_var").setValue(0.01,0); + getField("accel_var").setValue(0.01,1); + getField("accel_var").setValue(0.01,2); + getField("gyro_bias").setValue(0,0); + getField("gyro_bias").setValue(0,1); + getField("gyro_bias").setValue(0,2); + getField("gyro_scale").setValue(1,0); + getField("gyro_scale").setValue(1,1); + getField("gyro_scale").setValue(1,2); + getField("gyro_var").setValue(0.01,0); + getField("gyro_var").setValue(0.01,1); + getField("gyro_var").setValue(0.01,2); + getField("gyro_tempcoeff").setValue(1,0); + getField("gyro_tempcoeff").setValue(1,1); + getField("gyro_tempcoeff").setValue(1,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); + getField("mag_var").setValue(0.01,0); + getField("mag_var").setValue(0.01,1); + getField("mag_var").setValue(10,2); + getField("gps_var").setValue(1,0); + getField("gps_var").setValue(1,1); + getField("baro_var").setValue(1); + getField("MagBiasNullingRate").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoCalibration obj = new RevoCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoCalibration)(objMngr.getObject(RevoCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA2A63C7C; + protected static final String NAME = "RevoCalibration"; + protected static String DESCRIPTION = "Settings for the INS to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java new file mode 100644 index 000000000..5e36565b2 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the revo to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the revo to control the algorithm and what is updated + +generated from revosettings.xml + **/ +public class RevoSettings extends UAVDataObject { + + public RevoSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FusionAlgorithmElemNames = new ArrayList(); + FusionAlgorithmElemNames.add("0"); + List FusionAlgorithmEnumOptions = new ArrayList(); + FusionAlgorithmEnumOptions.add("Complimentary"); + FusionAlgorithmEnumOptions.add("INSIndoor"); + FusionAlgorithmEnumOptions.add("INSOutdoor"); + fields.add( new UAVObjectField("FusionAlgorithm", "", UAVObjectField.FieldType.ENUM, FusionAlgorithmElemNames, FusionAlgorithmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FusionAlgorithm").setValue("Complimentary"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoSettings obj = new RevoSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoSettings)(objMngr.getObject(RevoSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2DA70EA; + protected static final String NAME = "RevoSettings"; + protected static String DESCRIPTION = "Settings for the revo to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java new file mode 100644 index 000000000..789f31b3f --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + +generated from txpidsettings.xml + **/ +public class TxPIDSettings extends UAVDataObject { + + public TxPIDSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ThrottleRangeElemNames = new ArrayList(); + ThrottleRangeElemNames.add("Min"); + ThrottleRangeElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleRange", "%", UAVObjectField.FieldType.FLOAT32, ThrottleRangeElemNames, null) ); + + List MinPIDElemNames = new ArrayList(); + MinPIDElemNames.add("Instance1"); + MinPIDElemNames.add("Instance2"); + MinPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MinPID", "", UAVObjectField.FieldType.FLOAT32, MinPIDElemNames, null) ); + + List MaxPIDElemNames = new ArrayList(); + MaxPIDElemNames.add("Instance1"); + MaxPIDElemNames.add("Instance2"); + MaxPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MaxPID", "", UAVObjectField.FieldType.FLOAT32, MaxPIDElemNames, null) ); + + List UpdateModeElemNames = new ArrayList(); + UpdateModeElemNames.add("0"); + List UpdateModeEnumOptions = new ArrayList(); + UpdateModeEnumOptions.add("Never"); + UpdateModeEnumOptions.add("When Armed"); + UpdateModeEnumOptions.add("Always"); + fields.add( new UAVObjectField("UpdateMode", "option", UAVObjectField.FieldType.ENUM, UpdateModeElemNames, UpdateModeEnumOptions) ); + + List InputsElemNames = new ArrayList(); + InputsElemNames.add("Instance1"); + InputsElemNames.add("Instance2"); + InputsElemNames.add("Instance3"); + List InputsEnumOptions = new ArrayList(); + InputsEnumOptions.add("Throttle"); + InputsEnumOptions.add("Accessory0"); + InputsEnumOptions.add("Accessory1"); + InputsEnumOptions.add("Accessory2"); + InputsEnumOptions.add("Accessory3"); + InputsEnumOptions.add("Accessory4"); + InputsEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Inputs", "channel", UAVObjectField.FieldType.ENUM, InputsElemNames, InputsEnumOptions) ); + + List PIDsElemNames = new ArrayList(); + PIDsElemNames.add("Instance1"); + PIDsElemNames.add("Instance2"); + PIDsElemNames.add("Instance3"); + List PIDsEnumOptions = new ArrayList(); + PIDsEnumOptions.add("Disabled"); + PIDsEnumOptions.add("Roll Rate.Kp"); + PIDsEnumOptions.add("Pitch Rate.Kp"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kp"); + PIDsEnumOptions.add("Yaw Rate.Kp"); + PIDsEnumOptions.add("Roll Rate.Ki"); + PIDsEnumOptions.add("Pitch Rate.Ki"); + PIDsEnumOptions.add("Roll+Pitch Rate.Ki"); + PIDsEnumOptions.add("Yaw Rate.Ki"); + PIDsEnumOptions.add("Roll Rate.Kd"); + PIDsEnumOptions.add("Pitch Rate.Kd"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kd"); + PIDsEnumOptions.add("Yaw Rate.Kd"); + PIDsEnumOptions.add("Roll Rate.ILimit"); + PIDsEnumOptions.add("Pitch Rate.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Rate.ILimit"); + PIDsEnumOptions.add("Yaw Rate.ILimit"); + PIDsEnumOptions.add("Roll Attitude.Kp"); + PIDsEnumOptions.add("Pitch Attitude.Kp"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Kp"); + PIDsEnumOptions.add("Yaw Attitude.Kp"); + PIDsEnumOptions.add("Roll Attitude.Ki"); + PIDsEnumOptions.add("Pitch Attitude.Ki"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Ki"); + PIDsEnumOptions.add("Yaw Attitude.Ki"); + PIDsEnumOptions.add("Roll Attitude.ILimit"); + PIDsEnumOptions.add("Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Yaw Attitude.ILimit"); + PIDsEnumOptions.add("GyroTau"); + fields.add( new UAVObjectField("PIDs", "option", UAVObjectField.FieldType.ENUM, PIDsElemNames, PIDsEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("ThrottleRange").setValue(0.2,0); + getField("ThrottleRange").setValue(0.8,1); + getField("MinPID").setValue(0,0); + getField("MinPID").setValue(0,1); + getField("MinPID").setValue(0,2); + getField("MaxPID").setValue(0,0); + getField("MaxPID").setValue(0,1); + getField("MaxPID").setValue(0,2); + getField("UpdateMode").setValue("When Armed"); + getField("Inputs").setValue("Throttle",0); + getField("Inputs").setValue("Accessory0",1); + getField("Inputs").setValue("Accessory1",2); + getField("PIDs").setValue("Disabled",0); + getField("PIDs").setValue("Disabled",1); + getField("PIDs").setValue("Disabled",2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TxPIDSettings obj = new TxPIDSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TxPIDSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TxPIDSettings)(objMngr.getObject(TxPIDSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x42B2D2AE; + protected static final String NAME = "TxPIDSettings"; + protected static String DESCRIPTION = "Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java new file mode 100644 index 000000000..b3c01dc8a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java @@ -0,0 +1,232 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref VtolPathFollower module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref VtolPathFollower module + +generated from vtolpathfollowersettings.xml + **/ +public class VtolPathFollowerSettings extends UAVDataObject { + + public VtolPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List VelocityFeedforwardElemNames = new ArrayList(); + VelocityFeedforwardElemNames.add("0"); + fields.add( new UAVObjectField("VelocityFeedforward", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, VelocityFeedforwardElemNames, null) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List VelocitySourceElemNames = new ArrayList(); + VelocitySourceElemNames.add("0"); + List VelocitySourceEnumOptions = new ArrayList(); + VelocitySourceEnumOptions.add("EKF"); + VelocitySourceEnumOptions.add("NEDVEL"); + VelocitySourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("VelocitySource", "", UAVObjectField.FieldType.ENUM, VelocitySourceElemNames, VelocitySourceEnumOptions) ); + + List PositionSourceElemNames = new ArrayList(); + PositionSourceElemNames.add("0"); + List PositionSourceEnumOptions = new ArrayList(); + PositionSourceEnumOptions.add("EKF"); + PositionSourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("PositionSource", "", UAVObjectField.FieldType.ENUM, PositionSourceElemNames, PositionSourceEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("HorizontalPosPI").setValue(1,0); + getField("HorizontalPosPI").setValue(0,1); + getField("HorizontalPosPI").setValue(0,2); + getField("HorizontalVelPID").setValue(5,0); + getField("HorizontalVelPID").setValue(0,1); + getField("HorizontalVelPID").setValue(1,2); + getField("HorizontalVelPID").setValue(0,3); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("VelocityFeedforward").setValue(0); + getField("MaxRollPitch").setValue(20); + getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(10); + getField("VerticalVelMax").setValue(1); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); + getField("VelocitySource").setValue("EKF"); + getField("PositionSource").setValue("EKF"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VtolPathFollowerSettings obj = new VtolPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VtolPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (VtolPathFollowerSettings)(objMngr.getObject(VtolPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x973991F6; + protected static final String NAME = "VtolPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref VtolPathFollower module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java new file mode 100644 index 000000000..4db7179ad --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + +generated from waypoint.xml + **/ +public class Waypoint extends UAVDataObject { + + public Waypoint() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List YawDesiredElemNames = new ArrayList(); + YawDesiredElemNames.add("0"); + fields.add( new UAVObjectField("YawDesired", "deg", UAVObjectField.FieldType.FLOAT32, YawDesiredElemNames, null) ); + + List ActionElemNames = new ArrayList(); + ActionElemNames.add("0"); + List ActionEnumOptions = new ArrayList(); + ActionEnumOptions.add("PathToNext"); + ActionEnumOptions.add("EndpointToNext"); + ActionEnumOptions.add("Land"); + ActionEnumOptions.add("Stop"); + fields.add( new UAVObjectField("Action", "", UAVObjectField.FieldType.ENUM, ActionElemNames, ActionEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 4000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Waypoint obj = new Waypoint(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Waypoint GetInstance(UAVObjectManager objMngr, int instID) + { + return (Waypoint)(objMngr.getObject(Waypoint.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x338C5F90; + protected static final String NAME = "Waypoint"; + protected static String DESCRIPTION = "A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module"; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java new file mode 100644 index 000000000..06f3ab6c4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java @@ -0,0 +1,138 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Indicates the currently active waypoint + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Indicates the currently active waypoint + +generated from waypointactive.xml + **/ +public class WaypointActive extends UAVDataObject { + + public WaypointActive() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List IndexElemNames = new ArrayList(); + IndexElemNames.add("0"); + fields.add( new UAVObjectField("Index", "", UAVObjectField.FieldType.UINT8, IndexElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WaypointActive obj = new WaypointActive(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WaypointActive GetInstance(UAVObjectManager objMngr, int instID) + { + return (WaypointActive)(objMngr.getObject(WaypointActive.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1EA5B192; + protected static final String NAME = "WaypointActive"; + protected static String DESCRIPTION = "Indicates the currently active waypoint"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From 45f4ae0701b28581798c4020ee66bb542643bca2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 02:14:12 -0500 Subject: [PATCH 102/165] Allow selecting the IP address from the preferences --- androidgcs/res/xml/preferences.xml | 2 +- .../src/org/openpilot/androidgcs/TcpUAVTalk.java | 13 +++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 24fd43b5e..285e7b6d7 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -10,6 +10,6 @@ + android:key="ip_address" />
diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index 47074f968..f5d40040b 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -8,6 +8,8 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import android.content.Context; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; public class TcpUAVTalk { @@ -17,14 +19,17 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "10.21.18.120"; + private String ip_address = "1"; public final static int PORT = 9001; private UAVTalk uavTalk; private boolean connected; public TcpUAVTalk(Context caller) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + ip_address = prefs.getString("ip_address","127.0.0.1"); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -47,11 +52,11 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); InetAddress serverAddr = null; try { - serverAddr = InetAddress.getByName(IP_ADDRESS); + serverAddr = InetAddress.getByName(ip_address); } catch (UnknownHostException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From 20b585383d4db87bae20b123676e7cd2a3e27791 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 03:18:26 -0500 Subject: [PATCH 103/165] Make port and bluetooth adapter be listed in the preferences. Using the BT adapter not working yet. --- androidgcs/res/xml/preferences.xml | 8 ++++++++ .../openpilot/androidgcs/BluetoothUAVTalk.java | 17 ++++++++++++----- .../androidgcs/OPTelemetryService.java | 2 +- .../org/openpilot/androidgcs/TcpUAVTalk.java | 12 ++++++++---- 4 files changed, 29 insertions(+), 10 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 285e7b6d7..3a9103b49 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -11,5 +11,13 @@ android:summary="Enter a TCP/IP address here" android:defaultValue="192.168.0.1" android:title="IP address:" android:key="ip_address" /> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java index b240f3adc..c00db0bea 100644 --- a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -7,6 +7,7 @@ import java.util.UUID; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; +import android.annotation.TargetApi; import android.app.Activity; import android.bluetooth.BluetoothAdapter; import android.bluetooth.BluetoothDevice; @@ -14,16 +15,18 @@ import android.bluetooth.BluetoothSocket; import android.content.BroadcastReceiver; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; -public class BluetoothUAVTalk { +@TargetApi(10) public class BluetoothUAVTalk { private final String TAG = "BluetoothUAVTalk"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String DEVICE_NAME = "RN42-222D"; + private String device_name = "RN42-222D"; private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); private BluetoothAdapter mBluetoothAdapter; @@ -32,8 +35,12 @@ public class BluetoothUAVTalk { private UAVTalk uavTalk; private boolean connected; - public BluetoothUAVTalk(Context caller, String deviceName) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + public BluetoothUAVTalk(Context caller) { + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + device_name = prefs.getString("bluetooth_mac",""); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + device_name); connected = false; device = null; @@ -93,7 +100,7 @@ public class BluetoothUAVTalk { // Add the name and address to an array adapter to show in a ListView //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { + if(device.getName().compareTo(device_name) == 0) { this.device = device; return; } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 917dfb116..13e415c54 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -277,7 +277,7 @@ public class OPTelemetryService extends Service { Looper.prepare(); - BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index f5d40040b..1f647bd99 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -20,7 +20,7 @@ public class TcpUAVTalk { // Temporarily define fixed device name private String ip_address = "1"; - public final static int PORT = 9001; + private int port = 9001; private UAVTalk uavTalk; private boolean connected; @@ -28,8 +28,12 @@ public class TcpUAVTalk { public TcpUAVTalk(Context caller) { SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); ip_address = prefs.getString("ip_address","127.0.0.1"); + try { + port = Integer.decode(prefs.getString("port", "")); + } catch (NumberFormatException e) { + } - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -52,7 +56,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + port); InetAddress serverAddr = null; try { @@ -65,7 +69,7 @@ public class TcpUAVTalk { Socket socket = null; try { - socket = new Socket(serverAddr,PORT); + socket = new Socket(serverAddr,port); } catch (IOException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From a44e84ff9bfad12d35592c155e0e24eb64f5dceb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:25 -0500 Subject: [PATCH 104/165] Update the sdk version --- androidgcs/AndroidManifest.xml | 2 +- androidgcs/project.properties | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index c18dc0cb1..40b08c328 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,7 +2,7 @@ - + diff --git a/androidgcs/project.properties b/androidgcs/project.properties index 5d85d779c..a43ea8cdc 100644 --- a/androidgcs/project.properties +++ b/androidgcs/project.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:13 +target=Google Inc.:Google APIs:16 From bf9343532241536197d93031cff7d38af18d93bd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:54 -0500 Subject: [PATCH 105/165] Check in a joystick gadget class --- .../Android/Widgets/DockPanel/DockPanel.java | 319 +++++++++++ .../Widgets/DockPanel/DockPosition.java | 5 + .../DragAndDrop/DragAndDropManager.java | 124 +++++ .../Widgets/DragAndDrop/DragSurface.java | 94 ++++ .../Widgets/DragAndDrop/DraggableItem.java | 44 ++ .../DragAndDrop/DraggableViewsFactory.java | 19 + .../Android/Widgets/DragAndDrop/DropZone.java | 67 +++ .../DragAndDrop/DropZoneEventsListener.java | 9 + .../Widgets/Joystick/DualJoystickView.java | 147 +++++ .../Joystick/JoystickClickedListener.java | 6 + .../Joystick/JoystickMovedListener.java | 7 + .../Widgets/Joystick/JoystickView.java | 521 ++++++++++++++++++ .../ThresholdEditText/ThresholdEditText.java | 169 ++++++ .../ThresholdTextChanged.java | 7 + .../Widgets/TilesLayout/SingleTileLayout.java | 68 +++ .../Widgets/TilesLayout/TilePosition.java | 63 +++ .../Widgets/TilesLayout/TilesLayout.java | 299 ++++++++++ .../TilesLayout/TilesLayoutPreset.java | 157 ++++++ 18 files changed, 2125 insertions(+) create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java new file mode 100644 index 000000000..e2397394e --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java @@ -0,0 +1,319 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +import android.content.Context; +import android.graphics.Color; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.LayoutInflater; +import android.view.View; +import android.view.animation.AccelerateInterpolator; +import android.view.animation.Animation; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; +import android.widget.ImageButton; +import android.widget.LinearLayout; + +public class DockPanel extends LinearLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "DockPanel"; + private DockPosition position; + private int contentLayoutId; + private int handleButtonDrawableId; + private Boolean isOpen; + private Boolean animationRunning; + private FrameLayout contentPlaceHolder; + private ImageButton toggleButton; + private int animationDuration; + + // ========================================= + // Constructors + // ========================================= + + public DockPanel(Context context, int contentLayoutId, + int handleButtonDrawableId, Boolean isOpen) { + super(context); + + this.contentLayoutId = contentLayoutId; + this.handleButtonDrawableId = handleButtonDrawableId; + this.isOpen = isOpen; + + Init(null); + } + + public DockPanel(Context context, AttributeSet attrs) { + super(context, attrs); + + // to prevent from crashing the designer + try { + Init(attrs); + } catch (Exception ex) { + } + } + + // ========================================= + // Initialization + // ========================================= + + private void Init(AttributeSet attrs) { + setDefaultValues(attrs); + + createHandleToggleButton(); + + // create the handle container + FrameLayout handleContainer = new FrameLayout(getContext()); + handleContainer.addView(toggleButton); + + // create and populate the panel's container, and inflate it + contentPlaceHolder = new FrameLayout(getContext()); + String infService = Context.LAYOUT_INFLATER_SERVICE; + LayoutInflater li = (LayoutInflater) getContext().getSystemService( + infService); + li.inflate(contentLayoutId, contentPlaceHolder, true); + + // setting the layout of the panel parameters according to the docking + // position + if (position == DockPosition.LEFT || position == DockPosition.RIGHT) { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + } else { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + } + + // adding the view to the parent layout according to docking position + if (position == DockPosition.RIGHT || position == DockPosition.BOTTOM) { + this.addView(handleContainer); + this.addView(contentPlaceHolder); + } else { + this.addView(contentPlaceHolder); + this.addView(handleContainer); + } + + if (!isOpen) { + contentPlaceHolder.setVisibility(GONE); + } + } + + private void setDefaultValues(AttributeSet attrs) { + // set default values + isOpen = true; + animationRunning = false; + animationDuration = 500; + setPosition(DockPosition.RIGHT); + + // Try to load values set by xml markup + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + animationDuration = attrs.getAttributeIntValue(namespace, + "animationDuration", 500); + contentLayoutId = attrs.getAttributeResourceValue(namespace, + "contentLayoutId", 0); + handleButtonDrawableId = attrs.getAttributeResourceValue( + namespace, "handleButtonDrawableResourceId", 0); + isOpen = attrs.getAttributeBooleanValue(namespace, "isOpen", true); + + // Enums are a bit trickier (needs to be parsed) + try { + position = DockPosition.valueOf(attrs.getAttributeValue( + namespace, "dockPosition").toUpperCase()); + setPosition(position); + } catch (Exception ex) { + // Docking to the left is the default behavior + setPosition(DockPosition.LEFT); + } + } + } + + private void createHandleToggleButton() { + toggleButton = new ImageButton(getContext()); + toggleButton.setPadding(0, 0, 0, 0); + toggleButton.setLayoutParams(new FrameLayout.LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + Gravity.CENTER)); + toggleButton.setBackgroundColor(Color.TRANSPARENT); + toggleButton.setImageResource(handleButtonDrawableId); + toggleButton.setOnClickListener(new OnClickListener() { + @Override + public void onClick(View v) { + toggle(); + } + }); + } + + private void setPosition(DockPosition position) { + this.position = position; + switch (position) { + case TOP: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.TOP); + break; + case RIGHT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.RIGHT); + break; + case BOTTOM: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.BOTTOM); + break; + case LEFT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.LEFT); + break; + } + } + + // ========================================= + // Public methods + // ========================================= + + public int getAnimationDuration() { + return animationDuration; + } + + public void setAnimationDuration(int milliseconds) { + animationDuration = milliseconds; + } + + public Boolean getIsRunning() { + return animationRunning; + } + + public void open() { + if (!animationRunning) { + Log.d(TAG, "Opening..."); + + Animation animation = createShowAnimation(); + this.setAnimation(animation); + animation.start(); + + isOpen = true; + } + } + + public void close() { + if (!animationRunning) { + Log.d(TAG, "Closing..."); + + Animation animation = createHideAnimation(); + this.setAnimation(animation); + animation.start(); + isOpen = false; + } + } + + public void toggle() { + if (isOpen) { + close(); + } else { + open(); + } + } + + // ========================================= + // Private methods + // ========================================= + + private Animation createHideAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, 0, -contentPlaceHolder + .getHeight()); + break; + case RIGHT: + animation = new TranslateAnimation(0, contentPlaceHolder + .getWidth(), 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, 0, contentPlaceHolder + .getHeight()); + break; + case LEFT: + animation = new TranslateAnimation(0, -contentPlaceHolder + .getWidth(), 0, 0); + break; + } + + animation.setDuration(animationDuration); + animation.setInterpolator(new AccelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + contentPlaceHolder.setVisibility(View.GONE); + animationRunning = false; + } + }); + return animation; + } + + private Animation createShowAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, -contentPlaceHolder + .getHeight(), 0); + break; + case RIGHT: + animation = new TranslateAnimation(contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, contentPlaceHolder + .getHeight(), 0); + break; + case LEFT: + animation = new TranslateAnimation(-contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + } + Log.d(TAG, "Animation duration: " + animationDuration); + animation.setDuration(animationDuration); + animation.setInterpolator(new DecelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + contentPlaceHolder.setVisibility(View.VISIBLE); + Log.d(TAG, "\"Show\" Animation started"); + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + animationRunning = false; + Log.d(TAG, "\"Show\" Animation ended"); + } + }); + return animation; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java new file mode 100644 index 000000000..59643dfc6 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java @@ -0,0 +1,5 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +public enum DockPosition { + TOP, BOTTOM, LEFT, RIGHT +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java new file mode 100644 index 000000000..d7e0c5e44 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java @@ -0,0 +1,124 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import java.util.ArrayList; + +import android.content.Context; +import android.view.MotionEvent; +import android.view.View; +import android.view.View.OnTouchListener; + +public class DragAndDropManager { + + // ========================================= + // Private members + // ========================================= + + protected static final String TAG = "DragAndDropManager"; + private static DragAndDropManager instance = null; + private ArrayList dropZones; + private OnTouchListener originalTouchListener; + private DragSurface dragSurface; + private DraggableItem draggedItem; + private DropZone activeDropZone; + + // ========================================= + // Protected Constructor + // ========================================= + + protected DragAndDropManager() { + // Exists only to defeat instantiation. + dropZones = new ArrayList(); + } + + // ========================================= + // Public Properties + // ========================================= + + public static DragAndDropManager getInstance() { + if (instance == null) { + instance = new DragAndDropManager(); + } + return instance; + } + + public Context getContext() { + if (dragSurface == null) + return null; + + return dragSurface.getContext(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void init(DragSurface surface) { + dragSurface = surface; + clearDropZones(); + } + + public void clearDropZones() { + dropZones.clear(); + } + + public void addDropZone(DropZone dropZone) { + dropZones.add(dropZone); + } + + + public void startDragging(OnTouchListener originalListener, DraggableItem draggedItem) { + originalTouchListener = originalListener; + this.draggedItem = draggedItem; + draggedItem.getSource().setOnTouchListener(new OnTouchListener() { + + @Override + public boolean onTouch(View v, MotionEvent event) { + int[] location = new int[2]; + v.getLocationOnScreen(location); + event.offsetLocation(location[0], location[1]); + invalidateDropZones((int)event.getX(), (int)event.getY()); + return dragSurface.onTouchEvent(event); + } + }); + + dragSurface.startDragging(draggedItem); + } + + + // ========================================= + // Protected Methods + // ========================================= + + protected void invalidateDropZones(int x, int y) { + if (activeDropZone != null) { + if (!activeDropZone.isOver(x, y)) { + activeDropZone.getListener().OnDragZoneLeft(activeDropZone, draggedItem); + activeDropZone = null; + } + else { + // we are still over the same drop zone, no need to check other drop zones + return; + } + } + + for (DropZone dropZone : dropZones) { + if (dropZone.isOver(x, y)) { + activeDropZone = dropZone; + dropZone.getListener().OnDragZoneEntered(activeDropZone, draggedItem); + break; + } + } + } + + protected void stoppedDragging() { + if (activeDropZone != null) { + activeDropZone.getListener().OnDropped(activeDropZone, draggedItem); + } + + // Registering the "old" listener to the view that initiated this drag session + draggedItem.getSource().setOnTouchListener(originalTouchListener); + draggedItem = null; + activeDropZone = null; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java new file mode 100644 index 000000000..aebb9d481 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java @@ -0,0 +1,94 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.Gravity; +import android.view.MotionEvent; +import android.widget.FrameLayout; + +public class DragSurface extends FrameLayout { + + private float draggedViewHalfHeight; + private float draggedViewHalfWidth; + private int framesCount; + + private Boolean isDragging; + private DraggableItem draggedItem; + + public DragSurface(Context context, AttributeSet attrs) { + super(context, attrs); + isDragging = false; + } + + // ========================================= + // Touch Events Listener + // ========================================= + + @Override + public boolean onTouchEvent(MotionEvent event) { + if (isDragging && event.getAction() == MotionEvent.ACTION_UP) { + // Dragging ended + removeAllViews(); + isDragging = false; + + DragAndDropManager.getInstance().stoppedDragging(); + } + + if (isDragging && event.getAction() == MotionEvent.ACTION_MOVE) { + // Move the dragged view to it's new position + repositionView(event.getX(), event.getY()); + + // Mark this event as handled (so that other UI elements will not intercept it) + return true; + } + + return false; + } + + public void startDragging(DraggableItem draggableItem) { + this.draggedItem = draggableItem; + this.draggedItem.getDraggedView().setVisibility(INVISIBLE); + isDragging = true; + addView(this.draggedItem.getDraggedView()); + //repositionView(x, y); + framesCount = 0; + } + + private void repositionView(float x, float y) { + draggedViewHalfHeight = draggedItem.getDraggedView().getHeight() / 2f; + draggedViewHalfWidth = draggedItem.getDraggedView().getWidth() / 2f; + + // If the dragged view was not drawn yet, skip this phase + if (draggedViewHalfHeight == 0 || draggedViewHalfWidth == 0) + return; + + framesCount++; + + //Log.d(TAG, "Original = (x=" + x + ", y=" + y + ")"); + //Log.d(TAG, "Size (W=" + draggedViewHalfWidth + ", H=" + draggedViewHalfHeight + ")"); + + x = x - draggedViewHalfWidth; + y = y - draggedViewHalfHeight; + + x = Math.max(x, 0); + x = Math.min(x, getWidth() - draggedViewHalfWidth * 2); + + y = Math.max(y, 0); + y = Math.min(y, getHeight() - draggedViewHalfHeight * 2); + + //Log.d(TAG, "Moving view to (x=" + x + ", y=" + y + ")"); + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams(LayoutParams.WRAP_CONTENT, + LayoutParams.WRAP_CONTENT, Gravity.TOP + Gravity.LEFT); + + lp.setMargins((int)x, (int)y, 0, 0); + draggedItem.getDraggedView().setLayoutParams(lp); + + // hte first couple of dragged frame's positions are not calculated correctly, + // so we have a threshold before making the dragged view visible again + if (framesCount < 2) + return; + + draggedItem.getDraggedView().setVisibility(VISIBLE); + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java new file mode 100644 index 000000000..d0c8b7e25 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java @@ -0,0 +1,44 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DraggableItem { + + // ========================================= + // Private members + // ========================================= + + private View source; + private View draggedView; + private Object tag; + + // ========================================= + // Constructor + // ========================================= + + public DraggableItem(View source, View draggedItem) { + this.source = source; + this.draggedView = draggedItem; + } + + // ========================================= + // Public properties + // ========================================= + + public Object getTag() { + return tag; + } + + public void setTag(Object tag) { + this.tag = tag; + } + + public View getSource() { + return source; + } + + public View getDraggedView() { + return draggedView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java new file mode 100644 index 000000000..246b2392f --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java @@ -0,0 +1,19 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.view.View; +import android.widget.TextView; +import android.widget.TableLayout.LayoutParams; + +public class DraggableViewsFactory { + + public static View getLabel(String text) { + Context context = DragAndDropManager.getInstance().getContext(); + TextView textView = new TextView(context); + textView.setText(text); + textView.setLayoutParams(new LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + //textView.setGravity(Gravity.TOP + Gravity.LEFT); + return textView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java new file mode 100644 index 000000000..06a8caa17 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java @@ -0,0 +1,67 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DropZone { + + // ========================================= + // Private members + // ========================================= + + private View view; + private DropZoneEventsListener listener; + private int left, top, width, height; + private Boolean dimansionsCalculated; + + // ========================================= + // Constructor + // ========================================= + + public DropZone(View view, DropZoneEventsListener listener) { + this.view = view; + this.listener = listener; + dimansionsCalculated = false; + } + + // ========================================= + // Public properties + // ========================================= + + public View getView() { + return view; + } + + // ========================================= + // Public methods + // ========================================= + + public Boolean isOver(int x, int y) { + if (!dimansionsCalculated) + calculateDimensions(); + + Boolean isOver = (x >= left && x <= (left + width)) && + (y >= top && y <= (top + height)); + + //Log.d("DragZone", "x=" +x + ", left=" + left + ", y=" + y + ", top=" + top + " width=" + width + ", height=" + height + ", isover=" + isOver); + + return isOver; + } + + // ========================================= + // Protected & Private methods + // ========================================= + + protected DropZoneEventsListener getListener() { + return listener; + } + + private void calculateDimensions() { + int[] location = new int[2]; + view.getLocationOnScreen(location); + left = location[0]; + top = location[1]; + width = view.getWidth(); + height = view.getHeight(); + dimansionsCalculated = true; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java new file mode 100644 index 000000000..828a1cbf2 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java @@ -0,0 +1,9 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +public interface DropZoneEventsListener { + + void OnDragZoneEntered(DropZone zone, DraggableItem item); + void OnDragZoneLeft(DropZone zone, DraggableItem item); + void OnDropped(DropZone zone, DraggableItem item); + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java new file mode 100644 index 000000000..bb419d404 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java @@ -0,0 +1,147 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.MotionEvent; +import android.view.View; +import android.view.ViewGroup; +import android.widget.LinearLayout; + +public class DualJoystickView extends LinearLayout { + @SuppressWarnings("unused") + private static final String TAG = DualJoystickView.class.getSimpleName(); + + private final boolean D = false; + private Paint dbgPaint1; + + private JoystickView stickL; + private JoystickView stickR; + + private View pad; + + public DualJoystickView(Context context) { + super(context); + stickL = new JoystickView(context); + stickR = new JoystickView(context); + initDualJoystickView(); + } + + public DualJoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + stickL = new JoystickView(context, attrs); + stickR = new JoystickView(context, attrs); + initDualJoystickView(); + } + + private void initDualJoystickView() { + setOrientation(LinearLayout.HORIZONTAL); + + if ( D ) { + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.CYAN); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + } + + pad = new View(getContext()); + } + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + super.onMeasure(widthMeasureSpec, heightMeasureSpec); + removeView(stickL); + removeView(stickR); + + float padW = getMeasuredWidth()-(getMeasuredHeight()*2); + int joyWidth = (int) ((getMeasuredWidth()-padW)/2); + LayoutParams joyLParams = new LayoutParams(joyWidth,getMeasuredHeight()); + + stickL.setLayoutParams(joyLParams); + stickR.setLayoutParams(joyLParams); + + stickL.TAG = "L"; + stickR.TAG = "R"; + stickL.setPointerId(JoystickView.INVALID_POINTER_ID); + stickR.setPointerId(JoystickView.INVALID_POINTER_ID); + + addView(stickL); + + ViewGroup.LayoutParams padLParams = new ViewGroup.LayoutParams((int) padW,getMeasuredHeight()); + removeView(pad); + pad.setLayoutParams(padLParams); + addView(pad); + + addView(stickR); + } + + @Override + protected void onLayout(boolean changed, int l, int t, int r, int b) { + super.onLayout(changed, l, t, r, b); + stickR.setTouchOffset(stickR.getLeft(), stickR.getTop()); + } + + public void setAutoReturnToCenter(boolean left, boolean right) { + stickL.setAutoReturnToCenter(left); + stickR.setAutoReturnToCenter(right); + } + + public void setOnJostickMovedListener(JoystickMovedListener left, JoystickMovedListener right) { + stickL.setOnJostickMovedListener(left); + stickR.setOnJostickMovedListener(right); + } + + public void setOnJostickClickedListener(JoystickClickedListener left, JoystickClickedListener right) { + stickL.setOnJostickClickedListener(left); + stickR.setOnJostickClickedListener(right); + } + + public void setYAxisInverted(boolean leftYAxisInverted, boolean rightYAxisInverted) { + stickL.setYAxisInverted(leftYAxisInverted); + stickL.setYAxisInverted(rightYAxisInverted); + } + + public void setMovementConstraint(int movementConstraint) { + stickL.setMovementConstraint(movementConstraint); + stickR.setMovementConstraint(movementConstraint); + } + + public void setMovementRange(float movementRangeLeft, float movementRangeRight) { + stickL.setMovementRange(movementRangeLeft); + stickR.setMovementRange(movementRangeRight); + } + + public void setMoveResolution(float leftMoveResolution, float rightMoveResolution) { + stickL.setMoveResolution(leftMoveResolution); + stickR.setMoveResolution(rightMoveResolution); + } + + public void setUserCoordinateSystem(int leftCoordinateSystem, int rightCoordinateSystem) { + stickL.setUserCoordinateSystem(leftCoordinateSystem); + stickR.setUserCoordinateSystem(rightCoordinateSystem); + } + + @Override + protected void dispatchDraw(Canvas canvas) { + super.dispatchDraw(canvas); + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + } + } + + @Override + public boolean dispatchTouchEvent(MotionEvent ev) { + boolean l = stickL.dispatchTouchEvent(ev); + boolean r = stickR.dispatchTouchEvent(ev); + return l || r; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + boolean l = stickL.onTouchEvent(ev); + boolean r = stickR.onTouchEvent(ev); + return l || r; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java new file mode 100644 index 000000000..128828980 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java @@ -0,0 +1,6 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickClickedListener { + public void OnClicked(); + public void OnReleased(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java new file mode 100644 index 000000000..346f2efed --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickMovedListener { + public void OnMoved(int pan, int tilt); + public void OnReleased(); + public void OnReturnedToCenter(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java new file mode 100644 index 000000000..bab74e5a7 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java @@ -0,0 +1,521 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.HapticFeedbackConstants; +import android.view.MotionEvent; +import android.view.View; + +public class JoystickView extends View { + public static final int INVALID_POINTER_ID = -1; + + // ========================================= + // Private Members + // ========================================= + private final boolean D = false; + String TAG = "JoystickView"; + + private Paint dbgPaint1; + private Paint dbgPaint2; + + private Paint bgPaint; + private Paint handlePaint; + + private int innerPadding; + private int bgRadius; + private int handleRadius; + private int movementRadius; + private int handleInnerBoundaries; + + private JoystickMovedListener moveListener; + private JoystickClickedListener clickListener; + + //# of pixels movement required between reporting to the listener + private float moveResolution; + + private boolean yAxisInverted; + private boolean autoReturnToCenter; + + //Max range of movement in user coordinate system + public final static int CONSTRAIN_BOX = 0; + public final static int CONSTRAIN_CIRCLE = 1; + private int movementConstraint; + private float movementRange; + + public final static int COORDINATE_CARTESIAN = 0; //Regular cartesian coordinates + public final static int COORDINATE_DIFFERENTIAL = 1; //Uses polar rotation of 45 degrees to calc differential drive paramaters + private int userCoordinateSystem; + + //Records touch pressure for click handling + private float touchPressure; + private boolean clicked; + private float clickThreshold; + + //Last touch point in view coordinates + private int pointerId = INVALID_POINTER_ID; + private float touchX, touchY; + + //Last reported position in view coordinates (allows different reporting sensitivities) + private float reportX, reportY; + + //Handle center in view coordinates + private float handleX, handleY; + + //Center of the view in view coordinates + private int cX, cY; + + //Size of the view in view coordinates + private int dimX, dimY; + + //Cartesian coordinates of last touch point - joystick center is (0,0) + private int cartX, cartY; + + //Polar coordinates of the touch point from joystick center + private double radial; + private double angle; + + //User coordinates of last touch point + private int userX, userY; + + //Offset co-ordinates (used when touch events are received from parent's coordinate origin) + private int offsetX; + private int offsetY; + + // ========================================= + // Constructors + // ========================================= + + public JoystickView(Context context) { + super(context); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs, int defStyle) { + super(context, attrs, defStyle); + initJoystickView(); + } + + // ========================================= + // Initialization + // ========================================= + + private void initJoystickView() { + setFocusable(true); + + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.RED); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + + dbgPaint2 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint2.setColor(Color.GREEN); + dbgPaint2.setStrokeWidth(1); + dbgPaint2.setStyle(Paint.Style.STROKE); + + bgPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + bgPaint.setColor(Color.GRAY); + bgPaint.setStrokeWidth(1); + bgPaint.setStyle(Paint.Style.FILL_AND_STROKE); + + handlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + handlePaint.setColor(Color.DKGRAY); + handlePaint.setStrokeWidth(1); + handlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + + innerPadding = 10; + + setMovementRange(10); + setMoveResolution(1.0f); + setClickThreshold(0.4f); + setYAxisInverted(true); + setUserCoordinateSystem(COORDINATE_CARTESIAN); + setAutoReturnToCenter(true); + } + + public void setAutoReturnToCenter(boolean autoReturnToCenter) { + this.autoReturnToCenter = autoReturnToCenter; + } + + public boolean isAutoReturnToCenter() { + return autoReturnToCenter; + } + + public void setUserCoordinateSystem(int userCoordinateSystem) { + if (userCoordinateSystem < COORDINATE_CARTESIAN || movementConstraint > COORDINATE_DIFFERENTIAL) + Log.e(TAG, "invalid value for userCoordinateSystem"); + else + this.userCoordinateSystem = userCoordinateSystem; + } + + public int getUserCoordinateSystem() { + return userCoordinateSystem; + } + + public void setMovementConstraint(int movementConstraint) { + if (movementConstraint < CONSTRAIN_BOX || movementConstraint > CONSTRAIN_CIRCLE) + Log.e(TAG, "invalid value for movementConstraint"); + else + this.movementConstraint = movementConstraint; + } + + public int getMovementConstraint() { + return movementConstraint; + } + + public boolean isYAxisInverted() { + return yAxisInverted; + } + + public void setYAxisInverted(boolean yAxisInverted) { + this.yAxisInverted = yAxisInverted; + } + + /** + * Set the pressure sensitivity for registering a click + * @param clickThreshold threshold 0...1.0f inclusive. 0 will cause clicks to never be reported, 1.0 is a very hard click + */ + public void setClickThreshold(float clickThreshold) { + if (clickThreshold < 0 || clickThreshold > 1.0f) + Log.e(TAG, "clickThreshold must range from 0...1.0f inclusive"); + else + this.clickThreshold = clickThreshold; + } + + public float getClickThreshold() { + return clickThreshold; + } + + public void setMovementRange(float movementRange) { + this.movementRange = movementRange; + } + + public float getMovementRange() { + return movementRange; + } + + public void setMoveResolution(float moveResolution) { + this.moveResolution = moveResolution; + } + + public float getMoveResolution() { + return moveResolution; + } + + // ========================================= + // Public Methods + // ========================================= + + public void setOnJostickMovedListener(JoystickMovedListener listener) { + this.moveListener = listener; + } + + public void setOnJostickClickedListener(JoystickClickedListener listener) { + this.clickListener = listener; + } + + // ========================================= + // Drawing Functionality + // ========================================= + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + // Here we make sure that we have a perfect circle + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + setMeasuredDimension(measuredWidth, measuredHeight); + } + + @Override + protected void onLayout(boolean changed, int left, int top, int right, int bottom) { + super.onLayout(changed, left, top, right, bottom); + + int d = Math.min(getMeasuredWidth(), getMeasuredHeight()); + + dimX = d; + dimY = d; + + cX = d / 2; + cY = d / 2; + + bgRadius = dimX/2 - innerPadding; + handleRadius = (int)(d * 0.25); + handleInnerBoundaries = handleRadius; + movementRadius = Math.min(cX, cY) - handleInnerBoundaries; + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + if (specMode == MeasureSpec.UNSPECIFIED) { + // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + @Override + protected void onDraw(Canvas canvas) { + canvas.save(); + // Draw the background + canvas.drawCircle(cX, cY, bgRadius, bgPaint); + + // Draw the handle + handleX = touchX + cX; + handleY = touchY + cY; + canvas.drawCircle(handleX, handleY, handleRadius, handlePaint); + + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + + canvas.drawCircle(handleX, handleY, 3, dbgPaint1); + + if ( movementConstraint == CONSTRAIN_CIRCLE ) { + canvas.drawCircle(cX, cY, this.movementRadius, dbgPaint1); + } + else { + canvas.drawRect(cX-movementRadius, cY-movementRadius, cX+movementRadius, cY+movementRadius, dbgPaint1); + } + + //Origin to touch point + canvas.drawLine(cX, cY, handleX, handleY, dbgPaint2); + + int baseY = (int) (touchY < 0 ? cY + handleRadius : cY - handleRadius); + canvas.drawText(String.format("%s (%.0f,%.0f)", TAG, touchX, touchY), handleX-20, baseY-7, dbgPaint2); + canvas.drawText("("+ String.format("%.0f, %.1f", radial, angle * 57.2957795) + (char) 0x00B0 + ")", handleX-20, baseY+15, dbgPaint2); + } + +// Log.d(TAG, String.format("touch(%f,%f)", touchX, touchY)); +// Log.d(TAG, String.format("onDraw(%.1f,%.1f)\n\n", handleX, handleY)); + canvas.restore(); + } + + // Constrain touch within a box + private void constrainBox() { + touchX = Math.max(Math.min(touchX, movementRadius), -movementRadius); + touchY = Math.max(Math.min(touchY, movementRadius), -movementRadius); + } + + // Constrain touch within a circle + private void constrainCircle() { + float diffX = touchX; + float diffY = touchY; + double radial = Math.sqrt((diffX*diffX) + (diffY*diffY)); + if ( radial > movementRadius ) { + touchX = (int)((diffX / radial) * movementRadius); + touchY = (int)((diffY / radial) * movementRadius); + } + } + + public void setPointerId(int id) { + this.pointerId = id; + } + + public int getPointerId() { + return pointerId; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + final int action = ev.getAction(); + switch (action & MotionEvent.ACTION_MASK) { + case MotionEvent.ACTION_MOVE: { + return processMoveEvent(ev); + } + case MotionEvent.ACTION_CANCEL: + case MotionEvent.ACTION_UP: { + if ( pointerId != INVALID_POINTER_ID ) { +// Log.d(TAG, "ACTION_UP"); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + } + break; + } + case MotionEvent.ACTION_POINTER_UP: { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + if ( pointerId == this.pointerId ) { +// Log.d(TAG, "ACTION_POINTER_UP: " + pointerId); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + return true; + } + } + break; + } + case MotionEvent.ACTION_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + int x = (int) ev.getX(); + if ( x >= offsetX && x < offsetX + dimX ) { + setPointerId(ev.getPointerId(0)); +// Log.d(TAG, "ACTION_DOWN: " + getPointerId()); + return true; + } + } + break; + } + case MotionEvent.ACTION_POINTER_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + int x = (int) ev.getX(pointerId); + if ( x >= offsetX && x < offsetX + dimX ) { +// Log.d(TAG, "ACTION_POINTER_DOWN: " + pointerId); + setPointerId(pointerId); + return true; + } + } + break; + } + } + return false; + } + + private boolean processMoveEvent(MotionEvent ev) { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = ev.findPointerIndex(pointerId); + + // Translate touch position to center of view + float x = ev.getX(pointerIndex); + touchX = x - cX - offsetX; + float y = ev.getY(pointerIndex); + touchY = y - cY - offsetY; + +// Log.d(TAG, String.format("ACTION_MOVE: (%03.0f, %03.0f) => (%03.0f, %03.0f)", x, y, touchX, touchY)); + + reportOnMoved(); + invalidate(); + + touchPressure = ev.getPressure(pointerIndex); + reportOnPressure(); + + return true; + } + return false; + } + + private void reportOnMoved() { + if ( movementConstraint == CONSTRAIN_CIRCLE ) + constrainCircle(); + else + constrainBox(); + + calcUserCoordinates(); + + if (moveListener != null) { + boolean rx = Math.abs(touchX - reportX) >= moveResolution; + boolean ry = Math.abs(touchY - reportY) >= moveResolution; + if (rx || ry) { + this.reportX = touchX; + this.reportY = touchY; + +// Log.d(TAG, String.format("moveListener.OnMoved(%d,%d)", (int)userX, (int)userY)); + moveListener.OnMoved(userX, userY); + } + } + } + + private void calcUserCoordinates() { + //First convert to cartesian coordinates + cartX = (int)(touchX / movementRadius * movementRange); + cartY = (int)(touchY / movementRadius * movementRange); + + radial = Math.sqrt((cartX*cartX) + (cartY*cartY)); + angle = Math.atan2(cartY, cartX); + + //Invert Y axis if requested + if ( !yAxisInverted ) + cartY *= -1; + + if ( userCoordinateSystem == COORDINATE_CARTESIAN ) { + userX = cartX; + userY = cartY; + } + else if ( userCoordinateSystem == COORDINATE_DIFFERENTIAL ) { + userX = cartY + cartX / 4; + userY = cartY - cartX / 4; + + if ( userX < -movementRange ) + userX = (int)-movementRange; + if ( userX > movementRange ) + userX = (int)movementRange; + + if ( userY < -movementRange ) + userY = (int)-movementRange; + if ( userY > movementRange ) + userY = (int)movementRange; + } + + } + + //Simple pressure click + private void reportOnPressure() { +// Log.d(TAG, String.format("touchPressure=%.2f", this.touchPressure)); + if ( clickListener != null ) { + if ( clicked && touchPressure < clickThreshold ) { + clickListener.OnReleased(); + this.clicked = false; +// Log.d(TAG, "reset click"); + invalidate(); + } + else if ( !clicked && touchPressure >= clickThreshold ) { + clicked = true; + clickListener.OnClicked(); +// Log.d(TAG, "click"); + invalidate(); + performHapticFeedback(HapticFeedbackConstants.VIRTUAL_KEY); + } + } + } + + private void returnHandleToCenter() { + if ( autoReturnToCenter ) { + final int numberOfFrames = 5; + final double intervalsX = (0 - touchX) / numberOfFrames; + final double intervalsY = (0 - touchY) / numberOfFrames; + + for (int i = 0; i < numberOfFrames; i++) { + final int j = i; + postDelayed(new Runnable() { + @Override + public void run() { + touchX += intervalsX; + touchY += intervalsY; + + reportOnMoved(); + invalidate(); + + if (moveListener != null && j == numberOfFrames - 1) { + moveListener.OnReturnedToCenter(); + } + } + }, i * 40); + } + + if (moveListener != null) { + moveListener.OnReleased(); + } + } + } + + public void setTouchOffset(int x, int y) { + offsetX = x; + offsetY = y; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java new file mode 100644 index 000000000..5fbd76f46 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java @@ -0,0 +1,169 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.content.Context; +import android.os.Handler; +import android.text.Editable; +import android.text.TextWatcher; +import android.util.AttributeSet; +import android.widget.EditText; + +public class ThresholdEditText extends EditText { + + // ========================================= + // Private members + // ========================================= + + private int threshold; + private ThresholdTextChanged thresholdTextChanged; + private Handler handler; + private Runnable invoker; + private boolean thresholdDisabledOnEmptyInput; + + + // ========================================= + // Constructors + // ========================================= + + public ThresholdEditText(Context context) { + super(context); + initAttributes(null); + init(); + } + + public ThresholdEditText(Context context, AttributeSet attrs) { + super(context, attrs); + initAttributes(attrs); + init(); + } + + + // ========================================= + // Public properties + // ========================================= + + /** + * Get the current threshold value + */ + public int getThreshold() { + return threshold; + } + + /** + * Set the threshold value (in milliseconds) + * + * @param threshold + * Threshold value + */ + public void setThreshold(int threshold) { + this.threshold = threshold; + } + + /** + * @return True = the callback will fire immediately when the content of the + * EditText is emptied False = The threshold will be used even on + * empty input + */ + public boolean getThresholdDisabledOnEmptyInput() { + return thresholdDisabledOnEmptyInput; + } + + /** + * @param thresholdDisabledOnEmptyInput + * Set to true if you want the callback to fire immediately when + * the content of the EditText is emptied + */ + public void setThresholdDisabledOnEmptyInput( + boolean thresholdDisabledOnEmptyInput) { + this.thresholdDisabledOnEmptyInput = thresholdDisabledOnEmptyInput; + } + + /** + * Set the callback to the OnThresholdTextChanged event + * + * @param listener + */ + public void setOnThresholdTextChanged(ThresholdTextChanged listener) { + this.thresholdTextChanged = listener; + } + + // ========================================= + // Private / Protected methods + // ========================================= + + /** + * Load properties values from xml layout + */ + private void initAttributes(AttributeSet attrs) { + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + // Load values to local members + this.threshold = attrs.getAttributeIntValue(namespace, "threshold", + 500); + this.thresholdDisabledOnEmptyInput = attrs.getAttributeBooleanValue( + namespace, "disableThresholdOnEmptyInput", true); + } else { + // Default threshold value is 0.5 seconds + threshold = 500; + + // Default behaviour on emptied text - no threshold + thresholdDisabledOnEmptyInput = true; + } + } + + /** + * Initialize the private members with default values + */ + private void init() { + + handler = new Handler(); + + invoker = new Runnable() { + + @Override + public void run() { + invokeCallback(); + } + + }; + + this.addTextChangedListener(new TextWatcher() { + + @Override + public void afterTextChanged(Editable s) { + } + + @Override + public void beforeTextChanged(CharSequence s, int start, int count, + int after) { + } + + @Override + public void onTextChanged(CharSequence s, int start, int before, + int count) { + + // Remove any existing pending callbacks + handler.removeCallbacks(invoker); + + if (s.length() == 0 && thresholdDisabledOnEmptyInput) { + // The text is empty, so invoke the callback immediately + invoker.run(); + } else { + // Post a new delayed callback + handler.postDelayed(invoker, threshold); + } + } + + }); + } + + /** + * Invoking the callback on the listener provided (if provided) + */ + private void invokeCallback() { + if (thresholdTextChanged != null) { + thresholdTextChanged.onThersholdTextChanged(this.getText()); + } + } + +} \ No newline at end of file diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java new file mode 100644 index 000000000..145f6547b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.text.Editable; + +public interface ThresholdTextChanged { + void onThersholdTextChanged(Editable text); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java new file mode 100644 index 000000000..d2f3be2d3 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java @@ -0,0 +1,68 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.FrameLayout; + +public class SingleTileLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private TilePosition position; + private long timestamp; + + // ========================================= + // Constructors + // ========================================= + + public SingleTileLayout(Context context) { + super(context); + } + + public SingleTileLayout(Context context, AttributeSet attrs) { + super(context, attrs); + } + + + // ========================================= + // Public Methods + // ========================================= + + public TilePosition getPosition() { + return position; + } + + public void setPosition(TilePosition position) { + this.position = position; + } + + public long getTimestamp() { + return this.timestamp; + } + + // ========================================= + // Overrides + // ========================================= + + @Override + public void addView(View child) { + super.addView(child); + timestamp = java.lang.System.currentTimeMillis(); + } + + @Override + public void removeAllViews() { + super.removeAllViews(); + timestamp = 0; + } + + @Override + public void removeView(View view) { + super.removeView(view); + timestamp = 0; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java new file mode 100644 index 000000000..04bf0c1d4 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java @@ -0,0 +1,63 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + + +public class TilePosition { + + // ========================================= + // Private Members + // ========================================= + + private float x, y, height, width; + + // ========================================= + // Constructors + // ========================================= + + public TilePosition(float x, float y, float width, float height) { + this.x = x; + this.y = y; + this.height = height; + this.width = width; + } + + // ========================================= + // Public Properties + // ========================================= + + public float getX() { + return x; + } + + public float getY() { + return y; + } + + public float getHeight() { + return height; + } + + public float getWidth() { + return width; + } + + + // ========================================= + // Public Methods + // ========================================= + + public Boolean equals(TilePosition position) { + if (position == null) + return false; + + return this.x == position.x && + this.y == position.y && + this.height == position.height && + this.width == position.width; + } + + @Override + public String toString() { + return "TilePosition = [X: " + x + ", Y: " + y + ", Height: " + height + ", Width: " + width + "]"; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java new file mode 100644 index 000000000..c1728faff --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java @@ -0,0 +1,299 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.ArrayList; +import java.util.List; + +import android.R; +import android.content.Context; +import android.graphics.Color; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.View; +import android.view.animation.AlphaAnimation; +import android.view.animation.Animation; +import android.view.animation.AnimationSet; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.ScaleAnimation; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; + +public class TilesLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "TilesLayout"; + private int animatedTransitionDuration; + private List tiles; + private TilesLayoutPreset preset; + private int tileBackgroundResourceId; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayout(Context context) { + super(context); + Init(null); + } + + public TilesLayout(Context context, AttributeSet attrs) { + super(context, attrs); + Init(attrs); + } + + + // ========================================= + // Public Properties + // ========================================= + + public void setPreset(TilesLayoutPreset preset) { + try { + rebuildLayout(preset); + this.preset = preset; + } + catch (Exception ex) { + Log.e(TAG, "Failed to set layout preset", ex); + } + } + + public TilesLayoutPreset getPreset() { + return this.preset; + } + + public int getAnimatedTransitionDuration() { + return animatedTransitionDuration; + } + + public void setAnimatedTransitionDuration(int animatedTransitionDuration) { + this.animatedTransitionDuration = animatedTransitionDuration; + } + + public int getTileBackgroundResourceId() { + return tileBackgroundResourceId; + } + + public void setTileBackgroundResourceId(int tileBackgroundResourceId) { + this.tileBackgroundResourceId = tileBackgroundResourceId; + } + + // ========================================= + // Public Methods + // ========================================= + + public void addContent(View view) { + for (int i = 0; i < tiles.size(); i++) { + if (tiles.get(i).getChildCount() == 0) { + tiles.get(i).addView(view); + return; + } + } + // No available space for the new view... + // TODO: Take the tile with the smallest time stamp and place the new view in it + } + + public void clearView(int tileId) { + if (tiles.size() < tileId) { + tiles.get(tileId).removeAllViews(); + } + } + + // ========================================= + // Private Methods + // ========================================= + + private void Init(AttributeSet attrs) { + animatedTransitionDuration = 750; + tileBackgroundResourceId = R.drawable.edit_text; + tiles = new ArrayList(); + } + + + private void rebuildLayout(TilesLayoutPreset preset) { + ArrayList positions = buildViewsPositions(preset); + + // We need to transform the current layout, to the new layout + int extraViews = tiles.size() - positions.size(); + if (extraViews > 0) { + // Remove the extra views + while(tiles.size() - positions.size() > 0) { + int lastViewPosition = tiles.size() - 1; + removeView(tiles.get(lastViewPosition)); + tiles.remove(lastViewPosition); + } + } else { + // Add the extra views + for (int i = tiles.size(); i< positions.size(); i++) { + TilePosition newTilePosition = positions.get(i); + SingleTileLayout tile = new SingleTileLayout(getContext()); + tile.setBackgroundResource(tileBackgroundResourceId); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)newTilePosition.getWidth(), + (int)newTilePosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)newTilePosition.getX(), + (int)newTilePosition.getY(), 0, 0); + + tile.setLayoutParams(lp); + + tiles.add(tile); + addView(tile); + } + } + // There is a bug in the animation-set, so we'll not animate + animateChange(positions); + + // Regular repositioning (no animation) + //processChange(positions); + } + + + + private ArrayList buildViewsPositions(TilesLayoutPreset preset) { + int width = getWidth(); + int height = getHeight(); + + Log.d(TAG, "Container's Dimensions = Width: " + width + ", Height: " + height); + ArrayList actualPositions = new ArrayList(); + for (TilePosition position : preset.getTilePositions()) { + + int tileX = (int) Math.round(width * ((float)position.getX() / 100.0)); + int tileY = (int) Math.round(height * ((float)position.getY() / 100.0)); + int tileWidth = (int) Math.round(width * ((float)position.getWidth() / 100.0)); + int tileHeight = (int) Math.round(height * ((float)position.getHeight() / 100.0)); + + TilePosition actualPosition = new TilePosition(tileX, tileY, tileWidth, tileHeight); + actualPositions.add(actualPosition); + + Log.d(TAG, "New tile created - X: " + tileX + ", Y: " + tileY + ", Width: " + tileWidth + ", Height: " + tileHeight); + } + return actualPositions; + } + + + @SuppressWarnings("unused") + private void processChange(ArrayList positions) { + for (int i = 0; i < tiles.size(); i++) { + final SingleTileLayout currentTile = tiles.get(i); + final TilePosition targetPosition = positions.get(i); + currentTile.setPosition(targetPosition); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + } + } + + + private void animateChange(ArrayList positions) { + AnimationSet animationSet = new AnimationSet(true); + DecelerateInterpolator decelerateInterpolator = new DecelerateInterpolator(); + + for (int i = 0; i < tiles.size(); i++) { + AnimationSet scaleAndMove = new AnimationSet(true); + scaleAndMove.setFillAfter(true); + + final SingleTileLayout currentTile = tiles.get(i); + TilePosition currentPosition = currentTile.getPosition(); + final TilePosition targetPosition = positions.get(i); + + if (currentPosition == null) { + AlphaAnimation alphaAnimation = new AlphaAnimation(0, 1); + alphaAnimation.setDuration(animatedTransitionDuration); + alphaAnimation.setStartOffset(0); + currentTile.setAnimation(alphaAnimation); + + scaleAndMove.addAnimation(alphaAnimation); + } + + currentTile.setPosition(targetPosition); + + if (!targetPosition.equals(currentPosition)) { + float toXDelta = 0, toYDelta = 0; + if (currentPosition != null) { + // Calculate new position + toXDelta = targetPosition.getX() - currentPosition.getX(); + toYDelta = targetPosition.getY() - currentPosition.getY(); + + // Factor in the scaling animation + toXDelta = toXDelta / (targetPosition.getWidth() / currentPosition.getWidth()); + toYDelta = toYDelta / (targetPosition.getHeight() / currentPosition.getHeight()); + } + + // Move + TranslateAnimation moveAnimation = new TranslateAnimation(0, toXDelta, 0, toYDelta); + moveAnimation.setDuration(animatedTransitionDuration); + moveAnimation.setStartOffset(0); + moveAnimation.setFillAfter(true); + moveAnimation.setInterpolator(decelerateInterpolator); + scaleAndMove.addAnimation(moveAnimation); + + // Physically move the tile when the animation ends + scaleAndMove.setAnimationListener(new AnimationListener() { + + @Override + public void onAnimationStart(Animation animation) { } + + @Override + public void onAnimationRepeat(Animation animation) { } + + @Override + public void onAnimationEnd(Animation animation) { + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + + // The following null animation just gets rid of screen flicker + animation = new TranslateAnimation(0.0f, 0.0f, 0.0f, 0.0f); + animation.setDuration(1); + currentTile.startAnimation(animation); + } + }); + + // Scale + if (currentPosition != null) { + ScaleAnimation scaleAnimation = + new ScaleAnimation(1, + targetPosition.getWidth() / currentPosition.getWidth(), + 1, + targetPosition.getHeight() / currentPosition.getHeight(), + Animation.ABSOLUTE, 0, + Animation.ABSOLUTE, 0); + + scaleAnimation.setDuration(animatedTransitionDuration); + scaleAnimation.setStartOffset(0); + scaleAnimation.setFillAfter(true); + scaleAndMove.addAnimation(scaleAnimation); + } + + // Set animation to the tile + currentTile.setAnimation(scaleAndMove); + } + // Add to the total animation set + animationSet.addAnimation(scaleAndMove); + } + + if (animationSet.getAnimations().size() > 0) { + Log.d(TAG, "Starting animation"); + animationSet.setFillAfter(true); + animationSet.start(); + } + } + + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java new file mode 100644 index 000000000..76a13d73b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java @@ -0,0 +1,157 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.LinkedList; +import java.util.List; + +/** + * Describes the positioning of a tiles in a 100x100 environment + */ +public class TilesLayoutPreset { + + // ========================================= + // Private Members + // ========================================= + + private List _positions; + private String _presetName; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayoutPreset(String name) { + _presetName = name; + _positions = new LinkedList(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void add(float x, float y, float width, float height) { + TilePosition tilePosition = new TilePosition(x, y, height, width); + add(tilePosition); + } + + public void add(TilePosition tilePosition) { + _positions.add(tilePosition); + } + + public Iterable getTilePositions() { + return _positions; + } + + public int getCount() { + return _positions.size(); + } + + // ========================================= + // Static Presets Factories + // ========================================= + + public static TilesLayoutPreset get1x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X1"); + preset.add(0, 0, 100, 100); + return preset; + } + + + public static TilesLayoutPreset get1x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X2"); + preset.add(0, 0, 50, 100); + preset.add(0, 50, 50, 100); + return preset; + } + + + public static TilesLayoutPreset get2x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X1"); + preset.add(0, 0, 100, 50); + preset.add(50, 0, 100, 50); + return preset; + } + + + public static TilesLayoutPreset get2x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + preset.add(50, 50, 50, 50); + return preset; + } + + public static TilesLayoutPreset get3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X3"); + preset.add(0, 0, 100/3f, 100/3f); + preset.add(100/3f, 0, 100/3f, 100/3f); + preset.add(200/3f, 0, 100/3f, 100/3f); + preset.add(0, 100/3f, 100/3f, 100/3f); + preset.add(100/3f, 100/3f, 100/3f, 100/3f); + preset.add(200/3f, 100/3f, 100/3f, 100/3f); + preset.add(0, 200/3f, 100/3f, 100/3f); + preset.add(100/3f, 200/3f, 100/3f, 100/3f); + preset.add(200/3f, 200/3f, 100/3f, 100/3f); + return preset; + } + + public static TilesLayoutPreset get3x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X2"); + preset.add(0, 0, 50, 100/3f); + preset.add(100/3f, 0, 50, 100/3f); + preset.add(200/3f, 0, 50, 100/3f); + preset.add(0, 50, 50, 100/3f); + preset.add(100/3f, 50, 50, 100/3f); + preset.add(200/3f, 50, 50, 100/3f); + return preset; + } + + public static TilesLayoutPreset get2x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X3"); + preset.add(0, 0, 100/3f, 50); + preset.add(50, 0, 100/3f, 50); + preset.add(0, 100/3f, 100/3f, 50); + preset.add(50, 100/3f, 100/3f, 50); + preset.add(0, 200/3f, 100/3f, 50); + preset.add(50, 200/3f, 100/3f, 50); + return preset; + } + + + public static TilesLayoutPreset get4x4() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 25, 25); + preset.add(25, 0, 25, 25); + preset.add(50, 0, 25, 25); + preset.add(75, 0, 25, 25); + preset.add(0, 25, 25, 25); + preset.add(25, 25, 25, 25); + preset.add(50, 25, 25, 25); + preset.add(75, 25, 25, 25); + preset.add(0, 50, 25, 25); + preset.add(25, 50, 25, 25); + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(0, 75, 25, 25); + preset.add(25, 75, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + return preset; + } + + public static TilesLayoutPreset get2x3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Custom 2X4X4"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + + return preset; + } + + +} From b7cd02c9bfb32738ec339e3877b694801baeede2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:02:05 -0500 Subject: [PATCH 106/165] AndroidGCS: Refactor the UAVO browser to use a split view - objects names on the side and content on the other side. Add a filter for settings versus data. --- androidgcs/res/layout/object_browser.xml | 54 +++++++++++- androidgcs/res/layout/pfd.xml | 34 ++++++-- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++------ .../src/org/openpilot/uavtalk/UAVObject.java | 9 +- .../org/openpilot/uavtalk/UAVObjectField.java | 6 +- 5 files changed, 151 insertions(+), 36 deletions(-) diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 9c7456915..67dc0af76 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,6 +2,56 @@ - - + + + + + + + + + + + + + + + + + + + + + + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml index 191a80eb9..5291f2724 100644 --- a/androidgcs/res/layout/pfd.xml +++ b/androidgcs/res/layout/pfd.xml @@ -1,8 +1,30 @@ - - - + + + + + + + + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a6ed177a2..1a7495ada 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -16,8 +16,12 @@ import android.util.Log; import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; +import android.widget.CheckBox; +import android.widget.CompoundButton; +import android.widget.CompoundButton.OnCheckedChangeListener; import android.widget.ListView; import android.widget.Spinner; +import android.widget.TextView; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -27,6 +31,7 @@ import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; + int selected_index = -1; boolean connected; SharedPreferences prefs; ArrayAdapter adapter; @@ -35,10 +40,15 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - Log.d(TAG,"Update"); - update(); + updateObject(); } }; + + private final Observer updatedObserver = new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }; /** Called when the activity is first created. */ @Override @@ -47,20 +57,48 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); - - Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + + OnCheckedChangeListener checkListener = new OnCheckedChangeListener() { + @Override + public void onCheckedChanged(CompoundButton buttonView, + boolean isChecked) { + updateList(); + } + }; + + ((CheckBox) findViewById(R.id.dataCheck)).setOnCheckedChangeListener(checkListener); + ((CheckBox) findViewById(R.id.settingsCheck)).setOnCheckedChangeListener(checkListener); + + updateList(); + } + + /** + * Populate the list of UAVO objects based on the selected filter + */ + private void updateList() { + // Disconnect any previous signals + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + selected_index = -1; + + boolean includeData = ((CheckBox) findViewById(R.id.dataCheck)).isChecked(); + boolean includeSettings = ((CheckBox) findViewById(R.id.settingsCheck)).isChecked(); List> allobjects = objMngr.getDataObjects(); allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - allObjects.addAll(li.next()); + List objects = li.next(); + if(includeSettings && objects.get(0).isSettings()) + allObjects.addAll(objects); + else if (includeData && !objects.get(0).isSettings()) + allObjects.addAll(objects); } adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); @@ -70,29 +108,25 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref objects.setOnItemClickListener(new OnItemClickListener() { public void onItemClick(AdapterView parent, View view, int position, long id) { - /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), - Toast.LENGTH_SHORT).show();*/ - Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); - intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); - intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); - intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); - startActivity(intent); + + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + + selected_index = position; + allObjects.get(position).addUpdatedObserver(updatedObserver); + updateObject(); } }); - - - UAVObject obj = objMngr.getObject("SystemStats"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - + } - - public void update() { - adapter.notifyDataSetChanged(); + + private void updateObject() { + //adapter.notifyDataSetChanged(); + TextView text = (TextView) findViewById(R.id.object_information); + if (selected_index >= 0 && selected_index < allObjects.size()) + text.setText(allObjects.get(selected_index).toStringData()); + else + Log.d(TAG,"Update called but invalid index: " + selected_index); } public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 28c279040..087d2b808 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -52,6 +52,11 @@ public abstract class UAVObject { } private CallbackListener updatedListeners = new CallbackListener(this); + public void removeUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.deleteObserver(o); + } + } public void addUpdatedObserver(Observer o) { synchronized(updatedListeners) { updatedListeners.addObserver(o); @@ -730,14 +735,14 @@ public abstract class UAVObject { */ @Override public String toString() { - return toStringBrief() + toStringData(); + return toStringBrief(); // + toStringData(); } /** * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName(); // + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 3ed221079..af707d3a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,11 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + data.toString() + " (" + units + ")\n"; + sout += name + ": " + getValue().toString(); + if (units.length() > 0) + sout += " (" + units + ")\n"; + else + sout += "\n"; return sout; } From 0348a8921eb3d25adf8175b566235b2c3d1e3145 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 22:20:00 -0500 Subject: [PATCH 107/165] AndroidGCS: Output all fields from the UAVObjects --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index af707d3a0..988642ff0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,14 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + getValue().toString(); + sout += name + ": "; + for (int i = 0; i < numElements; i++) { + sout += getValue(i).toString(); + if (i != numElements-1) + sout += ", "; + else + sout += " "; + } if (units.length() > 0) sout += " (" + units + ")\n"; else From 3a3ac552da368015b5a87e00991a4903b6a1cea5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 23:00:25 -0500 Subject: [PATCH 108/165] AndroidGCS: Refine the graphics of the object editor --- androidgcs/AndroidManifest.xml | 4 +- androidgcs/res/layout/object_browser.xml | 71 ++++++++--- androidgcs/res/layout/object_edit.xml | 9 -- androidgcs/res/layout/object_editor.xml | 49 +++++++- .../openpilot/androidgcs/ObjectBrowser.java | 19 ++- .../openpilot/androidgcs/ObjectEditView.java | 117 ++++++++---------- .../openpilot/androidgcs/ObjectEditor.java | 18 ++- 7 files changed, 179 insertions(+), 108 deletions(-) delete mode 100644 androidgcs/res/layout/object_edit.xml diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 40b08c328..52bf9cb30 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,14 +2,14 @@ - + - + diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 67dc0af76..567c04f15 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -1,10 +1,13 @@ - + - + + + - - - + android:drawSelectorOnTop="true" + android:choiceMode="singleChoice"/> + + + + + + + + + + + - - diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml index d93b1a097..be6e219e8 100644 --- a/androidgcs/res/layout/object_editor.xml +++ b/androidgcs/res/layout/object_editor.xml @@ -1,6 +1,45 @@ - - + + + + + + + + + + + + + + + android:layout_column="1" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_map" + android:text="@string/location_name" /> + android:layout_column="2" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_pfd" + android:text="@string/pfd_name" /> - \ No newline at end of file +

~U2 zV(7I;?-JQ+3bcJ9IkLThF8Qg~=GOcM3GaZ7{jg?y?V=016Ti zhIF;zB&JNM3->slq?mwUd@Ld{pEL87C^ogtz+yNv1UNw~*j=9|Q?<^jx4{&ia+rM-t=djS;q)#EXCT@A;AeWK_IW*1 zyC<;yiF=k_eRO-5sAu#%TF*w1Hlh)AR!2P}`*V8nO&yA$7s zaE23{cHe`eVb}0nMCH^%g{QP`(bQC*Xl|zS^V7FS7rfc*b=!|zwL)1&8D}7i&wcgF$ZLUp5vbNW! zpcTKp!3C-2*Jhw8{UWUx8`btsJlZm@strHUZEnwI@td=dt}Xwyy~*1*W}ppM*VFEl1EPDh^9KN-9w zit9t`S0CQg)$TFhxTw!^`Gk1_eNWwsNc@Dj4;`)qHW_SMoBEvY+K$q8$q+<;y$xM& z#`A={DQLr`mp0e+VK3MltrcqTWDEAFG0#(I$@~7ccjDk{b89x5UY-Jf6Vk}1R7*Y= z-Ihd2)t2}4WOL>==T6P$7bl_Vxfrx!4gDT1#*82L*;%^zbLTOz3M3(c>j=Ll(0xLz zZW@*hhvBxWM&_h!fgr#|y-8pteI5`)jFnj->21cX-3v{E7gd>8seBSyh??~YONgl7 z`S}??k@KzQ>eDOTr=UiUX(-it406@(iF^(Fp=y^&%$tgeohM`T^hMaXEDodkb;8oP ziKtP%ig8;Hu{!$a&mW)Qx33=Kk8eK0U%!2c^T+ntyA82yhdB5Ip8SP>e!(Yrf=jrM zjh`Ju-!nVW{lpIVdz{=!eUJYvmAdP3t}5L;fE}M5Lj0wrNVvZd(Z}YY^Ga?5^7%4S zJeP!PR9YlnLlK>giayx}mHxt}j+p=~hzN0>Ld@0i8j4NV{%?xLf=Hs2p3z-*7-E`}!oNonLNLkXKXpS3KN-HHyCxKCuU0dZnB#=u7wuCDEEqNws}Sm&JUFZ{Y)MLg#jU8Lcz#bI;Zm6;_E)@B^*I4m1PXU)AS)1fnFI_;; z{%Ge-efiNnEJ|31T&-s!SF4%G(`GjEx0{1}?c%v*rS&YN$kc2G2G3fDoz&y{b!v{d z*paASr4p3`Iu`j>3Hg^wlt6=eb>VMNw+_NytzVaeQN>zrZAva?Ja*(zzV$boGJkyg z8TM@1h5{{TBeL-f(D^&~vd3!EiqF1KhoE9A%0!3O`p~ypXp5Ud+qwX1o^6ofmZ~lt=d#uVZxYPPl*OAo_Id zh&0coM8=fqP_l3leDU6WvX5`@>(`&++R=R&$U|95y-<{OFv^(@uKd}fP^&^E%!wI~ zO$*~Nd+ZQ=diyd4bnS*T$x`clIUoV@@31~;dzo6g0v`M$O>~63D{rQ#mR{mN-1`ZSDM z3kyyb4x6~F8&dWw2jv(1`0XdywR1a)bc{z7CrQ4x6!7`l#_=DgO2h1}W}}^dB~I*F zk1_o_VCk&!R7sk0w22-{7uf-FDafZKW~Mk+`EIO1Y?SNYuu=z=-;P1kMw%kbdi#rIj)`(&`*lKfO0RF-~k@xi1enY#AQ3bD#%uWryqR# zSEppX&K!%$+p_hjy*UgrVK>>D$*J!$W*U zX0MJ@dvxOhzWL;BeD%>oeD(Mte)!*qd}gYN1{3Edj>OPw{uYSW`3+R^YEGEK8} zQLa1>wIQXz81VlU_h@@Z{CdccZ%-N9POib$8k4jKmkIyOuK$EDKYfTL9+nB?SYbJ7 zHsW|NalDf_9@MoJ=1yj0NL4ak;@GP9d3bfjgWj0jYp;$wA3c1CL01aOkKcVv_-;c{ z!S~Hshz{bnM)p>-2;Br6-@T4{Nqa1rISy@GHsJw_f-a*q0?-w+(xex3#k|B0WHmld z*lM-O^Hvndl@&$1%|&iHUUMh#Lv0~y?$^kX{{>_r)6|NTtjp@vs$k=~1e7H+tRctAtdIyF(78h)9VOPZ3Z=c-kyjD5SdpnQ#LsQp@f)T>#=V5{k* zJqHWt%|^5PctL3B! zcu*t7@jX$Ebv=t13FXjiLJ(YDdLU{;;Y)oQDpS0T~Tyb9c7hAZ6H zeaVmCeuN#{w~{x<8MyPcnT31-9-W_jT39!fPe{PAU28G2&s$hHZ4BD9cq71|11KkB zNQ`oqLFW#-6kUW{xH78oEX0{dKH#z0Kcey)e%Aej+N(ZCjoNigtuT~Rrc|z2kzvRO zF=x(n%$Oc)`^)9Rk~XiIwT2-K)-HGxeNQNDt*6twh6|IdY;JXPJ&ql^~C{I8CK0lr4n@wW^@y z8}%_QW;B{Me$D2wdM?rO&F4Bz_!s>8%NMwM?g+%{btp#y*zq*rtU|1h1vKN;KL^=rib! zutFXj0#Gmo!o_0%AcjX{xX+~i1#0=s%+d?ajLPig+=2YmVQeJah2 zwrM>bQLUyUFWI#;58*BkbrI!fZ8i;qrmw>GRr9DeHw$p@$_l1;1qzh{$v`O~(NaRv zXaqf4s8#0g<;j=$hpPHN-{VIf6L+2g&ihb`2Px@!DGaLrPb*Znag^ z%9S&h;k!clvMwhV#tSLpsaVk>s7BSJBTt7I)~^eWP>JZ-wWHBG7h9-3D?fetm^lA~ zUZQXD@!K~sQAgeM?2djs3a4|&4vaJ^&*QA>W6Rp*#PMOCcDk0s^0}!$I<>>7#Ym;c z53b|X;hi|NXEToN-;UEfZLe+1H|*4f#1IzF&Fl+l&g!(G_NjFVbwb78~nqA&$*tB^D+|2Sp&P5jmNrt+pC{Xss^bh?wP`5t%UmbpFKjty3N#= z+Q*|?!MEZ};m-HwOemvp`#EH|voRumJ@#%~g85TM;{p#TYgn(24VGFV=W)yCO?hC; z8j^1Xwo>HpBJ-LWJHb`B$p}@>W$Myc+&BOJ&0`!quoo5kE=I}j3sJoDJmhUP6@}W) zK&c*!P^#x*6zQ@6y{2!#nS-0La^6JTyL5z(!>%SfMJ+K)PwV~{;5h`cSPbxdzZkXv z`TqT@c>L(9v9ZVZFXJ&I_jQzkEN4+jNB9cx?-Q8s-MwT7BUT|})$|opmnMIjhbDf= zdLCRmjTTMZQ$BTHtnl%JYj~GC*fm*(^Hedl(*yjuWBd8Ot9Z!0%+23;%_go3c-JZr zom|x=vmN{>eWRiWc&Xee z$7woQJiXp5TDce%Fl9A)=A#=fAG|kA zDX(geS6H3_KDTMPag440|ggl zohY*dvY=nD?!k9|aPJ!K-?)ggXV2i$<;z&SECG>G1yQ@f>o|4x9L}6OkJD$*ayRM) zLgYN&zkAsvYwvFEFIT9a|2O2R$B=h=JYF;~6|{6|Gnw!gw@m%^KT}14ALz=MPuBzw z{$e?~D|Bl9;|Dj`ryuBE_z3E+#FhZ1GN%vkv3vYk9rPvV)cTU@FT+FeK7MqI&Zh5p z2K484xVh;*oSKq<8|kq#XB6$A;e!X5)Kec!k1<0t7b=jm#*E`JwnfcXs+k@mb5)Z|ZxU$Lq8#jvO$oU(@+$g|ni$JS zyHiiSsiPh!Ee4_Tx-YYN5GTU0Ap;q8+K3*{iL~fgHz&8K5CXh$cMBkJOh?yUH-1kD z2|(U3=sguI5mZ)`qcOG8R&@a7Sq1Dm#{bLT1s!VMGkkN z!`OyKj6L%#(!5-bdYY|=FfL{%3gqC5xZd{tlXqQw{`n23rPhLerJ!427&rPB5H`AX zYL7Ey!b|4TYM>?}bgLGvg6iJ669=(?#+_!77_nIkWcXsI?sL=t`DV3H9tO>j_WZGe z3#Sg@@Sd%xU9*POCl;)h3sb76<6CXmqQCgzNn=;fSY)$Kf-`$GnY0*vYf!rydbDp2 z|A>BgOf7rV&;iy$&6SuJXd7B^@pEFedbt{@T)j+j5GrQg4$&}$HwhOloNGSNI<;$J zA-la|>3lnKR!z4qauOPWZ0Y4+N=v|b5>hxwEuqbD84Qnz;u}M`N{Om!M=&=qB?8%r zA@9aupR=tgq1Bm;UJbf>HR>vw%D*o9s*|#QghP4wBDrp>ah5QakWweb50n?JLXMu` z#L9!zn*U=*jlg5ZTO8l95~ug9#iherv2cbPZy|rA_=Dc*zDK_z$6wHs29QensA^S? z+fTJb+{bN=c1!Dp);iTJmwHL1<68sqYG&*h+5U^AIzG?T4G)a$hhBMvJ{ z>v_!vfy|K2Q4+gnQ%FKU*ap4G1*cy);LyjH&kI<;$w8Iva9 zjn`jgop~@-6=f2fJy`2%L4SdMNvg{C^Wfecn`4zLRX{(UK023kwM(b=rVwhMi@P%8 z(n75?I44!jnlzduqP~YqT@A;EMuWIVNDDrKo4-wwoTxGk{a zR*RLiRB{nggQFpLMUq69`{Pda8`R-}s)w;}$42;fZ&|~&)yA)ysEyIMrBgW@ZYuh6 zZ^ih>&W8x<=5;PcoRqFB-H8r!g{Hnb0D(hKk zl@k?Qzvm0Md;1z{)~aq>qvK{yp+hkS$^ zi!ZzYxo-WhRI7@7N=YmWwiPOr$7rg{eY3h7qz#605vm$p|sdc;y$JZKBb#*D>W z$#}&VJa(9PMd>M62Vkz+ymu;~t1A7hUw`#^VCVn$KYWcURp~zDYOXti0l0)|+{MsE zb-#9Dg_#ogJeTNmD_SH&YGjUz%zz?1@mFoqDCuOD;&iuYx@pYy-j>aqn31Dv%!D!U zj~i`gDl0hPS(fYy99#4+Oly&~Xav-I6Iza@h@~PDPaw@PeV?eojtQ0tSDvyoY1A6h zG&cgAIFjl_+O%#Yx??jzZS^T-tvVR8j?ulapr#>E z<4oHiR}tymRef?Ia)V}!EF03R1D3>3!M$r|aqs#iE)SG4E~CnGWaU}8gZ3jom!tD9 z=ROHuqlO(t<_zgVz-4(NC@xHT5d+FG%_~SCTLCk0+f1?dr?V*%&{je(4RBeTMlP4s3w2-BdisQh z-YBok;4+rjL)$l7A==Lkl;g+3KVcjuO^iX8&g~7Hb`qkUZJ10IsRBXueHzl=ef=@s zqmO3G>V@bKw+F>W?j<|!z6#k34A_EZGY)XYem*9TABurJ+VSThX7P~9W+s;OQkktE zKDdD`>z4EA;`!LXb@&Lsh$(A6Z7k?s!> z>WfrRyHe=c-7qabdpXfcq*jjDy?&KDBR@Jt$W>R}utO=5Lbu)~dgXPQ@flybw2TC0 zMvQWuAUzEk$tB!I(8OkR5uKNx;b$6dHy94LcL&#c6PDU~u4b>9)me%%Rgq^SjOf=H z-P<+6lnKM=9JzqcKYT>6dM$IU|+!9O$d9!-}wA9;>k+e`)%H+Ay(|U#8@_r z60^p3$&@q)4fe@}WR+Co6YK5zuErTm*ahpDj#sw8I={B;`gHb~Skpwa%T!v+ia&5r z^n-3+b9wQ?5&kB`mTxW2s^A8o;Cc!-@`)N7f5Vk?N3ob^?)UG~(vCvxKsTJ~mo}lm zjnB!izWn4NK70QTo_uf@Uq5*VljzkJVAWzl=S6DF)v8oN?HaE@K|A&9*5bkLHBhuz zapW&RZ7x4e%Dnlx<18Qlxv9Jb0;yC=>87svSUO*#?@{>*pct+9+BK@97T0O3bM>hJ zrw6r(Tu36p?LyeKGXn56r-rc^8L{*W zIL&2ZIfeoV&LG36Ivql>Bm1IHrxu8tJeDi4*YNF=59v}W&*9|aweXRTgEjmJ@+roG z2-Y=f_;DVmQeTJJHc7%??L#0dpvT?IDr@GvX->PFF$%fM&KaHWG9Bn$Y`X)9pxPM=C z-uEMNF8v1um-9oE794%jqJgwKN3KipLK`K6kl2)9WaFb|xeZi%4bIPiG~H7mm7$b~ z!-~3zRS#97?s`lw$YX=lu-aW-&a!&FZdpiI5>HVQMube&Y#N6W!Bd!@#-%rb0=U#u z0hK~^hYUMc3s9clW>m2Erc@|j@?B{9`m=Y4%HQzCXK&-wzD;Pf_6Z`1M1KJp5jh#) zT4mLD#Lqtd(AhZj;{ocs_yba1JHBO%R<-EY-oE{mwa~eZ-|18gI2IM$W2TxgNuH%x z5dHo9(-$~#Xcta!S@8J5ooMw|HwcMU>o!F-esuL$t;4-JRqOIsO_j=Ah5z(TU#ir3 zgP$gWvTk1aR~n&P&;Ewun&0n)^3NlrLNG2PW;buEA{r`rt zG2r0ZptNbt1)1jAXd~#m_@Nx4a=0kg%k+g@vJUbR5sEO&$mnrdZ_+sACKJ{5CVh{k zDtGPfLnLfFh&8*8VAH`8Rh@(|y%1uxjz~ z7b?X>D}MjsGd#L}8WYa^f=X+DLY~;${MAHM&b3xzuk_{R?HK+ASr z1E6<-T!~D%Qq9--;kDKqsK|8X+PXGIW!`hY^ID^k<$IH%+$*o4d+z}_dvp&@azY*4 zwGl&mcc4bpioY@TD&gu14iET&A7=}AEJzrSIHBQ7X<57_q0_B%2i)cF1Kv1y95)!0 zd;7|1{?g$*t5?npxg-qw*#v$4W{Hjy^K>wQ%d1Tz;I5Vof^ig@!X`hK&`48Be&cR<4U`rJVr1-mvRD-nA zqSXa${}h(w)fHZJm0(i5y@H&}a-~oQVR}Y~z114x`cBl6C=Z|>XLkWlfO>$ZXVT^u zyQQ*v$ekpCqg&WzlL)-;s@oywoyy7@b?2t5*LxF5&$#TKg)(c%)uq`}Ct}&cIatD< z1YbNq9xIkDMwc#K=$>;O@l~o+v7>VqFNn7?OL<+sXs$uo3)GRjOpX8zp#5_3ivqU@ zB;7Ftc9+9@U_W_iCyo>Bi8*`)aq2!paQ@;YoI8I3?K<~CzriDzK94N7dkZwr7yeI;oS?A%1?g5BMQp_drvGdpu67fA6J zr6N!8!!P_$YrA;jfH5NhC|KI3)(R136Pn(ld&-UC)%7~aDI9#lc&vdhmB;pk3J-az z{pFWlV(i6vZc2O)pL1dVz>W>*(6*&5F8cLbE-BrG$d@pCiXThoOvR}FU2&5EZu)6G zjkd_;w#>cS`@+1O;1taMG=q0_6c@M8FnG!nmx;S46^QPpUj;NEZ=ML-!nArDl0&Yg zOJSYI^U3>Op&;ElreB=nOT)Bj}xeIXk@KJ2q zvXv*ioo7h-8eF@64YQeFwpv3|Zh}e-dAX~^h?lp=pzdwZvt#QZhje+5;PanKOj;YD zz|hGZBXY{TmdY}Iw2tEZiLm^ZXT(0i14d9>ICC7=FP*i(-Js!^#2}teoBTb9yA#Vm zKqHjVry~NP)mlydiyy8gUq5%uAmhm!n+!$eSXEG!BF!Wd#5goAxpQ*ba13dqrBr(gu5370R7XB^5(jOK4te{lB#BQ^V(WcL8CNf(kc#xWe5dLn%aO){}^$q7MN zE%NjaVMXKOjuC57!K6Zxo|4M%O;bIor~FFrhv3~U5gIEQjz&MeOva3q=-^~?+o7-1 zHO^sPlhwSC2r>-o*1s^!U8VZ_{yXhZ-bMv{2aX2x5z{rObJT3u0yl5o;LqQU#IVuP zc=+HRdJh=%7EuUU@y@w0e3 z+92C<5oFW<#xS22HC-01xAEO*-X&anW>0rn%+DmATRnmTMPj;Vx6X9ll(n$>og0?hPRe&~ zp0T(h@iiesy))z%Obih(Exf6euqGFg;g3L+IU}`2Et7sHEUSe=t@4#8NGq)ts2BRK z-f7lIHxi(QJJqG<^d8kO{-b=M-i&lL#>U*|HOobS9-7S<*9jh>p8&q%$}`luxM5+ri~wrt^Bc# z_^Hu0gAHryjZdwUDw2top-ofes@>{y(DmHymG&ZhUZWDFO+63FEFIJ=bof&4LuqM4jUKP<* zBWtZnsd3gAYl3*`;FYbkeD9w3lyPX0ZVhj7)f?_C$>2JFF*f; zvnLMG((Hl?v?i;Nv)5?Q9M`U0L$3iNFk);h?%lnO(c>pl0Uw3C_wJgOa{ulvv}o6j zahEHp!R$u`;#{0vc$c$q-`3R_&7IrBdbUOU#1VF8^3u68+*S0Tt4lnCi#%uk9qN%* zJy*YUb#+&FN1)h)%=30{wzS`SSn*lh5U3-CI zCxq#MF5yZ7PUci+aO z>2apn$n_`y=&q z1LLxqwP#bm%Ya}0hd*g$e#n!k_V3taLS62Zp!$-m7`cmninC{j7TlfOnm@8Q3h&-J z$FaO+n=vH3CyGWsAx{c~#atxQwI-%pIB_j+5H zkw!!%1f)|$6hRDZy>@qv@BNLn*FO7j{XZYib69JyHCN5~&UeHdb4*Q-Y}}xp9eZ)R z)Q{UeqW>B7BrJLq{n-ztd86&xx?ZYd3y_tF;qt*F&GH>fJ_KupFBFP^@g?VslVaAC#n-S9@ zB4*#{-}@IYIHuukJbifo+IH^aR^_HG+pK=Gj@Gz!XIYa^O9Ox0@!O@hxOvA5n&`aV z>NV>iFJeP?kzO08hh_r@EP!H?X&L)lQV^1uYp&a+4T^+!o4Pa6WK+R(A>#jSP z`KsKxeL+b7g!repDttXh0_KKi>6#&`#gV73wFKO`aha>OY+SdR%n08ANI5=#x)gnY8Gg(S-pxgVAw?IUz2WBqT>3p zxSp`q%~2tdEgDo%T{0!$1fRQh8O#91Vy}di7Iq*Ev=FPI*+ctQt(9UNz z*!EfJcH+=(Yu2WV(A`kOJfh$1U>0vk zsfu-6SBXuTY2zn7WVIW#v`N!uTmPY>{aoov54aaxS2ea2XYKw&>?wJXV}rz#*+$4~ zGGqK;8#%C7;5A8d3WoTOYFSLjx4(SU8%!_jzw)_BBbP7y<`Y>)#9bYD^M3u(KL6ki zJ1Lhq{#524!P%fYTnY&{3WnbZ36QB{`rB4b`TY6=1taJ>CUQUkN_BUuMR<~X{Yvwb zU*Q(xVf_e7;PhVG4(F~zwkuW$VSiyLzOmUBZlGa4!cun{##+{|Z`I3Hu*1)9 zwUR~dRJ2W7+rDnK<=4ft(SEOWDi`<8AMj z^;Sdy7tcJg!WL=i@H=n4-Hz_qrh$+yR<*3AaPEJ>>er}gIh83SpK_+~QUyeN$#3jd zP?Y-N+uU_C8D@ymEbRE9Ts zHoSLx>)yV3+^ZH0%Rvr~^n7vs#3fXKa<#2@?ChW$^@>&m1;nEcRKPfF(^oSHnHJZ! zRdd&+`QWrdf>Dk_1q(PX*b=PH0$W`r=eeS*G+8RkAFt`V}|zgm2L<3@9RTwef4%||H)&dv=?va z*k;sTU*yq0$kipq^Y zx!4w|?8H+`Y^d(hZ`(AhH@uw{y7guUcCgMijSy%e2AF01& zHuDDB>|b|U*H`9R?dOJDt?k3D%C;d^_1Pg-Yv(Ad`us4fzI}w%d||Xz)wvql*4(W$ zEIV{;?^vtO{;pA0OF5jY?H;Y)qph~~tG+PGYU~NlSJ^qzYHGil%2nMl(rRhHs_t2h zdvM?9h6c~j?<(5{TaD+3`@1ySJjM==v!D zogKDQ*trv>q)-N_7Su0w?TU$$wI+0GfPTLsNA}Ab^`fFva1)}Kgb^uhfq9+At?i31 zKeNYIJ!OSUR<Cq~iJCL%_yRZ@3|tDhf>6w(|u`OK6U!EN%q>=Q`Ws}=K#UN zU-@!nZJI)bADTK@A;W1NHjJN&C-SsJ9jYP=WE@QJ;JWnZMu5~5p6gTd6FzxS2UW~j zZw6j8%CE#5XGw>0Jnm0Wbmf|2J}rQ|;k4lz_=kOXisLk1;$H4l{hj;8LB=&^~(UwWcGNZoO%msJ z@Dx(IOqF`ptyg~^fnc0-y9SUMZod?|IPRRG^@doE@w6iGX5*d3NkOl3^kxPq945Ge z3zJ!d6J6f%+f|os&M-Cyi(1;r3h?q8PM;K7=Owyo0|G<#Z`skuCQ|6{1|?-h6d_ z&idWrl*~bn6;N2!ZAEUghd$qAB^I?;hF}sq3v08LRGReS^Od`Lp%O7KR&r+&PcKu9 z9ILskRDx$#h9iG9Nu0@Hy|%5=+_x2imBTtMvc6rgcN51v+4CBeds5|}P-5s+x;9K` zy-a0g(jX5H>X51PRm6 zsR>uD(_12a&tdG5>KWPibBlrHf&mxza2Ga8Fg#rO{$N{Hu8r<}huD|mcG0T-v6ijLug zPoIW^I~@jbsf0`>`_-wFN0k$@O19X zTe$YF(J+L7{);4zIq0wEB|;p7IclCF)IQ1slX2OGctzKPTLC!gaZ!!h5fR1luw2k$ zt}*~$pUCA*bOTRw{*Uu8PvRIEt}8SZe}1#kvi29>P7psnD(ox~j+P6rD}^mj`LBHI zYlXY@!XQf~Y!cSDbO=)TlP3S!u1f!}B=|~|AJOs(lOj8MSZZXuQl0CUr^na2D4z76 z(oc8P+F7~-tALOupT!+KRla)0D$<|RQ$VzO&rD^f?tQmaR~GD{hvwNeSLKZ(I8Z0} zijX6yLp~g7L!VA(;be>lW|fEL=vpu15-lT`rCP+b+<=z@)nYPu&W6vUUAMkAdHQSz zGb8P7I`?+2M&W>sV<^-)@2xEO_Uz}5AVRg7`#P+52M@|^*Q|crH5G)X!br4>;CnD7 z;mH$4#b|TU8)(yBHjibMUW!i(tsvNHje~gT3>xY*4rZcfumh0U`c!ebzcd?-J4Hj> z{(D8G>&-3P%8F?p>`FAGE|~?wq+i+>&q^ zY#O5Vs7|08n0E;^%YB$$)rdWn3HRBibBgb|EewFkKFPm771bR(dSIs&Jgiv)E!)G! z4ds|_Dkg5`+lsZC2&j#vAvcx-??Ee3Ug-+uq{ESiLyy6B93CK^Ex^7vu3nHHiYUQt z8=p|9NGE$}>_8hcq>nQ(I142{Z|ZQCX6)S#wweTNE(($Lps$Rzp>gJgzA73z6pP0|T!5=8|Etmw4n})CS zcgasz1G|kI)VEF=W?{&*g&b%DW)8D4U$0Zvvd`}zyE`?YKtOW?2*3C2y4EFl%sf!nukY5Vu=uwA0Y*m5PDyqsm<+js0@b?Y~?dW~9I`6{)oZi8ml zx_uXG-LA8>Xw%VJwC-rJ=B?Y?)y-RVu$DT~sCjF1K=O&anB9%&=M0CfbCN18u(6Odd6)zjI=!H6*C_+G`Ky!HT16_LNa}{*_~PR!;cW z6+?aMprTQ>t+RE@=i8z=Q*7p>ks96`V=bH1^L(6yd+1u<&wUl!+!nj)sywC{3s+f; zpIJz8i*C#o9|E!7pgIP;vxa1z4(zz%EbM?PM^d1NQM(SeLScP!Bou^+t&YJbB%V8= zU>cw6p-9;`6(u`m!e|?+5$(ybv5MgsWlI!qJWGkt35`D>Qv`sMkdLtoeA40lLncZW zwn;0`=v%J0>I%7f_4q-hT{@%6J7|ZuE3w?!T{i5q)mj2V3h6AZNCG`SDR{w|KpdrF ziy*Gma~zT(C2Kh}hxR_fS77#KWwkJ0jCK5c&9PM0f%H}V4i5@Wv$&NYA0S?6X8|mF z3rx>Ccd$P_YGV@8p=|W@(dDevlih9BM;mS0xDg5}S*g4v)9kE<(qG*1tcMh%wb7HQ z5Tu^+rrgZhcIxTA2l}07Qm88AEE6!iv9dsn6l&6_q2>p-aI2XTUS2EH>28=ASqiD& z+^UJ@KE+b1DP|Yx<~_$`-aFLCZj($+l}Z3-Qo5)j-U+uTqNe5+NYKFReY?XVpyasS zqbDXHFKy#yAP*daT<6MTrx8I@0x*^bcvHdt`=4KD>z6A{%Oh#FYQZ$?(Xo{$Lo6X* za^2chtxnADqWLG5z4gKDMuDb`?2rUh#d6Xxu&FSmuRERNJotiGF zwC?x!Xd*3SqkI?Tv>K(vK8rrVqR!xG9)fqME2A01!mu&S3|F(>q)^T3fKjce8$CYU zCPlTN<4x>ES-nwbSZ2>lv0fl3hxfG-q$?}&ywY_b^`4yVS zpU>?Fz6*WXrInCIx2A6Sx?mzbXTV_^J6BQ`)Kd)@Ur-Ik6CEEJ2aGVF&b|7w*2q3> z8`iCHeVqpNoE(Z14GbjTBK38K!MIW-imSH-c}8y3G02%|OCfS8j|S<{w>fw}EFF%} z3iK*4?Ub&o!>d3AS4!L*#1EZDl>8V^Px^x_&tKg7{Owm|n*QNC`|jJX?VGQ@u-Mo7 z@5aym`>DPE{`>aD=bzbczx-&w{``ae^3(UeJ^bP(dv?pC_LH*K|NiSw_J{6pS|fRj z=1;Kao?C8Hri~0pUOE|)4q#DT=z9s8msTF=FLcMiWg**Ib_>RfPu1m@7#@D$F#l2U zd8l>1j3cKtsOiZkHPFdW{9{Tuj+?xja)q{1g8uGGrvHEfvL=ik=9&MVSopAgqU4Y( zH7AHybHzwEO!YQ}y+XXB8}Ykhg>v@LqzN`-N=zYi5*Lcvov~(?jrww}JZRN{(!g^~jg?$^`WYBjI1BZoN4 zk%kZWgz6tdOEC_lpt1$PlINYBoK!Y#)=3eAue^N1&MM@TSg<-8m0!B>Q4x7_JNV)* zEj)h6-h1bQQ!(utCn{a-ds*lrc*nMESYzjuEC=YKv!~JcmxX`@$PhOGXX}mb`YwBP zHHydJeR(7TA`hx+fGkvEC<%9@_n! zXVJ!}P1Su8lE6i50s4o7*oiF|Ut~)2(Y-q)8eXtH&u#V*=?#ZB+K4aKNU^Obm&b!5 zNm2F2I8D12A|iG03Tc2B^g+=qZwes;TtStksaY#M`s#RL_tgnjDEit2{o-%DMbGGu z5<<4aT$qlC+?~eh3g|Vc?^;RF-6ZZFi7P0$MIM(BnNZ0}3ClA-++d>=;j~PVR5PcJ z_sNOdwcY{Y=b$C*wy*~k>>WFiO$CggM(j~CT|#*qw~|9lfL!XI9z7*bwR1=+|)^XLIre%fhjfuReyyQyp|D zBzPL{D-BGmG|}l}{Jb^=|L0 z(p&}FlNOLp=V9R%#Twk=5X8l@LVEqgDq60*ulqc%kqrcXXj__qcyqp#TIFlq_rdpH zom|IWf2xD<7ZnHPw%MGS(>!YS?enLdm}qF8=;*u- zy2R*WnKpu%?C;;ii+{>d@{?^>M3zsw)fIs{UC>(;c+e8KS!snS6Gqt|isa%}UX9OyG{Ob2UnYmsBZUnY=5c+9Mj?OX`YJB}+J405V|99Z6|iwMwP< z9q;w%YNk4IFW0xCbQ0Kk5@`2zn%Uuq2Zh}L)T>vmq6DP#qzo$nXzs%{ecV`^yXmn& zwH;GMW|Q1sEWeIA3ov$w?=ZK}LovY)NtHb;RraVD7D&E?tQW}6h(FK5seo{*MK4UV zwCI};Nwd{n^bH*mP#u~8_Z30&l&(A>XmY1R(s&O@*LYD1GulD2woB(&Ew9PsYIe{1 zJ~sV5%@J`Rvl7#C@IjKil3IVx#)pC3N)zkLE z4#iY2dDJRuX_>UqgB?;pu8d+MS?mtHxVuVgE(YQ>+@f^m%$ZXwj-}b&=hh3l`RyvX zzPJJ=2ADhzOt7z3l4ijk*yif1Q-O8e_ns*>~n2N zp2r*{It2YQRV4+_Y9pm#GHhdMA;5e|!`C^DXg z{SR*fnUFUHrRc#pP>*0#38*Iow^Jym0_v+0`mcvTm1-D$bGj7-t~Msu;v&&~GX481n@9iNUfon3OVwfG=gO7Kmp}pogagO0 zv{IOe#tw;I{75#=g+8?K>~;A9T`_b``FKPom%jo4n54t_^%0^u(zs=mJNbPn7^Rdv z!a>#!@CLTJDYA6|Y?^iJ<_%Wmz7lqS)pAy|@_kmLQW>i)4_VPWZu1AIf5wfxRK7f* z)gVC?w`V#M$$S3N@>suXeU;zz_v2?5J%E_=-re+2CRpGL`%S_2zkKBuPgxJFy# z_!x_v9B+}+NNu6+9CQg9ryJ1p?Hl@iPRKkfWWFk*rR+<>^Kl{bsPKJAI>G@Vb00J+ zWbV~7GdK>UUpysUV`@z+DH@$6z`pRfK)*7KTG%316Ic|dcMCaYoH>Q?{$YSuuxq94@3dUBoC*FL}N z-LG7BI@UmCD93Nst9d|osUx>3`)Qoa%ULh=Kn>qEdO(wT9^k4PiM#L=u6(d|6+KaR z*0zz#)T&nAMRw?tQtxntP7V>;Rf8Um(4r>}?Xj`_+Sa)O=5|0RkbAcfg<1Ej#e28cFsT;A?5la4LwdHdNyEBZ4RI#A zXP_K_HS|In-G^iH^2?Qnu_Jw{lNYwFx7}LYh?&bv=T7rEs0bgfL|JB@B(r#4+_6Ot zsi!qsw!_8_SBeR}A^?gZ&a>{-Tw(6O9G(|64``oUR`=Ja3emexk;Vt4k3IX|?WkO- zl3Kh{$>PO*3<)K-TDkJper$IeOXR}%8XEbP2lZ*GnY1-H@KIe2+#+;%XxZQfUQ@jTI7{9EA!S0Tl3B9`a5fj zzj)cQpO_@PiDh3LZrS#YwnslYEIa1EFI#~QuZyo;XF%l?5|QErJv=Yto(QyQwXO8# z{+9N}D!Wr^HdFD6DWf=OL)GNV!4_Lbp4iasL{S6kT%a}uV+KuSgB(3_z?dvqMAuKf z^Ugc%G7`7mp*zE)j3hIbbBn6}R*{Mn_V_Y9oGpAuVT+NrAT#qh5@m&XtX9{VqU_;@ zkqh@0%TC{iNFXP+{HBjk>VcY-JT-2JM)^;}?BD?!yLJgV@whl~OusfZAA)`{q+Q=v>Cu4!&61BHd=r*fd(5lW@Va&#;l-&;%3;ZbYZxSkcc{T5e;KqRll zvKy?;*t53yba9ow z=j#8}yb=`$)(a-ViN`tzWddNy!1LJ+o_d$|}k zf;a>f!5Aox2?*wUV%17Zz43aPVj3ORUt!H3VISk0A=SV;6u7|AA?bGk{P5KTew>=3 ztX3_WD!0ybduYl;o1@WCCM`RBRo=mJRV|GnHP+C{Lz83nm~yoY8$8gBCl;2b4*_tf zvwpq0a>VttS<|O_2xYGxT}92ost6#=v6hZMC&g=#=F|;(2ZiV*2&-yUE4xjO2cTTZ zd#vrKZX!sTILR=CmO>Z`EYV#O!h+!4ho{?5fBhZ+E#)5#dz||IBYX4bF9U#OI`I7m zmgQKQhMz`T(+irR;DG%4&tELhKEd>vURL4AJo`gVxB!sz-ajBCrkh1yNCG6!#ml-O z0A%US11#;rDl4iAVO=1+77V^s(fiXwQ`H1iJFHMtbh%~IS}lq&%AQs4Ubbw3_js04 zYziQc9*hI>PMZWEGvBTC$pIx?7vd}p;G_c0+XPXLvXCv5NGW_QVL}(44;ldxOjJnw zsIVM&Vim#q^?r|Fg;pm;m7_fGT}XcqW+2EoIzw?Cm^E>N%(HOeLd%vdn@jeq<$p(f zQbG<)A4LMCG&v-PbO4=Bkg6tNKv^a|u!f-$?hm)?I&09a%ss`u*E*I}3hQe?zdk;y z|EMz6u3War(k6`6ON-BR4s?P{rgSb_y4YGaZ)y)uOS2(LS;CZd`U^H5PxP>~$?Pdy zRt6_7%skWrHCIwC+Pa0JkJMSnpE|I6H=D3@vW@hk~kh>P0z0n%4Ygn zqtZEcj|DkaGg;{0(yYd!qqY)s!JZU zwOU$^gR!qhnrlyYbu{Wzkqv$1JKwTton^_KMMG|N?9De`cRr$W5zq;G^f|Ix%t}}U zly@pDr7$u|y1zRnKp5!KpCe0k=b{!tEo6qMEG#75Eb2%V6nKwR{T3?}u)L15_|?vr z;5vS_v?sfnrn*+k4(O=>2g`#k7ylpFyvhw4RLKN$=G?#gdF$1#fnsl)Tc1u%t!Mkj zHb67iDwZwfs-oXs4kC;R+~&4j!33(}suzX9!F4=FIfi!17Xk$%}?$LC{it z6UL3PHmzG)Z%vbASOTpa*AogURYO%Ft=6qwW1Tv*_54t?l>P>o-Kp6G+`~n;&pQB! zR4m=tbxA#iJ9s7QZX9dUuz|hv8jC-^qL8aYnnwGq?S6f?B>0*Ds4F#4gg?e3Tmh;; zx=S*4dtb}GbBJC1`KthYS)TalC2668lz?>FZj^ z2l`Aw=BGR}*k-=&PEL%<`4*J^Z2niZ30x~1O=qU zSubwv1S|RQEGsr}h}x1^652Evw4*))(F}bmzD0T`!W?b1_~4;dV*0~&=g2X3ljbtHAB|A@|hr1NgKIJ@MN0P`@_tcy1!9LAx-1nO#dyTXctv@fYOo**n@^`r+d^Ft>d5hTtx!o?RP< z_J_ZGYb{T%GE`9h{qolz_SvuB2WN|AfUT5UH-g+@ln&c_w+yt2=U3Q`%0z@gNL(e3 zF>DO)p7HNQ5$n;ti;NsC#5tg^4b&e&G{_a&E`ziWVJkUbqP)C;AAfBR=hC|g7OC$NTaW{;F~t21o|oh7TYgo|FMhC_1nB(vG*@2joDSG{rUJcjs4El} ziB#Ty)E?B+YX4?du&h>tmC#Of5`AI4T9uQGqlD}a_%(w|vl!XhhWBczOj8{U!w84b zj4^%eetEv=$FN^AXrb}cxM2iH05gecNJ!JJO)EuP_pmlHY?!cKumJrRP6$REhb#OB zp+=!39YHV1V7M4{^=B;)WJRC+sk#uaHn0@)Y*|uWWDjWHwgm_Hg{l9n?@M;1rkaOP5 zGVJ^_8NeG6cuz=O4OsOV+4hkalE54N>CfNo^WWk;9F3jZZks=TB`95H-g{D1w@Fcj zasLnKmfGCkhl=`k>u3*8ouKH)c5Ysd8#UZjOrUw&t-BeeF$46}T{O02?TUSpjM>!Mvyl#kU;Oehrle zgtb2V)(YxaA+@qgHz@+B4{2aMS9pgz)DBf%JY@BB#r;43WjEh<-5%&{4r9`>&P5U+Mv(A-VOyqA z7gxcwIGV_)cSy<)8LKv}SY{iKY_<^&SZT2T23YK!9epgvu3`4xFPcZ9inc7vK0GeK ziVJtjaDQQ_8y?y>_Vv z8&?cUZR+o?_z?qoTa1zROyuWF)7o2fXYY)(ug`ZOqr{di8*H*VBg7H|pVzmP5|yx| zLV(6qf^q`}TE+3>?Y>^U1MuqjUHoau7r=ZMfBsv`uWKLMi)|T|FF$6Cl^r<9is*c? zB1J5QzbXoRiz?#Be`WPwde0(y#nPR$ru5jccHhupRz&01gwQ%)XW>g4%H@wC9XOqw zR}W+oN+4%_QDqzf;;4%_klR`x$f@6N^mB|eP~X}+Z2lX zTa?Dz{hWeA>C#FS8J9#cjLaNJ3X+)dmDCo5L5&4povIkzrp}n|YtkJsq+%$lDR+tA z?i6F)Eoh`cs8Khvv=c*#y*wF;&X?-dcc?y#h*v>h0Jow7pKu!Bv6$joIUIv6a}d?m`|M*%V z&HvS(Qm`ve_0hfC19VYHqi!lChrLJnYe6vkNhLMPIc!ir?>jux?fOi?)8i3JYA26H z3Ospk=!4E$)vF89r?oox$M)fcSM2x;&-(~w!uts-@qW77Np=k0arb`8^SPt9l{r2~ zPNTm9T&4UfwC(=tO*{SLCvmsaDZO2`lT#FkH^!R2xiK*3GmU*`msDEaY5PFirSeX) z1?R~vfd4lQ}m(z^fNcU8=LRcS2_*M!U`Cp>ETd8RUzzA@h#NK7>g?1HWSWG=Ql;UaZWDc>&mIKgc zfJva3$$e6wFOI-8;FmQWheZP%N+k<%C?ZTBIL}}j6*_Tnw{kqTaTh!qCfX*$l8m&n z+#KFr$DyFlSF-N{TQvehGR8li(R1=qYKjY^-oE|uGsR*(=u@3s$_ryJDchN^FaPuB zvKI8Gxq%3A?&lM~Q()_t^hWmQw`xHZ%VK|imq>Zb^Ss9OY!}!mv_UvfIvHt}mzH7X z14%v~m60|}DM6-6)XdqaAf&I>$|R~0_}{l`yxN10ga#0((ZO(JD6*@Mbw0P&ou7gK z{ha2$6h0@p@v_{VFHNwP?>-%%G4oN47G*i0F?NjrMfMJ{gWtXzVDGBM*!DYR`6sX^ ztm7|W1jzmGwGHu1z)@?tD+ej0e&o;rHdE`owrbJLO^sA)hEL8;%>>TLAl(T{iz84a z+O%n5$3yRXoDru3vCJ@DfU$taib@@d0hdW&E0W;36nKt9Fj^p0Q54;>i6f1x@VNTr zStxs{%oWNGp%hMn1(07|Lz!FX(B2(Ntf_C5@!h{mGaJ#TjT_*OGNmR8q+$@a5}+*f zV+JTgLXet^Z1%p^Oz$3^Y>VW@#l`M@3y>WXIg}~ zjMp{#tw6Yn7gyVkA1>I<=i4W`+;B;8;wpQ`Jdt5stFoO{wY9Jg53Yf4!z)HF!Hup7>%;1%kH9YZ^ zFXiq16%^^u<-05_uEu@AdtgDku9p(B97lW>p~9fGMu)DWj=A1_nO-=`Aw1C@sF9a= zA{vK`$6tN)j%f6I`~JW0+S{j&*@=&i2Qx+q$ylZ!BH|vQA|Ip{H4z)B(B0?(0g@0j z1^mP!`jIDcWVB^JnP%Buo+JWPz{M;2BfRa6c<9iD85TJ|O|TR>zN(QQ&YvbYSRq8G zv^}W+jU%#h6x0?YPN_~1M3e-^(-%}e%G-UjUTWUI^Mit9gQtN;McTl z5*%yUyJ$PRonp1D8tC5Uc5j()S{q^q;~m$ytIW6>tiL zE_k{UBmzB?KfY7@w$`p`GaEc-lqT`7SHN2}rA}$0IT>7jDdQ5?C3dD@OB*Y1U0bznvg$^muEf#%ihUE`J-oijkg~Ek_n6D^^NcfJP z)cg!W-VW=o3iAvC+T#Q0^cDut38yE4(A1g=9_nXP6+Bc`9?8Z+Tn9PNx^?O3&MjY) z*k@RJ5A_7G2}M%KrEwZ7`26+P&-lPEt8!PWP}XCG$}3)oun><5lCL?9oy=v49MT|3 z#R_F~Mwu`)m>0WO!NjpLiV^Zap{xWH-4~A`B1nknq4J`!drID|Kb60yRB?-z)?R7t zq){YW+0vzSuM&z4zuT{ED@+np#E>JAL6YtV0_h%S&V((KbK#;zmL*FTBQ%%*Wnx6x zC$t@peX3X!y)ksJJ0f+=F_f541xNq}BnB!02ggF(hFA+R33?Nl^rTlVvm=RP!5)`I z!~6IXGeMX6bj&dZnMu) zR!4B+RL5Y#(vupKno`|LZ|LiTmbI%^R#uE=(nxAsUuD^Npw9j7Fh^U#^AJjM>IQ#@ zPr%Z?GlJTN8U@4{W~H=>pT-=zlBRoWwz;#cq$mqr`8spBShTnSAG z_?$bR)1re9Ru#jDsT7s|`rbGLj)B2lp^ey?y~3#HOc6Kcqb%vlqBC2*>5 zq&ugxp3e#h$86$&6av#lwnOla1gLeh5ZK|d5T2-)oCD}#r{H1t*Q%+|qVqE5zm$}J z+uo9NKl#zgK)N%>Vo^gG7z%6*b3cS(M$VctvJZ(h0n>3ns-W|i72+$I?Nff3+`~j4 zKq^p*G5Jq>Mf?zxESMD(&i~<3=Kma1v@v-j4idMHV3$IXOqI-FCO_NcYF2V>FPr=6 z7F#fDs?Sl~{`4CA=F^L|ZS#6hYKy}a=N>qOIePZ&Y6tf3)ktxFXA!D|s%neXqbb74 zejwaD7(Vj%+-+B|hXsUD12Vl?bk_tTCD}aKLr-&~=SoUq=maUYMF5#0e;XXC9CR|v~tC=xV^`#T+<2^x(%CUYL%x6=l9YbxWYt&dcW>EGTS9@|&p z$_l}kiWpAW2x-)f9tn9zSw^`X;>r@HbGu_iJoz--|C;Ck3)RzI=g3 zcg8AmAs9$*)4I8^dDyXu6MQmI%mjOaun>naNX}y^6Ic=w-RKsSLWd4pf4-j0bJK`B z%6xO2C;dvPz3`$3#9a|0FjTZ?ar#Wg@$y7aT)K0zTNsy_lcC2Ey<7T_<0uV1jvLs~ zW{&UYYg4;ZNNfpHqGIAfM4-cz=}7dcP$98}XmrUUtbn;gPOa7h_aGv+zUsAWdD zI-PITB5`1&$Wwb1{&h z#Pcu+n4!BIO_%v`kS6ngNpLx_vXxS*5u8PRx@sVJ@;FT>>0u;!8mQ1M>|JVtFQ&Sg z;YU{fELkq|WEJPno^g-0o9LP~?!>7wKr-1Oi3?rANzU5mgePsxK9RV|f?sTe#jP6C)1K4MIGI(cF`-DI6+qLENxd_^S(=_zoov+i29BQ|!p zPn}%+*drbbTSDZA4hM9od6tOSrsc<`Oq*a^w`{Q3#IeqSGmoKxpe7Gu3hP=wP&s?vAb)@Su>H0~uaKdh1ZhFZ}cJ%jioJ%v>` z9iBkbuME;X$k$ZZaxyLR&NglAt|3FLsG^Wk)zXBG+~~epvX}}|c zV=2>u1q&@DC6irwWiGoimy(!WskwAnuU33JJ_q}_CI-iAyI*_YF_RJwJPu70A`An8#*pb_i^ zUYNYoHM=$p5-AKTZ;?mpO4k!*trM9hGDJ$wLTi}LA))$|UyaKkn@Oq=0+qSskgN1c zPhQi^HB8{kQ72B!eFZ7G#wnPS$Skyo+^;Fx4ihMVQ?jg*`;UylV=LIb>v{)?6y$k! z4~fu#$Bt%$K+*7!(R}SaTDa%1R&<@FafA-aGsxFdTa*W@fs_x36d_L>B4I~0-v8X{ zYE-21nG5a-B&LyjheU`iFSJ&B^@3kl#^5pQmLxqW*LVH z17?jmOnK%Ghg=PEsfJMcL#8pX>c&o1u*9zrcDx0s1g`+z@p@S(|2cz(6_#e}AoZKw zo{;jAabCnpIGB9GZ!V?D05hM=vI%9SioUpGo1K68xR$8gWji;mvu!UwXTv{xQaMD+ z1xdwLh`vZF29=S(j&!ET-sEY&?s1A6`H8GGGIoFM`HI%f|W6CRSUJsk8VaX{huxs zD;Y4t_%Es}FpMztt1C8+@FHU4Ql%&tRQCy~mo{+X)g98nbxy*Is=j#GJiJJWLT)Zs z&I(9VNT%Heno^k#PAAht!34HAnI@)DUWJh~q`Ri)D}-}cuhuqHf8z&t@d<3uDRII7 zX2iQvA)q*Tz!p0Z@R`n#**O-9erS*m8(zQ`LZHr}NA?}U5rFP{SwQKfK;|AkOrFZa z9H)MDaA*2YDXot z5b5t&73E>)L#{+wLWkr+Iv{E!uYwHon5SEUZhbGmrw#+p&}WEHu#Tu_P6mV>(x{_U z{bQ|AN`E1(G|ACN-)Hx%>0#5}U2BcBs$Iu+trcV_53at2Rcg?5QiarDe1e9lU;jaS z_+c#xpv8R2_(h#1$TTka(Mp|6UGU#y6(^=ym3fa^`O)Ki;D|vf%EYklBd7_!cX=`G zg@fkhMvSt`bLUz4w8~@L&5&P zjCU#sE;+g*oMxH(fI4dL_6=;Hrdjsuj7i_d9#X*Z{nabDb02;5Qj~(wWU#qT>IilF z{0hziPO20spIjDbg~4h7&aZV$CNXD5a-|q*Y=HA*WTqQv=pwAzf?!1CU$5nVYIJL8 z0XQ1pig1!X=Rv#+oy=%s!M8n`J`x*jHBc^pD*oWL>bSmJ5l4A*XF&(^B2Gk*T^4@ z4+cO|gAPhx6xEX&Wu;Z9Ner8SI-A*vxE1ek1Cv?sG2Nw#yGx>mNFy}W;>C*xHhu&| z#weW0eWDulC?Z)`MD6Ag91$QG>?NW)vii`vj=OIF3KpRj);p4uJ~3kNL+;FMXPhVS zCWT>c%=Fdg&`JrXeC}h)%{Hn}Yq#B*Z$7%8RzVon&54p=H`EH%pWEC{=S;_)@PvS7IUr1UlS& zco*4+r1X40;OS99PQW7MI69o^wf&lw<_?IiC_5qAaL!ReK_fL_l$9 zoQU#dii@wtaZPx~Ldv{Vp3n;p7`b}dvN}pgyna(|msOjo@EwXi*RNY;O5dU)vHz%!(kK}H&n-&!q+jxm-)0d4 zeA4`9A+(H77O5RiN~nu804sqvDpq->cSnNZzQJb4R;{G1Bq@+-J< zr0(E%Dkn=?cjgI$?zPAO3F+P?EYhR66-;};#(uHh2JM<@@-g}374LLe`B*9w%N6J_ z;K#8HQZcVfMY))mJ4+1DqjTrjbPch@Mh&!4gA^(`Q0ry(?P5dvcDA8?I@_S09c)04 z_DU(($p-f7V1s&f^xtd;>UgYgSM`8LfA_YQqrVnQ;m|-`*I!2m^l0Z>j!~*l z*VfisF+iN-0*=S}bWyKknH9fJpU$l;OJ9{^b@Cu~M;ZJ)cIT>$_G|he^x^&3ug!f% z7xwGe{vB-QxPC%hkY~%0CPpIV1@r~l5`)l=GJ4%)P9^xt`==WT4m?i_?%8QBr&z#V zap$wDnW_ej+$Y@kJ7f*zWwJ?tIg6>wo%B@A(4nWpcloc$XJs2yv9!0Iw6rfb*^rM` z+K`V|TAz29Sg&^$*`QBWS+9$Wtj~K(eZQxU4ftq<4ftfG^}M*)27UU3_4{bK^-}r4 zTFM~S=YwT-9ecgrTVnk`Ug2kZ=&FIbQ=j*jC9dkFt9$!hS6Yv^7g|4EI8b-)@zw$x z_~CNvuX6+5S!xUa-e)~lk9YrUSB%q%GqUsa(06?Z{AqT z3%~BOoVMle}@4-RXsK(bZ}3~SY-o(GP#Xry4V zcn}%;1b-1g#+GuNW81Q^_H~|sv1Sbvc&2><$C~KR1JD$NM$i}mW-$(Aj^7{D?xf}Ln<@Qg4N93Zn4S0R~S6`R+xhNC-J1N|*Kyw*0K+hMII_p~kNcG|*y ztE~M)eQo!Lhit^kN!EYiXxsDAA?q-`pH1F8$F{w>%NmdEr0dq$@*_`KqcI(9>l-_4 z{MzX@b;~1m>}#zxIcKmveq^ofdVim_o!Z-;dwaL7I<=#c~NR7R>2H5)4|_gs_^+dEw0mox7w4iSn&94&GcnTu#GB-Moo9Hb}55WKgl zo8O|pP)c)-vPj`cse0Kf3+gTSg%l32=1X`>MhyMDs4U}fi5nDwvWMZC!Jx>$M=sm; zO>0}%)(xyntNPZVd0p$;rlFNppc^JG${rI46UrX2bY(B7AV!675Rv=*>9s3u)0*YB zVf8YtJ+j*4$HOI}s7z-AhuY=1W2#iHXlqw4wRNlbTW0H?2rg^hw2`Bmw(-&tS|cv2 zbu1vxcrc|tDDWW$w8A+rS)9HTAQWXWNIt-Vha_;!m**NSCYamiKdkk^*FI&pYZmwO z8`j(GNomRuQP^I3agViXsL8jLtJ=#7hADAJG3(#8tL@pk+45;!@dY!c+Y+TyxK8`{ zxx2K|Om_`ejTXRV%sJ za&tonZxJ^a|Aua+>smv zkoj0OFO(Yu!Y1^cM(yhnZXXFcs&R zn{95NY7@>@!>!`z#M~8$f=(J7tTSpx#=P%8eOoT{A2kQ&+h9(N{bo-ro$tP?utL4E z6MmCxuf5KiY5uhmN}Bzl`CQDl(abL;q4b$rO!o0Bl1v-$%H6I2uY4`6g1!aAP(xu& z@Ol{@n>ih+sTt3dhvJtno^P+7JnX*f1ABHTg1T~p40_$j=)F!Fc`xLw_gOepPR;4U=HJ!V+anAV&b^%p)J3;Pnbg}#$ZTh z5X%l{D2b-)Q5AVSj7PsXnjt_qu)dj%JLW z+W)L&I&*l3jTV;Y2G9Q z&Xcdo$jVo8$`vxzTmrXhN5`!sR5ETUOB)Bqc${?$^BPaBdfdLye2B7T%Ghb8HajL{ zRj5$jK79L}hjF!N-qhZI^EK7#J}y}>SILny1pLoWehtisA`cmOPZXo^6@{>7 zdG*|2)un!%YrV8&#tX`jI9Iu}4;?@+1RL|HeBv!N^ZTc+w3*@1+|0I7rr}t@E8YwA;oFkfVBNSD%qc;MufMy{vkrvOXJ; zt{ytA`FviH>YyTNc0^SrHSBxmPTA2t&)BZ5Yi!T6>ulfi8?2>tX@V}?FXL-iFzw*e zcg|`FlMS|g^OGvAT>2YVX~s`!Z+Ef4b8BeSfuVq0E)>4--gl7-_H31ymW)bJs;`}t?|F4x$mwX1Eh$co;{ zc`|VH@6*$M{^nDwT&beqHqTBRdeI?#Tr((FE?uBlguCpci{~XB23YM{HSFvEzHiO- z%_N!Oy?H~3k=mo?5`C`%zc`9=30T1=v_EiQ9~(1fn04*k!8*2Y>%5WhD24;g3M<1e zjT;ftEMBUl6<0J((T*MM_67~T69iUm5V-@WLhAFV2Kf!$D=mfK&SuT+j`r>C_9im4 z^v39R8De(;qtmWHELFgVp0&NRK?5t&zMb8!T(kvLlZ1A=2?I!VpMQZQ277X7Sv&<> z5z<`sXj{*R@p^X*atKWw+0!A(I0}#qRMKFg13Ed>iC#fJKoJ0vubntx)6&Kn>jXYD zX}mo=Wr8OmrUOteq|M|l3$nIv)6z~I-s8(nP13b27&R?6#_lU!A{fk4({N3^&&3r~ zhhV$#czDkMxWo(q+&}{eG=lUY#bnsh?8)y&vyo_^gd`)~oA6l1RnZlQO6R+A?E*H= z-&3lT5zj^)z=dU``0x&`wTu?!N|q?0)t*{9FO^f!N^LD@fkdybMI0(fwTvVLpKS%O+jsO7ymjXMnm|^$ZX0Gl4_!xo$Z1q(Ski{ z4#3J5pn4?+1AqF}v`J&I^JG_OZh$!%l_6#`+FHr#L6W`-P*wE+6%YqWGXR;ti^JZp%cEYI2%!4)R|8L&kgIqG&jL;%{6lB~Q_65xhj_eu@csV_PfjLkNhQL&B&!7B zm6#9E0_r{-n+(uo?bP*BR07F?%Jb%1^$i=X;*42}$q5FlfgnH*2OQJbx!jLxr{av6 zR&CvStF&;j6%o{nNNWv-x|JqFcW@}@#*e@io>oI8D#X&Pnx0d6*>WqQh`>9<)pP)C zGRiir8-!FO<;nAo++y5C(0RPVJ;Z$ayL!C}q5Kju4t`(RoTLlz-&#p&sf#bNBGjNW!qNejH8fWMFXcmh(fhYx zDK0B$S-CUd0A?^>cvZ-bK4zHJJ8Zlz9H^Io(w~?!gl;lp@{K&mK^NcBId~?3qw{z- zx;*SYyl>b!lEr%l!#-;wo=0Dn9?uixXaTUEzvXi0R{aX0SybuFit6b_^^7pSf*F!& z{O|yv^iZH2MRn^t^!m)KAn_3yu0s4#-tz`YDNn+nf^!)P7nYFb-NTsIp%!gd~=$u3fXbT+v#O zOjr!NHD%M$3l6EP5yOVcy;I*av0|Z=yRVGU%aT=biu6W^(1hNYeuqe^-oqXB0i;46 z0!~08WIKnWUOSy5{cbk_B47vPV4?&JwI6Vv03b#TKaa9BKe8d2RRJdV^82WYI1l6l zNHZ}uogahG*L!EluWn5xqIpp|FeTzr$4A;cEq+cE1g3ydRb1_Nb7)>NIF8kx6zLNW zz7VH*+NvP%2c$({GUqjiR1~@cFlii*hFJ6hDTrea*LB$}|5T8v#qkBl#lv}^3@xWl z4y0Xp2NH(#i}7(O}>UrVGBFkIfc#dNh74fO&IfXwlT+ zo`W1K3E3S7LjqV1Pe}}VMHQK`&E#o+WY$AATwa#a3cV-&^#28{43@dW$|=y(@bfMi zFs7CXFm@^B1$g2EfG8~no@hyqu@5$4d~*~R1InU5>?$zi7;~}TAef$nE z7D)5(y*S1>R|RjtR$}!}CQg>q)WhOMCDCtC+-05|mOoEUyYcE=cK7Xt>@Jzdcd4oG zQi6FV#vsdF@f7+)*&HI?Ne{C;DTtAH)J;7Um+&Ktw`bxG;! zWJq%1xIXeBShVGU)|&d^+fVGPPu|v&ENg7^g0*(X;5Bwb$4BkPPLEol9*eEcjGZ=r z=`vd|XNnE#-O(0mOKq{VYDjm%$hj+lYLeEB6A%#Merjl3bOdUsrFq=M7bod2UNC-ce4H(jJ;ng9? zc&fi>W*Ur=oC)8>f$3Ax0H?Dc@=>@1=6+q2vJPVECK>`TMq~LT?;F*UJVGQ#7QvZwD*J zX!P&_Vvs%x`skv?5qc>1ba(6DudDJ;lMTFwtVNu#U96wZ_a*K~=LhQi&_TU5`=O(s z@2%J)&h=N>o{AjmqvL%Pb2Nz)Sq3P2X@Gta2mvzrlDv8H?9Uvgus|hjq`YE({PBnR z!l7B0ELmc?b6pwCNR-Cr8CKMT`B)c~>_n+l#DbclfaM6A4Mm1!r&-tjS0$AFS!>v_ z&fTxyeXMl5(-Ra4)EuCf^HPjD{`}gN-Wl|D-IP6goO1S$96iK_ z3T*uavR(p9H{GLC=N8t!eG_Zfu8Fm2+sNALueIVJ_}!~pd+XM@wY6^D(2rBDV~3{J zfxq@mEyjT>+O<=Pt2T;E(p7C#vRkLt>JExZQdC82{k3XY-&*RgMT-Y5*0M!Ci*Y0? zdmL`7%kERwpzAcm2R?B<$=KbWS*{xmjc5T{v37&{^|YG6w*fYbEKqLUY}vA@SbUul zDVt#sIIzsXnnEXc3EPdWi*OB~ef!B<8aVr23Cz9;#=2GitCl>Lz$fiTJA%{jdc=DR zWz+WY@!vH*{#!f~rAFC@DZe>ADJ;v@l|{#iV?g8ylAsR9awJj4t#L5vq^dH=dB>!C zAJYfZxjv-ROQiYb?pX!DamA8150S`|9IHZ#TkHO6H~I(a6tBmvoyEn}A>cWW2;%r@ zO;IHU=Py70S0d+G8@A<~mY)^EAW(6su zJ*Ee}x!R&9Gja6>u@X~G^5)HBlkzCDlm5$Nneu4~Eo^ANLxL5d zG-}yt>1tdXsB-9y?&eU-b3K6JIHg_BiMNy!rP?P@BLm`eIj(ZZatPL+7bue4Dw3eR zOzd%o(A^ya(=Magar_nbr|VaUJ)WMd2ZVC_^;1WLy+1u^>wB*svn9tqwPKHdV+Civ zWjD`y+isovp*7IDsYhQsC;jGG+wt_1_T|SHY{9%)-l0S6Q5T`*!uypkU)B~boa+g! zs!D&aTB)2>(Y9LUa=u?xxzb`Byo_w_oC!-*u29x0moK9=m+!S$CGF&@q9fdcZFs%! z>+(t}Majw)lyB`mt-`1!6}hN_hJiWGevBU}K}q>8Il_<3tTBs-1d|XQlNcnsb590_ z6UL8L#qjSRo5d#O%g;ZwPd<9f{{APP-#7;=vAp@_tM-}BEL*m~uFRQ3IwC0mW%#Pw z;m-kRNFyo*D8<0XW%z~w2R~>=WDMY;bPUvAhWW>m7c>;t(V&TY@FR2Bq%a$2C>`Un zD9?5Mfy0ha(O}$HqQYQ;_Da4bFM_y6h=R(*m5LoeOAQG2KS{!#(ww^#!>+Yz{V0ig zZsMHitFH4nV9O(1BZzN37%j>R@e&UETLRkrcaxhhql1hYG1L}4Hb+a9&$9VilWoEL z$E@yy^)3I6((nr^EBM{TZQAr1IzG?lYi)`}k3C|`6r$8g$qLc65=v(ry13z~`j#@f z&%E+dVs=e179RH{W^*?DOlkM3f345j-~V@Fb%&VA_!HcvgsIuEg^bymXSm9_5MLTb=UKM1xm3qp52mq3LSj zmhPJV`N4be1U}KFJWp18g+0u_GYTcpVxCksisyu|h8SaXm#4}c%_k0mc37^Ph9pHi zAf>vHhF*)@Qj@?m!8Ja&f|TVM9O9lk&3!^X)fFcX$RnArgH!LA#!hw*))2bFaqGbK z6HFz%U8)hI;y6HvJmRsQ?kbaqYv>H$>KX?C&Bk6R{peH~$G5eTz0y^j)LGbxsFQ+PHi3@8aXJ)a52~m)5Y7FA{=)lD<`L;rK|HrXh-j|hy`VsF$Q}9Z zl@iBYfH{u(jkskd_Sk`BIpbe^C3_s@Y@m-8v>DT<$slR#xC>=EBE?t26XJ*M%fR7cdUW`o^qnLwU1BekP@d2+N& zVLT;YOr6H4g3Onq4Jm#N1Jt0+S6NVut^FZ;0re*9(Yb@bc&mp2b?w;JL0!FSWoxT| zZ^)-h`_@*sR!xtWhLG?R0ut(-H=rQ^FAbLlmnwUFA&UgbHNQkm>c7iK+@eI#v5VY41v2fHQ1i*O+3fURE~Er#G+Fux}@C5D-T1B!uNC z$kiwf$aVjDHZrN)2?weQU^M4D7+*CHCSf~|WDgJwcs?z^XW&!|NTZ<6P-%h5K-Ia%$&RWSuTC%& z0&%yB3XY%#gmGop?yU?n(yU+=|~-%;r8c!RfbNof{Soe-CHQ}&}4eQ@cy`YJZjCRdnA9WO%N3M%XyFuMmvq3!|V=}*T1kB3} zkwCWq`k*&NvVVjsm*ccL-6P(EsdBzAksQ%69O00c$n*a=dk^rcil7bnoSTH+A#_sc zU3wGgMHB@E6e&_H2o@B?LiHx}j-Y^|NDYBN8ZDHB-bGP*7wNq!*7@Ie_U^q2@_qmR z{dt~~bM86Y_ubi<+1Xi+hz~w^2aA9egoh=pO-TSn1vSN7LE77ir;sXwt=~U7uE1&# z5M2e~%hs*}N`EHmq7M8&}6m z+S&w3OG%Wpb;**pVWp&PTqRpUSBDS%L=~w-g3f^BNLfMj2wXFB5u{dNdZc|H0jV~y zlFt8u8Nh^Nm;qFGJhLpLR27xBRFz#s%Z8j>IMqTAzXlO0cwQ)(8S?ZFvQ|4~fp#d%P@d zT4K2j^9fBU*|4lQN6HwY4vNl53FQ+#vZv=lEp;`RG+^d;OI_{2X11(~trDxJzj4=w zdNTbR8t2DreQT)^o8rNWyeQnr0OdY5iJC$9a;oJ<}RMd7L@k+wv$1BoJ z--Tp6S$^szm^Mw(c(5LK+0o*FM>3Fgqd66)MsCca?Ya4mXRvnaaw!`Ztc~Fd58e8)!VbP^Y5|x~*(>=%hOIYXL87VF*X#98y%3 zpHLx6|HQ4&Pa9%XfH7{9O@Z@ABkR_a;vfUIS;#d#_lO%n@(CXN8)dNIlfR?Ffn&69 zn0WYP`O-j-=uF8-DOI4gP@S5~e-I-lDCEmv*vVg4KBf^Z!UbxqMd@zq~v$Swlqe zeP;8%imG%818TU*!;%m(+bHJi;WWz!-lO@T;=ir6A+F{t$D1X#>=Ztm@ke57Y_=%6 zCCk`P^BljZtvZxOjQ`$Wdvw5$pL#h@8IyP|ZEE zFrL){R6xZVee<0LZ@FWSltW%L7gsmwAtVAc3#MW}JWxJS%H=zPty;K z5o}OL<}*MxHG;y;sH8A*NG*9}XhTe7qY4}7IXf!c-7EF)`6Do7A;2(ie1Y6)~PE!LIPlBux?%izpk zi#o>FCe?P+dg*pNmV@8895`(Fr}91AYf_TsNw%EX*!UUQO|y+s1*Ty2E3U4l(i~m5o$xNRhzLa0&yfD0T*j+q%#RllY)Vp-$*GFQD^m|+>v5jr}^Akab5~; zuV@R{Sd#KN_!q5pR9G0w#J1BX@OwV`hBs^-*4+OU7{VOHS4Nt~FaO-)>w%02Vw-6z zn(+9=H<5@(c7&{vvSyk1WZw`!rjHCJmE<{E21Zso%Ln#t2CftRskvituc9bekWnl@5+1XQzohkI6g;vhspR+pXr(_58WY*bjE!IZk&v@ANbw>RD@5& zBJYhF)W#N(nu;&-kA}kzEbWqeAq{yFH26svR`QfTZZ6}VW@3lz5osQuSqI{bzgayq zGjK}bC}i_;WU9QE)rdvD#zA<$ScEieM+DlEZ#?|Tp{hzf=987cBa77u#8Wv)=tT(; zyI`b}5Fnrl(7~fa_~c)SQ5YLe$rqi;DE?HVVF{{Ep-f%1RGHWf?3i{q zwX`GL7w`xL&ewk0s7xZ*MI7fr+$kM2Q*}kS3gh|aW_Oa=2TE9}iYyli&PN0K%bm+- zjg^6Q z(Z*F*5+s{C#RGmMiDn2y!a#^-nt_Ap6>(~gZipa>ojU5MN{Wa2TPUfUXFa&vzX`|n z&(*}7!i!F5bU9P`KZPCqo&u1#80dMpfDSN&mez3#goT+_$`CcS(kOPS!bR(*8*D6G z7$-d+Xd%Y$%J#W@(v+E$qJr%}R*3BrSkqC|I1D|CAywDP2Q%4{c`_15pvC!>;SIgx z6V)(0edPYtbMnvKE7H7KW1V!B;Zr;XD4T03o4)c`8ppc^&qVmW-mQbY*}bEbME7xK zWsx~LRP&gHZ=z^<@YgLlcVv%jUl%9q;^#|Z>^G{lS4FoH9~M=?=Bu_Xx_NJDo=?)w z`d`o)@F=ZB32ba_;Owk8->_^P>C8t%pv>W6;R-i$jkRjlFgqGpaXlfY3M4R+Gb4%N z!LWHeG(ugLx|}J=wCJxKO6wpqn|(Fh0%5qmiWRBTF}_~dOWZ1|V+QvqmN^T*sw|Z&W21t ziJQZwFi(CI1_y|oK_SCvnhGUV`|_2^nNQ&y8hk*ernQ+EU-hfEd6eVESvYGeEs1IE|ey9T$?oe zDe`P0R~Vp_x&wwajDQFkiJh}0D?;3>hCx`jqLgV^ManjPLdrF-CS`Gz!!zHNu2TVF zU^i9~Yio#87R!QW;Fi`FQ?%x`ZRZCZ+EU-)uK2Z76g{maNcWxL9znmZO8e8YedCLx zG?pV*X{;e1+TYrhE~7CEGXjWsMj$iE$#%%c1HoL@(%=5sS^=x`wmvC{71+vphSY;g zg*rI?(ri{Tatz_CnHD5ji2iH@yZ|1Oq*W_rbxMk?Pu(aB7S6-*7|^MsKL~UVcvdw% zaBUOmdw`Q+ECg8(twR<=VYz1HgRpOU*6A9t7(2k+5W4yW;MVxT+(X)_Q+qfs;>ly+ zUPv-IZ;z^OCvU?iT5}_456J{7A@vxh(Wm^O{9z87CkX|6qsu=WU%Bjpq>@j3RdJh2 zOQb~7%=awU^Q|);y$px~r#hqi1n1%rXtt8TTd~TpGpz&DwU(8nWQUqku2%!8^lnqB z@zK*#bMP}#V{jX(GN`3ge7A{|>)lYwbgC^8t*S_w#$ZF9tR|%^mz6@rv9JufYnl~a z2|<7Kw+|+4JklgJZ_C8SV{LTtjF?OggatV~(k1!=xqb1p{EqXCxl@kKHpWjwNAW3~faQZ>1}f`w@2)ROcbqRwZjp?V zS#~rfW=;j5oFDbs5Q*CLmsFVZyVUsZp;TY+hcudc0PDtPD|1G8rdJJ_bZn)x^8VFv z`<8b<6M%`u2tb_Se5y*$aK0wd6!hR~mXka>se^%O5x|soAUk$!hBRa3ozWCzvJjnQ z2B{M_+krS|8(TL2ap1(4V_=J^9-f2&P{5577>5~5XdPtQTRn#kk1qAiv zlt0*f1TAG#GBlJ|>p@RJEeYST`ALx&&eD%)GJFngF|d?c0y{r^ws%Tu4PUANMLYWE zLB*yrYR1ZvLm?~4Cqr;~lIzFSpr)e$q(}qstgmV#`(4RuA!4@-Rv6i~ zv{fT+DgA3TeUzS6ty#5#JmK9cC9tI;e2z#2tkxq(?3Kcy`E;67%wonT`YcK1I*8Ux z>*(?mTSVbi$U;yD9qN@{znPvPu(4PO>VulMXd+KP(?aUt@MJb5+n1snx1^e7b0hbt z$x?_F!zl$3j0!>Irshi7xk6@vYt7_1(3Lqwzw#Xya#$fQu&c>Z-co2TU2X>&n1bK@ z1EDQdC9oNbwWEmnxCQekKxM~Jwu>wc`U>clst@DR=WEMPM|Z)@1712{_;K^$MLGB2 zti=7bUZQS)D--W5mg)DF%Cdh`Wa-USvitHLNjMrWC$Ie|@jK(C_{-Jg{qX~7CnDWn z>n?c<=7)uLeK~`@RdngX%>d+`YF2+ju3S1V6UL2_o!d9d@?}f(JfcHC?N`;KTDtk* z%QCVuneoSCp!454c{4A^Z&ph={%kzJ*sJj5_r0XC0r!BBN7 z^CUVKeltt`dU9B0Tm_oI&x&b2C{Iw(a&lqFK^057dS_=C4nQo67R)Q*{Z~k-h1h5D zjY#PQK=F|6QXp?GRorvrv1Y7?AH8^|P}NcBu<-h`s73ChcR$hf^9AX&o@hQc4LQQ( zq!n`e&NaFJ+ih75+lUfj#)ex_+{w2D#j~(M@g47)QH18?nLTa!G5OH*12N8!D0K5(&{w%rG=@V^oeLWhB)^ zIKLA6wB_BjHc8GN`9aH0G815Nl{!Bnrz!nbh-bAV+miV%@JZbPf(+N4REv+n#*B12 zhc+GV4MOus*t>C38XJnz13teG@Jg;90X!>eQn5)n{+|kerRDy^IMNet%VYQnH#jJA zKXg8K?9fl}tT<4bq3!HsNT?g$0-7u^y_|(qlNHQgm7#3lvSmpSRN_k4RI`z0FdwBr zgeh8-NGBJfmd}V$3S>S4-=b)GVs;Jzv>cdRurPxJF-fQqvmCSurEm|2Jj)1Cl(1EI z)V9@sxs4oo^W`1;IGFD_9Dw)2YC%8`tFA*^_el;;%A(>_~}Syg;_3rpUwJ@5{bj z+vWQ`+hzQik#g(iHFySrK#nSNE+pZlm%=;0;MnoMuZmnbA~z3jlk26AubtaVX!gt!5t>&b3+9vJ`Ep6!O6BDI4_oE$i$~;-a|h+YnFIPfbJQ>?lrt+# za1qccRTzft<%$=U9Oa4^lF~&&HGauL`6UuxN)#!iDjyz|Mw(@Ds|VTPu$k!UWkG~$ z;GfH<>SZD!^VnBK`Bb)OsFZ*kg`#<~Ys$xr9Wl_|M5%4Ki6b2TU3QO`rI??>$kjv2Om)`kYTIS0Sv3 zR17aBWsAWo3V~U3`@0|-@QuzLWc`X5d8$TLDP9;J0x@z7GZL`jQz-%bGtFzN*RLmy z(zZ*p)2F0<;%c=t;m$n*Pf0Rp2-yiDl$cga6X2WNcEhAKh<92V!i`r6upNx2(uE=% zV*_#1PXqKUULNo2&tD|XPMw5>)d7h>#}tLFiCOwHmQt3ar#t$5Qx2>lj3phRYj$N# z8lW)k>d4-owt%E_$LDQ1d;7Q?zjH#S$x<073&i`SESKuzWT8yFI#0Hq-yus6EtA8S z_Q;a0u~NKCb$M^x0Mc{m4SP*8CM4)rFa0WAun}+cNH2){c}a|mf%nT7WXYm=*r5HM zS_#tC$j0?+y-cQ%LFPxl$_XTP+HUmH)%fCEvi$ktK4=#lp6U*($B~ ziG(HnBlTC@mAB%~O23)wFqy*_2lkH;;$?A~Q}HKiOQ9YgO6W(^B_C25%M_wmawqV_ zh)fzu>&zp?US;`j1a!e%L6y{=-sNTKx1w2}KL|EZ^pUy$?Hk77spMVXs8M~XHp zFYS80C@FBz{uH!)p%_T?A#vl{WjT5LFxcq}5(6z0SH7rHjl{qVR|dgs2BA4PB}5in zMZNIiQnKG?QeelQI7#YPoSAl1oY^OEz{}SsajeUnQ#cXmBu)$ZMWUQV=kaFod7L_h zaC0=wammCd=j-D*N$3pDy5d(~h=so*6(pITiw);WoGG*uKJ%2~{Rc=9qwFF!;v zyPVE9r*VAIAsmNvR6sT7Fy zis~?(ZnbN_JbUSqG==NVvVfe*dsuqqs+juADPfMMG(K~htxMI=E%yCrEUCaV8KwiE z22r*qfkrFmTh<_GmoC?Mt&g6Ra>$k20jSa-8^|2nLqnV%v{=8`6zNxI_<$Qhxv+9+ zX#z)L?Rvi`9o~CIUi!4Vbn^C+cF{eg<|ofe&7p0j-e>Kl%jCY&b^Ke>@w1-N;iGQS z{_U5f!3#~KRLyb{UIBoN#EvCceTQMagDa|ZD%JzsS?8BJshD8pJ$ifx--~}_DDsiY z60a2)y~FD`fb=gMBNQ*r3!jVAWv)0q7Kzh)i8!z0>VxzD`YsjcZCvjz!zn&-IM@i+ z2g?y>xkS4IS4g;vCw;>&48f3$(HF7%AeA?8^^P$qGlv(E)1V}r`1e4Ar*Oy+CQASQM`_5T!6rC|wCH z$a^TvI|#@~jQl1Nc^!!{Q6}DLmN+ltgfk4fdb{pnIiQ(@704?kUVIH_xc-BamXaT7 z7R1$NK{~A5W17Y5FN{7F{r}c5C=VNkUGOpT#EhKpX}FBQ;WImSKv(DEr>*LP`vz*% zt0y%8Ls}BjXog|bn_1R?85cxMs8_1OmbxldL92jUp>~;y6aRv-ITn++hh-r3e^}4M z@_Ut92oJWCAEG%Df*)funCbxIqg9qRuD>uMNS%v;3Wk@5_zl6a6c#ta>cQ=0<4RJl zRdp%friPSzy1GO*uObnRDoQxMm8cFybOrcr1h>cq5T-#fOofvWGE(7yIW4HHc8EfZ zDvLE=3ImjIE8wW?95c6wGijeV&tbysyBf#%?!b{-dvMei-i`QPoT&ZcjQl~IF}TM4 zh!fZjAUv+gKjGZLpT+a}K|tyAL-;rCpoBY9em0*cBFK0IXS7jBA__@;hHKbfBoEkr zxZPyOY{%}B#yf9I+Xgiy;yE0BwdR3=bT1A@_xxQWj%Z-w$)>E2x_XI zRWFi{Ho;aVCZsLom0f{?%lw8tC&27KgOjwLEH&5+T@&$vJetN3Y8p$}`)$5}W@=G* z#BfDijG+$uGO4{ILOyDO10tTLPWve9QXU}u6!y9*r`jdoLQOc<{lc-f5(YXS4k(9% z*$(G3-sv|$JDf}e=L1{{aXpHi{F1eT(67F{RAZs4RV!(e(V#AZkf-~ukQHDN-cJB| z1(o{*o#+MAF&b>fc(5CjFndn}lQ13Em%o4+!SywGfNwx%=i>SfbMgF(oO~}zq%-d# z-Xb-Aor6#eJrmaq#GZzEovBSg%45K!L?M??fMVu4Fj=yLpRHLL*7E(LFnM1Urz05T z{%IH?fXGNNG-DBGB1$v`X?%{fzCfC@koH%|XAbiF7WvM-fD&CmY35x(Y4D__`PNsO zuMnCszGQun!c?Th6vv$uchm`ShaVKTe<}cvsUzl+6ncFK{P-1qO#2)``=B)AQIkoC z&ziA)Skv_F!+g;`(ayZ{63QoSvHu@!gr$S_e}sUl9cr~pD+HUfJuBOxV0pIW1GNeQl23C>u{gQ+M3Q)ZCil94`LTS%C1 zyioM?V;l%pTzl+j@{fgl=~b@fz?zlBp_IY#K*EP0=6x_X4hNpbu;i zSRjLWG0#D(BzydMte8}m;_pP`Na7pfbo~ze!A@Ws%<6cQhjFH%JYOIUrj@=t%xfXa zv=|rik8+k=l9I%zzFEZ5u;jQn3cg0{SxDteT%RMwDJandq|Q;q9ABM}co!xAo1aN3 zti6ULART|}U{V-^l21f<)?_;3&$OjM+ROt(U0VQYI5D_T7?cPJ>My=!Ss6;(2eJNN z+h+~JACXsj_mo}R(o`=(EUFi2MX~z6qyiilpH(xM$?t|kaZ7IphD?(SQR6n{Nr-6W zTS(>+lE~K8bJs4-V23$OcvS}ou*cRASf_G7y%G!}2wFGVH z$f9um877UeApUg2GV*+rQu4~vWu;g9%JN1BSbx1(S$aHIUOMC5^G!-ii~5mL_lXix zwL%FTyo?p3NbW%^s_INj%E@ihK7l*9sN*2eY2rkmS+obEN|icaYVIjn7Qwr443A(E z^^ezr#asna3-QaseFi#{aQ~WMK^OU;?ku?ivWqJY*K%Adt^oe=R{^sX06pI<1Mp+f zvFL7xkYfjv;Lbs61T29|$PhZw2az)d+@Lj5Y{MN``PPzReZ5HiCg8UK2bk_Q1bs5X z5~2!v#3yt)fq;HH3vn&R6@x1l*HRF67ylyoDB%sDX#y%5)YT%3?}+CfSd{F6~4 z5O~e8*CK?!Bn1Hc@)6MM#v{JJjZor=7>29?hcQ9_HPYmOLTTJZmyjPWw1B(xqIlh9 z7bVnqfb+i!(r*zt*h(-v(BYCZ!PfM zo?5kPNKHuNHL=4qss7&XjOTsU2C9;)=32vT?Bc3ztRK{=eCv#V6kgeEhT+= zw3Csaz9!S6-;%E(V}3WWr_3Msip=`-N%?x{lk&}o#u78>Wmz!(WtruDK_(CFC=-VD zkav1MEsbkq^`usL>4@VntHVtz`4PgLCMZKb{aB_>o}jBLggXz*8Hhu0dOz~Gbq(PPG-T5e;}P3-4!sOxjm6~7sqC;dh-P_8bW zo|P`0+Tu%F4bA87NSiS`cW8s_8F>}I-+TQPC9~;G^}10RLt4*)P!SHDYgLVur=Kb> zhxe|>+6w#~;!MBaZXAK9&0TP1I881c=_{9yy)Rc!ehi+ zySJ`my=MoskautrfmhC+IsxBSU%>BGgc%HjF&N%QcaH^&&2F~zo(SeZARDtBgCGG{ z60Vikaa|L4)fMrq#(-FbFe`!jWI!SbaT0M)z(snw0^j181}@M7Ng-bu2W>ZPDp8I z8Q61P_~9-EyS@}a$5&?w<`2YBtq)X=&OBWHL4oHf2m_N8RopBw1EMU})^&D737z** z(y?IYEt`{mFp#wYJ@;TB1c4?5B>?g(&fz+P>$F69mYdG$A_^T^&MeR_?Lm1K*Oh*Byvp`pL%lb&X_l$cyJN zgxx4+)COA_oq$2L3VV=Pbu}ON@(?!7t|iK@Ow&u_OIY=j!8aBw?VfJ(sBu+lj(mCZ zjHAk$YYx@Gwl@Z&^KzR?a%}%PEdSgP!BXe_YX{`FTl=x3gLODrOt)hxQdzJBbmt<@ z@;kj&&g`EHr?dxT?*<$p-Jz^Z8P$&~K++HAbr;8CU)eIHBznXU>CpZ;dGobiSo*xG zr%fK%zZVV{n#j_a1+r_$Cb@s_wv34$AwS}Mbu>;9m``cPqG{cMXx<6OKp6o7a-VbA z9fU2R54a~1^0=TPc2aOp0sPlqk)RZWS&i_?B*aN)F&!iV)QL!i10exl<1s+U4nZo= z0l+~;*vteBCt|=21grq9LhEkg9Gn_b%!2<7fS;-n%C4N56!-uKK>{Ym#T1}$UJS`{ zG17^_Kw3;?Qq0fN&{+&g0uN3M*pwxp;7b777}PHYp<|FDV_Q}T;--J1Vs26UpuJq8 zLpHR}XA+4eS=&xp+6l;wGl;emN<%vC13xFipafpO;sVU$F`$+s-=)ZZ2}&5tvfzrv z@3`amj$y0AfrACzyXMI^x)CS<16>CJbqQ$vr+p< z?j4XN-%cZ~|DH5!*YO#GCnpC&W0y`@V`r!)GU{@Wb^~4tm98Bk*3yvan|*MUTc2y4 ze(hgn+_W6|^5q$0)^8$lGG|F?ULSV&Z7T-`15SDU^Zq$_Xg&aIlz3d5Fc|(lA?@Vf zE%M-cqFg+>OwRl;NB+Rt{|}qKlMlL7lqu1DbTGV)!4O`e5R6ocsE_;OM-IvLD;H%3 zj{l|GaoPj$^p9_Foa@rX^W_fa1RlY9_3}mdFMeN&K^6!CJ#vO&Fbu+Am<-`>Hhz=m zUjP^{@ePC|41iUj%_+Dx@WNo&a8=xOpn56iCFiaB zjC8;^ISEV)7l#BzKXx=}`xF4>Bji1NgM=(OB~>B*D|f`XpwD8X2&EcFnKU0rl-tK} z0LznU*(oU)e?mf69FfrF2PHJ_CtN>bU$smy;55nM`j8e1oYHT>E@10l-5giu4U^pN>$_kiM zbVzWRef!^*a^@Y8j+hm8LJ;O0pvD3i09N6{A)?}M8LB5a8>nF{;pzjp+AxyNE3G&5 z+|C*le$DXVwl(9yfU7yQ?BbFwZE%^6-+~coFgyp6HNfSNAk)rxk8xkMxdBWC#?YjU z^TZR->@=!fN;{QLW5FiGFb{p)*RIxro8=UlNI*D_pR%FT1r<NE1u(Hjzd_pg7XSd$&-OiUNfYTUV!33f`^ zD-H|t#sm^6{xl53PXM$L8zea9q*N-4rHj5^01HE+Zwz!VP?}SZsKXSXBlsv(E<@a< zXQX)YX}R?KUo!6QpMOjE-9P^kX20sv13(M8F9U2L9Q)zLfk=(#nEhta3rrhlfbv!* z7><&BjEkirWv2d?OdS?a9k4yh@Dc9G81MQF4b+yUYXgFvERcd7dP{=cDDuhj&{&8}34urJ zQUa9rUg?3VObw|$0BUuX++#+v&Ts@NjNp7mj>hiGSjGGY;+$0wi;ML{uhG^Ut5Ita z6R;@Ao!S8M06bp6m<-BF3dS`mM@owZ<%~SQ)4~6Mz18oRARAnfzwR!O)8F@$)BE3m z3;_GCzn05C4|d33_s`4yOFtm&6-iCRDIE=p%EvhK@%Yh$@=WVya2|sr=Aq;HXyE&D z8g?zeo;xe^zWoYDuoYz5n)L=~Q$T>R%$42$x^J?G(KmsuDw?uSZ zXf{AKkI(?vpj&d61LiC(*oPp{%>B21mkG?Z=$7lh>syCk5lX2sRiPYIRR531pm}ep z!nSbVsDQ|e+?`KxO+R5ME$1f6Eo9%w$|d1 zc2*F|s1t-@>c3nlhP94Nm391V1L^@7zuH}P;2dA_?#95&t~NcPY8L{M{DOg&S;paW zdYfAdW>rrHapNQ58y04~NPB6KSb)nvCZ09!qT!>l^VQj)9PLSr2NE7wN`o+J2*dHr zmC=lDuyor*T7*Iwszn257^V0){C>SV$(UjNWZI~AWzOUeWYHG`W&Y&1Wby~~W!j+n z^5x)W693glvV6{9Su|sSdPW!Ir&*8>jg0N^zMXCh)K&Bi-Y z!!OXuL(suP)=1f1|Hx&SrcFA5nE)CX_njr;a^Vu|VJ>6~7wnG@a04IEPsC8eCvJsF3CKZ}CccGE?98w*rk{bP~sAVtSj39L;$oE+I`?>>2QU8;m*o}k5|?n%LjAnTG5 z)V@_HXfV~!kOC{e)!ame7nLgIN=W@0u*s=gQd-mtQ%(KLPgj&K&sLHy&s3BSEx`0Q zj+B=5;mp1UPSLFh=TnGN5mdfZNq`gM$t-KpE`~O?G?t;MGsOl1UGsDZWPO62K^XXX zK)Iw3%4lMDD4;wGPzHEBpq`$1KzS9QydF^Ad|%vcfbx#J;_d{LccSaI0c2^I=2sq) z!ACEdPA%SI7XXC=cii;=#zsJI145<%qALOCc(5Vl$`=42GXb7q=vdIJ+z@8p=-pKs zO`H#E3eor7SaE5^@C~567%+yK)CE@`L^cN6Aa^z3yz(^S9g!3F9-5rPZ#?`{)}Fs6 zo3GrG%~$WpW&m#U_4~5r#&0t149dI;^T#UWtTF;h5r>P=<-+JBK>dR_f%i`Rcvw)&fwrJ zhrUWI%&nQCWkJ*e3=5>R8f$*UoXgt+?L!mC;xKU}O(*Y7tf;{05awz_kdp^aHr>8k z^J@KvNJO1F*s21XY77wWz+fEeW&$1;l!B)g0MD(=h_wtzf9EE(%Ko+2NU4mK)~Z;0 zC2!7^*C+7IcVuG7vs1yzU4K!2{CfG6nQ3wd1C7gB5Ed$ZJ{k(=VPGBsB}fl-ZRVM1 zZc;ifGg0+Ov2#5+Yd~ciVUBAT*pHo{#oNFPq=C^$J|KgSTrhwu(UMSK1zvpvpq`3O zOas)J0+<+OL8#s5^gIhWLFi=11}{D-g%fo+sd~SKdz4I36VdjEkUbqLfzB}VE8bUJ#lDpf7=8=|5A6u zwh;7wy8;N7)dBj}KOd8}ckfD*&D+f$DCk^N*@*AD`mYWi3NjiGg{O+9#kSoVr6r<5 zKvg3XvgNt}i)i*v*;V859iY^76;3EeLjrCbB}_rVy^QNalRaRCO(p2h{(k%~~I z#6fCCg93775tKNOAl&C>B%DwDX{a(y3iK(6s8#^`SQ7=X%QrMbHm4o_UJ~2EYfzDLp5^OBO8z!x@Apz#nNB511^^Y5+V1*G62MkWLx~4#nzJ z3_T3|teZ|s&^jmPIdf%XuzWG&sAYYZs;J zSXbTYDE%SX%p45t5zkN`W3j#z&V@5b5M5Ns zQ&qv}_A3tqaf+Y`nI5~DTYup#?QE(yYNT;$wrH+CnrV=x4q;T#wh!IXR{)N&I$F->eEsW2(XC*7cs??9VxLoaW_D#$vJ!R33fa{`9pDn%)h z*8s_B;2t(1l}(6ERmxf)l1U(KkBu-$<|-9~ptv`itKT8J?#yfxhZAwvQ_l5NLFgqJ z2RePCC+@0Effn7I9m~K~!EEquF{}eZL99=i2z!2GdQ~gI!yEJ>j6-dVx-!z!MR*bo z%>@jGmE%sO-Ip>UN=J3;VF+Osz;VFCs|Iltj)bj;PZqx>I^RU|6)1O@GT7uv2x3|W zkl`ld&1bs(;BQ(H6oRo#ejHvFgk@?c3ZNqKnSBauEgJVxD3i3Z%eJEXx1hVy&>0(! zgBJkNi`^lEe?DuvDdN9S1~e7QfHR5m2 z+#=qlHHuNxAuu1PU2N||Fn77plnM@l(|lfR4HT8+23t@nf1!#IIbTe{;UphO9oY0RSueNIhpGz}Wbj(|&N33`S>&M*Hv+sS z5bXKtw0J0`ldYh#4b!Ky4p%BMgC589848{`|7H+3kU%GXFNpVM8GPWh>7mFLWGg_7 z-Be4AErM}Zwjv$T@v#*_i%v*^+_@x2*MVRJ?mV8YAcEK8qS%>+lK2q}QF0^39jArF z{SvxrzrDdi>mvqj#`by!4HE*va8Mc@BXJz{wEFR>M}ioX@t?{BRFW~r$fjp=oU7RSK9f} z`3=ad&#V@%Z3FNNCfF=8DdrJwBl%K!0E0y`u6*xDrpC`q>RGpTZ5#@F7G3g}{BrCE zS&KuL8aH}U*>o=lNhl4v}1StzynFER&%v6qQgH_)*EJ6jF<`0W@PH z-mm>t`W(3-7asm46Hi^0@+s)eIVtkd{u8G4OSaer46Fjh1+(iavkMj>1G5WMQfg7A z4vY!LLt#jK3%{Eqy;p1pbBk~Nmx@YsV0K+-1YJ(%Fl+G;mFqD+ASrr)N{7e?d+7lx zos`31K|$r?_dqh*A(M~$WX$jrSjosshSyKYkV6tmK{Lqzf!Xz=@^Q>A*O9l)DA!-*`fTQx3{Sw3DJT|LO}jC3Eacw^k{sJDdN#OYY?5ZSaoSqi0LO^i5&bnTf9 z>WM`Uofmc11x7hvrl1wqqkl2x`y9MRTNNDj$fdObdyh-hfm5b8O10Ptl&(C6J_H4! ziVd^1vkr8V!X2qGlvpbCks48&AGTIXZvRvEZcmdzX+Rn5>QwJQ6&sXa)H}G~7~DjR z6Y3pM4i{Qz&jy6U0=q+{)k@H!1cZE^ScY zqbaQF9F}S6D3WDBsnt194MuK(t%A|(V$8Up$wE<&hElQO9gA4_OztU3j zqVvvRq%Fg^#`3$ObR|l~@j?qr&Q=tLZM#4pC>m=4EC^} zK7CT3^?r)aC-waqd}o-`r%s8N4-TJ3>l443cNw3e`8CIBrh>30cE)FhU$=Ips%p)q zun6)1X&E_K#}7b{(Jq)ZbA@DpM-2#I`cA2@PWuM5HRb9rM}e#R3fd%qwh=(fWlaNG zuH9q+?NET0n&FwJ#G{rP04Ui@fJIeHs-!}rCZCbF0a_&(&i%i9@=oa%oK}-SQpp%X z&iCts!QlBN_W6iU4J-A*V3IRqX}Kb{8x`p@0v!pK7W!akB080}bUJVVP|DcoSQpc@ zy9V)B|0?x&UX)%3F3Z5fS7hSJt5_PjELoQC#23Z_R0y8fs8L>EYEP;Qd zZ9-yBNwJb;qI*UHzx0er|u6+9n-r@`1=s*3|8M{3+6h1gz z@L?o_;GOTu!>@eRt?Mi1TS)hAU8F^erb<>hol^@{xKQEEbmcrsC944Jf+)`$fWo;C zn1E=;P%tVz4TRKp2GyjonXOm(TNh3Op})(iLwhATZlRuhp!?d$0_3H`CF;6~(ru}$ z4QU;+R+pqaUjU{4Rb1b&=OjgDjwnG3H-+eM?A{+ThUB$a3)smhv7ov%1)*quN8N&d z=?!RLFWaRzOsbjETMw-O;l0O0!lab3q7(s-SP%e}Uq z0GSM;D$4HQQp-C(O2_djn}62F53Ui{z^db(&Fkcs;|FBN#?`WH;kR&f`x5jJ(0Y(+ z=5N-dvApnnTbTsjG-*YQ6imGjPy(2C(Vx~PoZ&bla%QANnv6TUhU=wCrzBg_QR%Yt ztn9z}Kt>sWZUsQ&poy(pfxao6I`uo8ya&K8!pU0i1CF=Q89; z(Q3gT_OJaFe{~}i& z{%wXr(4On}q~MYr;+eBS-rsfHlq~1qgJ`u_)HNP;p-m_1U{o^L5 zwctpn4y)E z5p{uNr8q++AY9B(l5Ob^G6NB| z5;?gE5nFE5BA+H_Z!Ly#7$8KGvu_Zdb0248Zs~xnA~$^yrnxa3PTl|00K)zK?|KuVmm)m(YSDa{tG9&5EX=huKzln@VUzz2u%cKUP=k))k826$j|=uT zF5u?IW2nI1|6R~f<#jy2K6og5vDW-Ann7uJD9ESOSciOK!8l`+ir?&vt@>y?!1Rvu zN!hB^)EN>%Nh}Zwfk~7nW)iG`lEb&^p*=eR!uJeo(Z}Dk(8`xLuk6^iNp4)d1Z{h1 z$%k`T4UjYuM$w;{G$JBVtk2KGT5-|mt;rC<6k9H_MN%3}v@(uniqHO(f;sQoqVvvB zqxsq4ugA{)8kzd2Vhqd`Wnxurld$5(uRI^CIIa>9>WV|z;5QYgZR{jqX%_n98{mrl zyBO_D4vwe=S<$r^;xW-jLSvzdTJXJmciLw`R-)w=L--u*rce_Y#^n4)5=~M~#L)Vd zR=BiV9s*N(tP|C*4O4m=N~-PfB5Y;_qPVU6D}<+UKjX&W;@&`@&|L~eBnW4djc4T= z2;3MQGhEE=N;S{|kW}s+S%REsHot(W;Np0pjqpeaU9?k!agJH8O=mLyXgd&JYzNwg zfkeAB!d!;+5Rl9-PTVvWWd%O`0rgvqI)T%6mLderG}Dig^mWG4HSMKKSFVb~W6jw) z>={KT<~`N(03Aw~LM&#vAWzwvD?NVf=43oN+wAaSdzn6MG7Ok5$R7`XlR00_ly~~| z@$;8NgC9zGHffVTe7Vz$GHuEv`F!eRwLGV=uj3*eCFU4{A4^R8KH*;>>@ZP9p=;4; z1_TS`@RcT^^mi2BW$~8)Klp-EgsGP?I8fru520!nW^HMP04D>0&hh9~?klnzJ`@u` zCB<`2|3oP1FR>SoUZ(Jj%?r7gACjYY9_k9Hm#kPsb1nwNqNljBOG8*`VOU z^>6riw4G*SlLp3)OG|X@R;9JP8;erKqHS2J#bAvvTGm{=CzpT!OCEymvrxa`{_BH3 zCF$3@(smQefOf~kuUizCpd8$_%Mrz~{Af#I!$$~qZbeq8B;jgDQye{QPbwq{i_j&V zf>^>K8p!7n0mQtTop2o!Vf^UvkbI6G3)b!5zl;JW7zVeJx_-49i0KL^@yrMcNP}#; zOq(%vqR2mRs*9L2XH3Zo5k+ZIP_60?3ZA{TLo&S$}n@O1m$~<<-ij9U1<^-OwuJ{!cs);h2{>{u`nIv zjyddD&Xase>Qsk|LvC;4uI}Cop_~Qo=n!KDMg|d2Op>=D78c=Icj|#M!X!s2Fx*;X zU3^%IEk6o#64;ivEWYBHWari|YKwtJ?(Kugr9nFGOr0ZrGQM+v-y1PH zK8>2oN2|HNuRlsV25Hf;0>-NcW6))-=Hv2hyfQluF-BRc`9Si5!;*LDQ7M~vLaM;7 zu4KXq$wm1PW7L!hTb!04Z|+uPt+ic6knx=bvq(DtEej z@BM05U9{}-awnYgJxJO=_pC0Ia%TmRU}(9I4Vm5Y_J^{z%N=bo9 ziNP5vhX)Rodz^GD$5PTP^kNKq63?WMq($6MMB2t4w|FLcrsF%eL63%w33qVA4?rkX z!u7GUUbpNK(>)h}vhTsX0%XuHfO;uFTyhEOr2u!*-$i(bJl#b=#v)=H$R(0UtLNd) z=Y^PS76Gk`P`*XTdm#`sAMt3RGY1!GH`6ClCm@{N#*I2>KsDORc^Bp7Htxwt3**uS z>Ri%Ua%EgJTfj2mT1=F3yfI(o?=Kh2gfcEXj_>$}FwSD6!#Iq~G-#vAG&8gnMiSfV zQ_Qz>VS_qsupHU55ofKxhP?_c<>#FnW%8I25(>q@gptE#=Y~WX`cZ$$M3#Zpx`bCb z*s_q_B%$}?M0sMa;L{oQw_nea^(m{>oR*BWQd&iqJ~`xGy;M24d?Gdj&{MctZX`&# z5q!5~Sfx2dr>3N82SsdvHtW}sjNsAJ5eQqzs2U)52Bza90Jh(1alP;wGy#naFez}c zT(AUSwk`*i*dmv1h)2HlrkROGY^s-3(~Dj0Ai2{C5)^q3r^|m&ad!}M8(2& z0!VliR{rVM13UUdmZWn!undrWbw0Xh7lvnL1OlEDgdIo(9?AS7I+t8@mj75B9WTgA#|%DOd~$)q?)3g&8i+H=JMX_E zv2&(Khv#6%h2_j|r;m|=@4N;tu6g9GUR~td8Dph)_fC3HGy%v30d_j+7UA^>Q41n$ zDJ5}7g@G^vg;^wAL#_#o*a5t$m`Bz*h>Bh2#z0I%X=ebP0bT+F$IFofZYDyM zB%5)OG4%}P@l#+6Dq%Xcd@+Xg6H$Pi!Ml*%h{grBFq#t=qYw~`d*@sm@%L{!?D0c2T220N&(m= z)`LMrvA3f^<*~rlWiBMZomkogwHk*~SvZrsU|Qf_{Q&Yo8eU21ZwtWox*)D$N?k2d zxKoJnER`koq~j$zU>dXo4jt!XpwcbU2m@e$%Os&?P)?Q?AhrWtx0aJSayH;lC8tBm z$-3KOlvBL&4L#Z*gsYqaOONY+YY}+P3Bp$JMlD;yl|?&gSig=QRM@_4YiZNExyo%% z;a!)PUH~ufr0R5ykD$V;X3LOBsfZoS9N1X;2E+U9`T zVF}6uO6PU)ucSK{ObFL%zrmNU84?#`e1Q})c#i}98wCh`hRN}x-6rP`5+x7z_|&ah zNlNtn42(6@avi?J}L4tL}pmM>mg+h8s_xwMtCWmsiI(ko*(NPaK<)5i9Z7?fkEJo#U>JM zBb4SpZ4@X?G)oh~(rEcu8kE=7wn1qa)9+dDF>Nz23CoSAq#~4|70`pU@1{i-)u>!@ zst#8~^tnaBkBg-A20=SRy2jPtk*0l@Zf4*s79iSL50qQUQ}#)#fkpIO+sTG_ z57-JO7V|J&Yh`f72~`%=uUskMMoBJbVe^d#mWWZb5sy?m0WPNTD?>3fH_1mqoTG3> zR&)qb{TRe}z!sAmbDjRPVcg*yi%4%I zuF*()Eb_3W;X*S?6vcv+)Qv%02xd7Mf+0uaVoWMFhNDD7ks^7HLCAp!?~EL~e~qQY zhf=gr8!4GTm;ASVP;%73MfdNJ!-|NX+p7$Bj8$A|oPA zDh|=AQIv~ziB5{Cx=A9xH81DBmLiSY!v5}GU2t$ZOou;B^h`HQt`w(wEi`U`-dt=J zANu0{c8pojeHS$QJzOyPj-pXlByDCKzU6W+Loqa$EZ$sX)N8$wS`Vb!9sSQ-m>ZN_ zq1aEoWXC>fS`S``Vb+j$S_+gPHxceD_!R{mCTl@XnI&QxRMqvt#kBk3dIx#g(x40| zO{}jpET5JLA-KlJ5-}#dyS#>!dLc!o%p8~#Q5k<*a*R!oh@$9hv`^8-&x)JI_St|E z&+xSmYM||d_;i!R8nQHxX`g78CeQ!5Z91ZDK3OAq_K7rl?Omx1ud)hDHS^PRXEJfw z!oac+U}>n2rM24i3IZij0rnE%2p;|pIL&dOlvwp5mVQ3&PK}DfG&4P8kcdXW z%T{QoewdgsWzw9E8Z)fjN6|Nst8VC%?#f6f`5s1o(rt|VWfvtxbq;uN5^rI}4NJ}Z zoOBOg5!i7O?;?J}T~LS>xAFd_>LseZJxt!}_L4c76@Hg0*KGhet^u(`7;1?bHvSIM zNVtPE5Ivd+jb@Ur+T7y7%bZ+h#n*6C$A1W#hcO*2H@j=^NcM@za2Z@qBH%rYtw*R8 ze5oI770zjC2ty|x1=aPv>!<~uk%%TYo(bpFR}6+9nwu|(mJLC*uq$pz(QSXo$h7a_ z@}`!~*<-o>8A5NXL{AYAHEwjLx`*h|*;RYjVY&3lqa{QjaF0>rwO@1O$le3s_?G}t z?k`6{*|eSt^D52dyl>D9F zm0WL(m4a~sn+v!w2`-c%lIOjdlBZ)IDS#LSx(yI7gXb>z>L5MpAhi2HDZuO1fl{zt z4;)ccO&a33n7S~xv~Dk|VI`qj1u(f!zaZhSe=1>phRUR{H-}2raQrL&+9y&NhkWGe z{2s3UlE3Q*z7h?@;U6X!FSE!Uin11csZ30Zd}0eG!5&arHvmMIvQggmGorgu0fuEK#is)K3sER-;m9>eeFXJkfD9& zk}BY+ulR}VZ5O0xI^Xz0S&aFoJi-Q|bvoGi;1?;NQG+MhL}oG()odzE9JZ4_WhMo& zSfLA%C+pY4$%4D2-s{sO;)Q4&UDL2r!;I(Uk4q>obFBrN_c)!R1KV+5b zA#1e}Xj+W^5az{D%^8tD1?YH!llJ@P|!rG#?iVDOP_1n~J*REAV z+CiJ%7&`K*l`CL+GWu_-9m#nS3Q7&qlNnA+VPW^lQ7Ni|@K+GNGcH>iqJceHf5f+} z)R+KNG=K{^;~of6NrNg9A~f4S0cZw<2Sr*@LY>NS-gz41!9z!+ZogSl{H1Xc@ybM8 z6C|SZ1POa(l2q+JMkkW|`SOtkgwSD}4?NYNp8N>A;J08U^cobpuf?2}KJdQNvQux# zmpcbpI}pgQM+KKm5J<2Y9e(_tYA8(`H}bm~G@fLEFaPPFbgQqY&pmP?ot}D|nJ_E^ zeu7>;s6eB>m%3TXDg@0VHVN8L*|c3L%%C+t9@t;Hcj>ISrV%$A#2yyUUN!tPw^%Cw zT%0~u>ei~JLSb>BQMGlY1GX8e??O6s7Q{+Ywfz3OeP#d7G`Jb;t(I=gp97u+{SX?$ z?{VZ`)bLNGC>qu_424iNTtXQG9jBe?GA``k5+_^oF^zBZn=(19IFUxAWPv6c=X&~v zj~zz1M`8+u5U_(}Oc4{}dfZ$n(s@Qzu=zq8blEp%3Nu+CRivzbk$|D*#L&Tm((v8c z68Xw___ymeN%EKNHc?7S2j)nIo*1er75NpS1euaEs7Kfx#Ca@nzF39eY# zpBgW{yL8YUek>>FbE=hSG@?6}oYI)_^(lld4I02J$QM&4$l|$QNj*$ulo*AyA9~g{^XsEho#2 zZE8!V04I)%n(XxFV?Rq`QliXXv`7}k#K^+Mi}fC}Bv!ur zZY~^E*3>b<`ZGNaU~UaMfAVJ>d3{2zpF1Mg&K;IJSI@{))SP3+P}8y!O_J(R0K~Da zWh4u$+qz|QIr;NGIkaz^o`g(Aj(XHUXYj6M!yMX*J_{UcX}AIllCJRB`^t-LP#;($ zAxF-_%++!RiU^nBXN~n&1|w3|p0#1G6QD=-?~vKkCn?Z$EtFvK5H$n|%Qc!0S^15p zV0C_>jYNWa=<*eINHaZx)UIV}KZh`fLWK*zYGPc z_=WBWEZMj75d-`CE!g%V-;$~TG%qTAf-+^wR0nVWVOV}OWP$KOPP#*EI3p|iTmzfX zSOXgb*v2`S;!>*kRm~IbTjgr7?t9ER1F>S@1~(J$4G`2u|KKlB@>H zUN-(Xc0*vM@y|k>msC>CLdL`@P-rX6R7jU-I$;U6jxMdILPJ{$vktWE{GK3f|v{sD~=Y&S`p%hqc9|l%$(_KcEL=2_~4IVU~*f@ zq8}5v3gI}tdBDU!f82sA!`F4>u_+Z3fTXqHvdzo(vd>y6?bxhYv$i!P1(>LYGN_=f zwe)Cclmum17nCDMj^22Y4l+p3C1fC}Z8b?iUeAhVInCm07TR6D7DRAORzamtA-2bV zg>AOnzifK@K3u4?`-AvK{=6jv`@f@=(>OtlQwKZ8E}uSxI0*aqor{v0$3}kr1&wbC zDwb?T?Ohu)6DN3*SrV2_Ym;T~mJQONeq9wDrm??t(*>1SY-tlx2XvS#H5LVoOG)vW z)~$4~kY=-vx-9YtdLCs?NlTy~?5CaX0zuDd>#*tpU}2((@jz$Y0y+K0T=i2B1MwH~ zyAIyCkYR9vy&7oKzqE@rpg!rcWN{nC-r4wy0^P}X6iyFsVAshtk%!mK^F#dR^S}3S z(C53#d1!|rTM}^&u%6w!N}tzyDh+zGcTcc$uPG`x5SfqS#o?2dCbJ>f*tmtxCyjaM ztv33HNk_>IGbJ`N_nFWA?kkKD{1tnyZ5zp+J-dAK^=vtJ?u>jpZ>GHXLOTt~)QEU? z>6CFJbxTgt(gpHz#}^ek%;9-JW6s z;T)g}XN0g5zP1;8msCKfGZIDvtAODh38kiQ(^D-VqcJ|e5MbD^ym`l}CJz$UH6{?im`Nr=ajF;#M&OAy8Jkf6We%fjuj{)YR*7RYdiW4D-YAKh zjDehOGM@M_ZNeDk7YRe=WYc5AaBB-~S9DX0hpzt_ipi_WJDUy9#v>G|5g@n2veg2# z>VmkDD)>1Goja7*2_nxx9??oQ3afB-3?ag~f%!GTO75Wp`}E}7iqICaGs1jL%ML-) z>Y=N%zx-T=eL4s{t?>@prAueIdgZe0`+ldwjcIkq2KBgQv9c;TL3&`&Fl;z#$#hC$ zsr1m^ZG_?j$@1a*@2Vj>L$m^cUA8nvk`v=`5XVG~!M4%1Ri82BnbXrOg0663o}VRobVPN8L3LbI;TMghMj&$oRB zd>9lz=-4MA<&%+~$obC0ImUueo%vTJwc^|Eo!a6k_!d6%*AgoD%$zZeR0kdlHbFJ= zj24!A4>&=6GH3wy$)1qgH?OG-r=Ulnm_O%O`UBwp1U4*9$q7QMq_dqDj+vH~?Ap1L z^oM%p?LKcHt$GSJHWY!(cm)dNSFmey7G%}UU<$bHV(u-PH?NH<&Xmpp= zpvKSu3xe4|j$ePzFv_3gs5}6agUPZFKWl0M8pSkVZLt)qZoy_%0?5kAg<=iNTs4Nn zx@$Ct8R)F2Pg?&+zAE$;}-$_+#DHqWp)KU8=R#BIjUHm01D#WJ9JeK8XVfIA?Pfo!T^`K9+{-_{iQ zVxm_*=+jl^&zb~H!c$83nU*O(pIkOHORjYQg;E0WPxkEDI-BJSFicHQ;`VwfS~e+rmx;F~eN4EQXwCE=ZOE=x%Ar|WvIpAhnO z266o(&rZz(9|v+(Jeg*UMA zbfruiJ5=6%?Pd9D+Gy3L5YPTnd)Yog{F%OWElLQ4?U>r2y6@ zK?t?sH6gQ&n&nq#VqP_5p``ATnD{M#<4hqrC*N@GWW{~ z8E8`aQnE#Dw?5K6&>BU->b&o+RsLvwifg*#enp{Ogzyw_w(f2`v!16vJ*CDElp^SD4NzOK$`+oEgmZ_+eR@oGi(>J{~ksx?)vn z)MrC=J{bf~_}#v5>O#!)Nn;h2q!lAa;3!xKKU}Bi|8^hkd&YSW&kGmK7w?J{D`2@d zb2`>bF?)riZxr%{J-T-hVorCf1|`MEsSwGr;2%IPo1VXP7-DeyBzhp6T(Xx$&r4F^ z@F|K7*EYTf#u^N_~S1cRsg|y@P%C zYh?D+Q8H_C6m%_XRKh0lXCbwFJn3PmZ?v0?g%Zk67+?$@$E=V92rR%o5wpS(MEjS8 z(-yLc`C&j{WXqcEMTMJ!H8@+=tnHYXZ5~F{KKGa;eEb2^)JC%i_BX8KZ&WRz!)OLR z{>o^O0PzY0@ew-2V64Z**ASYVK2>0549h#qM5dnk*!OJ2)-7AevL!LHJZ`BZtca7| zy?V&l=n>FCZdWFGUD9${`0Z@$>uCq=`)Q>?&bay|Zw!e7aL_+QoP`%-8f5sN6l5Go;P#jNKZTt;Yg9oL$M=L2!h&MY2o$% z`_G*_$!3kk=AL`rGjs0DnMdw*Kzfv|Xw1D3#T@+(VGKm`uDVo-?${h+tDc+`K29nB zE4(olI+i6$Q1UhAQ_UntjMJI|?CRr{XR|KF+>EQ1TC}ouKD(l%jg7GDS1)JhluR?& zKDaZlhTfZ<(kpWp=2~71y*Ga&yV1Jlxnk$#Q+>kltaNP6UcGvjef;oVdw}~CiY$?b zM*tUH=26nglP8Yr!-u5lS$6;KqCJS5=5npMLoA05QSY{4{h`DF+cHGw*e)Pbn^3`n zW+a-xy#)^FdQNxvQe8jCn2ARJ900Aj_v6Ue7( zE1Da(2Zkb-pd95~?^W0cJ8d0&)M&chAvMbgTN~Rlb}>d{tOSQvYCA&?B14Iqa5h@> zr>l&Yqt?Vdpus-YBHPNVDJ3w5Dr;!AYnpW$+R99BLdi025NXWI!7)9ExVU>m_rXX7 zog+c;9zAk6@2KV!Z%i%<4{UFgJWS_+vKLREWIw)r^^6te(Y;|MwdAUY&>pXOfKxhb z$R(m2k%G-QD;qB8nzBWg#_WzKwmhSQG@5mY5)vRN zU~%6G)J8C*??eI1rpwEpw7~gYJ%&C~JTaa@hufZdXX%iRMV(bD#{g@ry|$eMCD#n4 zP+g}?sWP0RVR@La*YQ&Mli>j)mQB=PcseB1e{?M4p}K`_?h(RCT4r{dMn96>-!wH{ z#K1o;rl2vjfQzZk2AoY)n|2eW#>%1COIN64)J+QGimj)HBN#olshUbuEBD2#l)Z=MQF36Kj>anx&5Ui2E#ZJi@-+G0M>NnWK9&($AyTl&)}Yv$R}>}Sb$70zpN z$F(J(Q-#TxW}^q99i#$JuMNtgJB9B-(+}|i76*c;MNuy|*wGcZD_l3{M-F*p|A|Ki zi``93SI}q;QIoC^3+?&6-iy}gvRwqF+tANCb}{wI^@y?xeiQNH?nkdA9pI))X?~YN zaHF65VmRlgMCk8p0|Gh2x-PXr)^cq~Mh$&aw7b>lmxS)K&($9>BPyEBxBB6l)tR~> zVeLdRv;*#j3j*hxlJ0sDY8KE6+*?zt)*tMk!CoNU4AACe(H3Y(tnhm$uU{(-xT{tB POF9#Cx>l?0awPr*RNp~U literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on_hover.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on_hover.tga new file mode 100644 index 0000000000000000000000000000000000000000..406204e32e195ac698df8ba12e11cec66ca3d69f GIT binary patch literal 134442 zcmagH1$Y)m`#qclcS>;!PFvi9ySuvth(d68coJMAxCN)UySqb6ODVKPS}63byS#1B z|D1cDeG=OD_kFpp&CWABJG(P;=G-!}etzlw+`p@SSN#g5on5V3HNSLKt5)?33JUV8 zUcGv{x^?STYuK=1mnKb`3~Sz^#ljXXS}bYVqQzpK7kd=&v~1a8v7bWGic9HU)R{*D zBjYV$3MJ&RgfU66nRSz{)Nj!!p?r%P@fDiaSX{PIP(o10`tgkhbzIzhO!tK5qr1oR zSln!Mw}hsny2Upe)opRpk=+)1nvU!m@6S-Y0{XQ$#uo}uh)061TgtRT zjtU74nbo9!yM!jAy2kNs^qe^7S@z7hCL{QphkIr?-lHFW-cXmgl>8arWJH(Prp}>o zoTW*l7+p~c<=l99=eQcd&El#wsTtR(e#6+9rcIm1rEJ=?NgM;Q&6+ifZ^j6nJvP}X)(I2 z-*yjE<>H}m-aL7bH%D&ddM!JucW8j_aYN84E(&cIM567YNK9|HXaM}$@?T8bSZ~Pl zYRJEBtdrKGWc(M2Y;6}hQEeASK;dpnhM`_aYh-^d8&aoCjnrw2^_Uze_BS#M8%$Wmh zRci&c*&;Ph+T`u2ShZ31?61Gfm?6Vfe}Dgu#6*T!LdQ(~OUb_?%y3KM)Yee+uaAQNZ7g@hIS@C{Lk6-iw}m`SKyJ;uMvKfGAKPKl0|ygZ#XZFJE5E zN8!N0f|jr1>es4`RYww$aDO}ctQdtR)BB>Hrze6YbU?w-x=7Wg6jHYazswkIRF*+A0Pyl60mqy}}c&yvG2Fvd6z~F7sXzJ;MYGXU1#DGRf z&G${y`YohstM@OBG^~U)?aQ(fSa?-JN2kPTSP@nk3gk)maX#M&_2f z)te~PzZOb{*GK8_hUmU*2*&Q4jgYV&s9U2dYaj<)%%~QuU;AnxpHl;TdsTp%FAqWrY>+n;a+-TdT6;7Wxf>q0xqE79am>xY9){;{vW6Q?1 zC|0xxav;Y;(~stxF`e_V?$9f zjz@erDkkt)9Dz!UBT;EdBr4hw!8nE)UonB#cvOrJv->LO{ssMc^hL#a!6-kwH!9BV zg(gb|pwXQEXf-nwD?Z+XCF|y3*4QXCs9g=B0rmErJk&<&Vyr%Pt$Z+a8bS+LwH7T> z1Vve%=gQrqlIQ%QIW>j)dWmZKBs~^>q)kV0I zCa-F;(n8*)yO~Qx)^Y{bNaN*EXt{C-nl21Olc{|$?d)R2?wpT~%^R^cvRO^Ik|_^c zS!mT8=g;r05fYGE*+r|0Wmqv-`l%9<0BRuvt)J4x_^x`>vDW-azN-QP0$!UgpxVCx zvh+A1Rkdna7(V?}d6tER{?P*hbL7ZQ*d=23_AMyDW-G+5bo1IJ#4VhM3ujMZ``a6F z_3}lOC|(Tj-noUD(>+E)xpU+~n_lg4@aHQCCwcYTHwz)B;}CXX3BoQfN5r*N7;tMX z2HZ}>fOpnoz}*cP@ct$YxVISt?r-6-6$3upis%6k-bR4|AHHqB?8*ncs#Nc7#DI5s z*PV4vE;rX;!1dJ_aCIdj&hsh9V$p9?G}b*ojWs9MVsvOX)C{U%;LPcYB$q-3P+ybe zH_)j>o;OOCK-%KPilJnQ;&|hYl2F8(JeS~av4RLv^fFy7;V(H-kc4Bf%qF;3t5OC3 zdHE5p;2uWqTY&yMXCvZNJR&bH$H1$rFz99?2HjqVL3h?;(7PKk=&rt1StWk{^0yHM5Fkcx2H8uNa}kFHopd$YDo?bTRqaU};^{y<#W}kh~^M zpCu+=j}a#AUmB`B#AG2~e^xF2E4$f>@ptpHXBSifRxFLjH(z~;JGZVQX6ht-@ZN3o z?A8U_w{F6jlSlBuy}Rh%wKMMBy@QCb5bK0_a^^1xD4Go6(L9FA@ssxgkD*O z&}%CYdSewrZ>>S-owW#kcO63CTaVE9HzM?dO$fce8KEC;fhUx}^n^apKZeSM60dgc z9@D(H0ikz!&pU|-z0G`Xu14tfl?c7M9HAGNBJ^Y|g5Qq8icgMU?U{8LKcE+CRjc?9 zR7!=-jqEI=8btId+AKzjEK$5TM42Lv(xu*l>Q&d&v5OTeYS>gID&88C4Jn)|P90xy zrQV`wWtFPI9WvmB*L9^D3G|CEKfy(!b;N;%2t6>*`clM|73{I>S2tE8g1t6^eJd$uf#eys zZytv8n00VIS~aeN*RsCmRV1ZEzA9FvsR^_N4YUHR16q}FreG7G(!YWqKV35KW=Gm)TQJ$0KXhYXiMe7u1FC_Syd$} zg{3vL`3s3;&E1A$j}V`-1kI!g`|a&cWivE|`P=ym*F>AAW$?Me`jfRIf^cdczci(xu)+%^KCPY5iLC z?$raiWUI3p4Aj3~McB^i2syFHftv`F;yskgLg-zR^7{m|5i+4F$bLjHvzfvk?L^q) zU5E*Lyc^}i9_>QdCp!)1p`;;$z9{@2fi0SThdJFQ&ENC_`)mUG?wnf|gGOf=_H9MgGl%W0)BM-+R z^vEJaTq0Szl+4l?97V3|!VZ|X8;~PD*#%GJ<2~??e6kmjPxkN^1FtD6^3fjXy21P* z(+lFdU-<~$%GV|6i^~vxXd#9lT!1-;7ov63dIoKeq;c9JMFQE0-$JE|Wl^x_X6 z3D#<;s#PkZGnuJP>lUU9=A{x}vSe{ou2j+PkPKGuHq9|x5jJ@esIMVx_Y8!bA|qWT zk4iK6Ux22h3}Zutk$eooY_71UY_hOV_wwJmSj}=N9}$cr~1-^gWKr8T%J|(ZD%MS|V%K ztWyemvF&E9vs_6LVg0dT?Ftq;tJy-*qK6J1h;wI7;vO~YQEc!d2lrvsilx}MX9qTK zSc|b^Mj=ba%xDu#P2|@b#J8-xct_(EwMzRCSxft%<`tBHQ^x@330FRN#PjwcrP)!j~uLH zzjM}awm=w(#lb0Y%zHvik7gc*)nq!f`og7U=*#Degg2bu2oDLRZjCC)k~s@9@sOIK z)+t$BIE}%^m9f~gDjpTem9{#P-Yh4X)QdZpPvYY7eP~p-rsG^A&ZbY-@Sr&ubx87rVWVGJk0l1oPPPu7sTmD7rGou2lETM`)$n-$kOcipb}O`RfoOcqnYK`E^|ocF;>g=KT(G zy~>7kX?lU=6$(2VZ(932ih;Jx8<>KjddbWF7(H$f>t-4@ET4z{TUX&Ch1BJf`!Fy( z1ZPeiPeQGbBl!3UVgF`DT8dw#N|ma_T*F(66ahJDReYe@u(SrcfIy~S#s*jLhs(~8?kriCahZ-hkCWDIsO=;P+o_3ubsoLZR@dl z?NW4V(+oLf4H4C1*dzP5{X#bu} za74P)S9%J~DE}n_2`60rBZOc5QhZ(^IXP|}#$`^FW0td? zz&;XoJOLxgwhNBOp?yobe7#I-n59#E@tnz&J9Dsi^9r0hybYI5?8VTiNSr%;!sL&b zHpvH@ge|e9VauOGqYa6xzhC7|qU=v{aMb{Uxfq>~Uy4i(!bZ~uLRLP9Em|xPME$8q zhZ{xflF{neQN!`<>Bks7VhGx`X^D4kU&nxmP%K>>k3$FcqIJt=ShhG8lP8Wdn{NG@ z6&O$JBwLoOsMEF)CJ~fnCUi#U1G5lL;bWGS+y|mS0yCKU*4h`>@$i=~vH6QTnEd1f z)!W?!Du>Y?iZV%|9}|!t?kicuDqkAeIeMwiD}{f}@;JO%zC0>2+_+v%vv1{~laQS5 znS=@y@s+9t(b-$kC|o+RoN_Yf-=OPa*vO%XIlBTqH%vw3*=5vhDWFApqExvRXr;<3 zGhjX^O%j-qF9^gJ2E?N%7V_C4OnZ4AXMTKwuxE!6@%d4v;=vS_Qg?`C1#RY}94%)( zK~K7|1`#KhAd1~Mbjb+TMhV~etQ_AW*444ov145Vj_uii8)pvS&V^$bHfR79z!O$O za&C*#3{^ZQhoYHmpO64E7|sHyP@X9KFRG-7A4MRitw-JIXF)Z2c4AFd*fT1_nJtr2 zDO04#N2dNxSCmp!-lJ=0+<)&5kK0ICG#48aSD|H#rfjP0*6iX8RlPGbm=kkmMq|*x zaOBALIx01)jxMW5AQgukTWp(xNa{;IzZhW}M#&Z;>GshsJpY{rJpcat_g{GY>o++3 z)dS4`^a6eH`_cOz`SruynDXcZA^i^Cp*i%^pTEPS8~QK&`~v#WsV3J$nDhbHFq5u9 zy{|8QLy4cC!JzmFNRu*+$^M45gRo=e3@n^B%yjWLX;Ds}HV%CUL?VnlQR>YSbU`?p zn?_)wr;bO&upt;YbTI0WNnO4vOONpK1UB*DL5QO3p;O!Dj*&-WERe=n%(Mv@IC40K zj2?lejcMSJr&LpdfND+Wyan^217|)ojU9x67pSLlbRvmGSv%C(&A4)b`jQZQDJVLS zjCghg{hl7c^`D=sKCt-9o9O$QKGMKNH^13kd z%9gNDWSBzU1;w~1wA4&fNH)+MfBF)7(X#q)jB@gq5EH8H)us3( z**SWM{zi;yH^rBK{DkY@eTI*J`O3g*v9->B{}{dH5tD)C^%VGwC>dl_vbXvSiI_j4Hr+CXB!yiu+w#6VbM16Dpzw zOu^HbsDxobg0a{e#WC*i0y>&w5OIzJ5b_1ke`iAqRJM~Cle|Z^^azD13}(-cqAwMm z*q7IwPFeKxKYqlZPmhv2#g_u$F+_eLKuTRr#+%I7^4Bm0&8W!J^my%>jW*Nz+Pk|T zEJzRz2K~dyiRbYO_vS}=FP^_$DiP>H%nUky7U#8to=&lzfKw% z5$9^w3~%=6#j*&QdP;%3`BAw^4Rl*G60KH@=1?k47AczYn35bF|Ef$PnL4|vG}8O| z{S(X;3Uhz|=WiJKl(nv_GK|bawaY89iD4P-*Vmx$!G%VCqn1x|Fh^pNlue%@Bl>o0 zi|Fx#%Y$=-y;n5`5u^L=2&M9)6B~Rhc6``Rr93 zMOP-9lTjYA7XI`Q20lK7&nPsaRUd)-zkP_{CrtfZ7$esHNqSU6%_Al0ucychb%sx+ zBcqL{uMMKOSQBwagmfj=a(jtT{WJ%WlL^Bq06zTSJ!0(*6ephu5Nb_>KuU$gPHJs2 zQM&Z$+8EaSsWg@qw^_OrZaSr5?>ysAKam$AyxY0#%_3*6oJS08si-_%*A1`8af21_ zu@N`t(VA?)Xy#W4SuHUGhBk7Z(AIp}NE&`bn*^ls-8M&f%D6Th(X=7rMm{=>ABeL# zs^MH4zkCG>-#F6DjE}LowmCZz>KTk|GDk>PUGsl_t zU3DO=2sElik6>qmCc0u+@>6jw-cN%m(MswkE79We%2csjygf>}C=+p-%{&y^s2LV6 zQ3SIttwI#NjN#%nPGYb@CGxyuSj*{?3~3Ua!qKOP5lk(4_g5b{+#mScUw>lCXJ^s> zQ!jjwT%mo;=vLw&C$jY&id(!OK zM15|y0G9ouU%y5uE#^=G?AbwtQMC^HOn#p|w4MnvjhAW=N+6@tI8h*5?tn}VW7&Qh z4;@L6#m}B#JnWIY_sDEWS)48z1$35w-L5DQt&pEQHq&+8uQ>fdyrmd&DO8*zr$q@W z0V=0P5BVgGAm*n4oq1s;2GQ4Npps?E&J@A28mOdY2~@IZY2QXZ=keKLggn}hiBC@A z=fD2Ibd|fnJ3qZZf5t}es)0(Wlj~{%l&opxPC!KvP)1u6k)}d;^)yXxTR43jwk5{n z$gcIcc4i;_Qy1~cdsi`ha1<__dlgV75|fZ3BuNc(WFzg?5XHDK@SVMQ5@Q)Ol5+7U zIQ}F8>o}G#C*QUcKrBJhP!Qpgl$R5>$vX~RIY`R?|Bocnx!l)b9C#2Rg~-G5(LO3= zUt^|fHOrs0BWAt0h(7Wl(trzNJA|=4{uiP`=uzm$p$J11m9s1qjvm2@8f#{D(tcPx zce1IM3p8l%SC;=~E0m)=1)NYKOGzRkIXY%t_GCs$_hNHUs#MnPs zhJ(=>wi9=FL?S7|NY#DlRi6FX1^o5*-JOaz&rc?A3LAi2e5N{X}GCYP6 z#TiaWE}9^p!=0}|HYr%N5N2Om{eQEFyk{C*6ILX2o*Y8ok9H&B*;UL^NdjI{(H=}y zD2&Pv2jdPRm!;QzL`Wpn>wb3=(e3O!M-X`tBCJZ?k#LrMt8tng>lWka?)A8GaxWg< zxnKy1iVSmjgPuh(p<3Rgho93vY$>0ZNzb{u<~vJC=h$0Rc79SCiFh@r0mENS&%Sce zk9e78vmcBe0@U~!yROi7nPq*8eY zw<0ydOStrXXDu3R8-YGY<|1OxT(iXV{(_3EQ0Xl@H!j0FmyhEChc`Zbco$zi{{-K> zc*-Hlb+~!`s%giPs)CCe&&T)-C;zQ3%^|x7R6Jg{p#iVkKgpM6@bF@XiKWU2J03$q zn*WurKtu5TNFQt)8-z`vISNeqn+qq)&ddxXs;E5uPYnI{@br`~NoafK!O`9Q+U zpyjI3O9d_O=zxqiniip&0wdWZ-G%;|Fv{^TI<_T&`ms4i(4+qyRcdn@1g!h|E_z9V zy*Ns?BDOLZxOAVZ_t38u%6X6BDUN0?$HKHet!umCf zZT_23q&c&K)|-MC9VBy&l_a@lD)jm*jKt;@GZmmOuLzapnHQ(o%HnenSv2)W3eE!)-JRafY=bz!_i|6>_Lx^cgj)f_l$_l4ItNl`(cJ&jFi5N?X;&^%EhcY%3T4fm@6)q8dUfxL-aH5Q>BaGYRxFlG zJXvhXM4g~^l|!iV_q+Z9s>Eik2`VnsB*p|cDh$0i7`6VZcOCmU&x7B-hJ4zgR4#?I zF#2M`Xt{*FAV8l>i6Uspi#D^1Q*OiQkLh%54r(mwXKW_HXFe;h@DiKNm^KcZ)-8Vp zavtH$uXL$Wj_@;8X`uj@{S`6DCKsdGjC@*X1qyS~43+69fllhJ>kAO*3brF_=shHaCq7@d*DZvJ~!vfqKwDt6}?krC2(!M1& zu2_Iw93<-4wk1|CkH;Mj55CJ0nHkYjY=lNr?$4e+fyC7-%wmuU8t4L!Et~|605u%l zQ@81FZ)|H;0#c_=RfZbj5nVBZ*zw40RG%M=71WN+fyJ2xt~-IgWXzc{ zg=4vEtX_mMiO^DSy+yHF3JHqH=3_Ylj)xpjd32`rW`N^-(eN`IAd=7Bos}xLfS67& z;?bWBcl*cZ4riy7N^t#$XE^lr0}io$g+KoO)47s&#fxhQX3a!$q*wPxZ~?&p0yvm6 zgKKRZg6{ig(r%lLcG3N<6h+vgi)N0uxdAH|&%@hv+g>T*H}!V_kxzoV=Y}=hug7-*%$- zXBQ~mtaP6;a9o|r$${pj6kH)`5cFlQfIZtVolcJwY;}WW$}^Mv&EqdOPH$u&OfnJ} zmE_A(cbqzLEV1%4o_u%%*Us)Y`*mgfTsny8o~9OAi1R9fn$~h$SX}KHahVhCv}!=^ zb(6pJ4~P`0znlCNGNq_Vz4Ico4{b#uQGcg7wAYJiJc49)9~piwJSHbZM*_?95YF+d z&LqWZb9!LndCt0;GnlqwCTmSeE)KV0;k;ScylDfil|al928{w|yc(+G;!>ED%_v;v zCLzkJV7TOj&+yZnL9LlZ8cvjZTw^tc&0RM0VD-!ER*t{RpI_lXF2{p7 z$Q%5Sx(Ek)Cp|rh4ga}~8$Uk7H~;;`?)j0UXCoi8Zb+^XbS!I24jOXpAFz}_9$#g$6uIb^wZ6^AU=t>)_5 zOg2lPB!^}+JR`gk3qDpdFl82ElE><|_|1o)f(8E&vfQ}jX-$Y4_yQd88Ht`ZBUBLv zGCze3()K_0LeL)ht9DqNQhmCO&d2FJeM0NHB;Cl48Cq4Bp~w_;_|BVT+6g?t^-01 z4l?gZmO>zjB(a4PG=u3IJ^TG9*!%T8%y@PN1E~)7r5x@@0u1M9kY@lr8bu?h_J(?| zXadX#8mkE}F5wcbto2{qM2I}{%uzXO5n4aa4zIm#AnGm-MQ08kx1Szj5Y&|Y!~5RG z$)kHXtU3|(>(;Wx8@sk|#{NA!aB%+~%%3~c79&Zeqzz!+;8$T-Fc~Ba9M<>&$su6? zFr-+5BpmsRu_&!CBv~Lys4~nkg##&rO=`>43o;i_Zd|gweK;c}dOHQr8m-hY($vWl zIUV#JoH%h5r_Y?kWe&G4^3Ly<{#2N>DBSg2HyX_ohF}o&L@n@(ls}%-7{YUigm!Z5 zQQHfp-WVz~MNTogK0=ARzKrY7-yTKea743XjD!lYPm(aFiJ>7RrVy?U2;-Eco+sv^ z#i}7#P0e%E$|+{~%9PUBqE@FaNr=Oi&6^B&i+p4_%R!(7nh;pVp+QGHPv@A>V2)lz zonL{0oWBvy(a3OH{=^YU;zS0?z>g@Vc?1(f{do?T=ryxLcI^Q~knSUO$krtybxm4g zm{3Yl-Ip%qDC(1D+%Qim9a`!bMy;{UzDWq?9Gg&%hIW`4<|sxqkWO=n%;5ujaQDu2 z42g=sjjNa7xk%q?xQ&xiH^pw zOMjvCx?fRw)32zs<97s2-j6)5J8ll?jWt`2wBXC}K6r9x+)s{t~)`C!sJ(Yl7 z(UHi@HHcOXDKu2ReCc9rCKOdl^Wu7B6`QZluUwfjj?}Irb45$Pg-dh3n1rT{%z^r0 zTvgC+`7qSyBIJroLXm%ZClr{~4F&iP1sC*2x2wz0|J}9ddLYBtBS>O3ovfuK55;w@s3g<^>9CDk&}rPQ7(enCh(xHi%bua9)28zJ4eCP+1=5h`pPPTia}duu6b>=}pj z(>oyJtj_3khl2XicC^11kCGdQBEZuQh1W(Q{8P3VQQG9>3}l<%9VsWbM8l&q5q5tQ zI-H(`D(ePW{+Y%$L52|xkS?MIQg$qZy3>21`H(I))x@LXq|o%X70Z_Rgzqv@pMN=e ziB&$2AXZaD4$=Y(aUw|16(f+VcXg!eQw13Z*FpMW^^tx=L!=wk2pPsTMW+k#=zn_^ zI-Z@2vg?K-<@jc3dU^o{lBm1gT#Aa@Mk6&#kz-MBQsZ{?|8Nu9o}Y(&aeWamwizmK z9Ygxuj&2thqVD!F$jJMZcY2j#Xg#Ehtcg^e%c9KiR_L{8h+!qLAbEy`kyw&=b=G7% zzoi0++@$S^@TB=A$CMgf9&$I%#@hsfR~gPvQ8Se|X~>8_^i*B((%wbi@Y8f9wVSM( z4NV41!=9h68l(E2V(2yW`4ARVvSdl~C`rvLH03giZ2^j|2Z|A81&3@$jx6cDD9dGY z+Ip@VgG}6DBtvL*WMo}s9N7>V$23Mpwo4kKtl|b*Cl9ue2jWp}=V)Y_(GgjMvRf85$m#hOl?npwp?DsJ3n}G7xE5iMq_>(2Nl^k-l>|Za~rx zZASE<(n*G9iBt~F5nRE|Qw(uLprh1DrkbKxM)mKYEr+Q^VmKe#f@>mEa1gQ%W|_Q* zQ*X*VrYSm~nUB8Lm!b<9uKe1;NHw-8njD+SS@UnB`}M`BOa!H!+8Vj$_e8%BHlpAA ziD-Xr9ty?=ftEq*6e`70)l>`-vEEzoFY1|SeT}4-g`_8P$SQbHv}Pp)GZKPTsF)4`bio@_(KEh9`&6-^Y{bxqn^BP^P07+XJ2D-^ zp6$=5B+cmJ{k`DG;Dm6;gcMl;TzN6+x10ObR6-(n2Juf10!= z8%~aTB~jf)nRC0%0H7s13Cpj4gW#=?5V7MC z2JU}`uF)GPzFs$^$&#(nl1SSy4zIN2BY2485E5( zsk)3c)g>cEQQch=(Duw+wBulRNg^yYk(qyf541To2klPJMKh|>*@(!r%%?KNZii#c zgQ|GNrC~@vqz4z%}vco)w;xQ@>rT({X-^rm95*|HR`Bs&}1 zNSY8*R?3{lOD&A;q$reneSR5^RZD+Fh>=9diMK0C$P7br%GK}yk_0_qS#q+ZT2 znpTcH!;?E_2~#0+L!Au$Xn@Q-vJ7E|kE(+VmTygDWy55orINjGb##s!f`ofpu|VPVyEiUH zaJLRfojMH`&Y$C0tOQ&VwI#_}$9DD2O3J3uQAu1m{^XvNJ50K5*ZEN>H@F4TwR{tq zdR0b-epQgZe-P4#R^vfiBfKVc%i74uvSu7i3CZ$$^z!~zl3|VD$uy!7{Pc_Q6w{gb zPpPbCRKh`o9dnRu&BWX?g|Qa}bgielE%_ zrgUMxptepCV6tmS1!Gh7sEpLTf{?mr5YqK#Q}?cl zG>Yq9iK#0h9na}`q-8GJA2AJ&^x8;;iL7e23jjp?VXx)siA1?Fk(5flg zas7uD+;?c*486N`;vD|cHd$70C(0Z*YMAXFf#1L6daSQGVDt-aUp{4M7dn+rZP>0u zYpj1~7p7j|nvJ(PYnkh5y3q&RZPie8STYdxXZAwV`TgMOwq`gAc3V4wi@}DWq&o zi#ppi#v7gbTP*J|@1XxH*HR|GLnK5`Eb&dIeO(No-ml4ZbwXPsZ0lsJn;xr2q00)& z^JRnW+-`9c>doklTG2gGE2bB!PwS4lGyAaQA!x)>Hk{iZHDh|hQ^V5(uPLOfjae_+ z@v!Mar%vkA0Z^NF*Wpo{X=+UChPn*5;c~Km>&K&Z*Cr@YMDw1DL8wU*!+rv^iFtoP zSQiak2Fw&T=tizmv|8K1XTUX>TS}^q&PAh1H!4Y{o7rpEl6pmTW#(ooZ$(ZH>TF3| zNr?T<<7fOtBHX~?srnJK(I9dzDt4cQ0*wctNXsFt&Y6tkl$4NJm^g1a-d-Jx2}3y9 zE_MbQ)T?detNaCFZ3FaQt`hw1tEc$mn@{oQZ(ri_sYCW`7s4X+X%jT&{0Dx*cX;&o zW9)wKD0;5ngidQ{#H`+cR!df+?XtD#vX&#iJle0?goy`tO@Hk?_5G0P{R zNmNI)8r~i4M)yXCv3=laO(Qu#q4r~XLq9ya{F*`?#s;Gm&rQ2GK*Q)A$U~oIUfTY7 zc@A9mJxY`%9j8gf!7Pm=Z{#Y=JZwO+38w>=WLt@bC>4t%r9vebtDQD9bzSSh?MfcW=_E8B*wMV7?O7YqTp~Pc+ak=~z6jA9XCrC> z*9Q#lY}cC&>Wqew?a+O4C`K)vh+*+#S({V1tavW^%^Zxny<6a|%4HxERC<9B6RjSW zT5GI?za%V)qP=w^+BLO-Q~8TI*fn^XThU+4soRWQ4bB!a;QPDu>&$0nN(a~OV=Q^* zS3pcY)YAD4tCkW-KiWQ2Uw(QI%M&-FK=%bG&}{(<^<0Faz2i}&cO2KXbYF<{**ne0 z$c3A+mrCA{{+$s!eLU*bu1V&g1Cmdb{I5{199lGM3QvosO%Twkc~jJ@Q`_F$c_+bq z^7zqOZ}%Hg{`&269N4`ZC3?mpZ>NPQ*kuu))ioCV3v`J^ejeG|FGR1&>u`SGW=xLi zgSFh&p-1~RoX-3j3(-fAuK@DVxv1+p2j(r{i_e=iBMNl( zn9IssSDS#s@h^})Utwg=mK9a1R6?yb4q%MWj3J6$9xp-J|8g(q%YEQ0rGa9hY|BPV9$mn7#`XMi(y}MDWUmOD2QHt~;aEtVc(iI7YMvY@j$cu{h@7jtDTh?I> zk=u})!cbi^pOQ98yvq$16F08L+6}90j-iHrM5}tgLwmPl<5u3cZUq{6?-T86m89NJ z#8$at1=GQ%Oc;%!+{7`6JxMqz&z|GxFJ8T+^qZ(!sT{ZVs7j=FL`@Fyd6Yq(>f9gU z+bAx`dM(Pjbr<^VA|*iJb!o#vP;A* zGLE&$+Jie+@XfP_`0CRS@zv80@xyf5No_Eeb*4H)scp1KQ+H0Gf9I8 zP@DjxbCQx^B>aC(lC(u89^GWfx4VqG)2XrL%#b$W5b@6}`cL@s`G;8PVwo_WE-a_c zLmZDJj`tGBBf`2NVHPKo)FJs2$Ckani&sZP=!w2bZrTNX;@D9JT`4R-awYh_y}M9a z@a?e>(LVe($lGlpp__=)`!`ch3C79=Q_!nx2X4G5=yHOG7rG)Vb$UTpdXH5RGX9RH;In|m3m%5ME;ROX%;)at|4Z5aMdo=5!}6FndphD5%|rCm3ETr@GPfd4 zz@c3m;2ARjpWeTLvE1`Rwz+Vt{qclZ{Q3pHdv+gRJ$Vm5zWfLY3uYPJx$K~`d01J^ zu0`i~{B0mfCGvOE8kP-tNig360mkM1#h3ep0P4lvAeEs!@Y; zmX9Jnejet}n{ErywHJxBd-bec+#+!KvRK3|nq_+*sdr1qtyQBsZeKl%#f#@7K6W%*t2~T?^|To>ea4ptf2RFQSR22>MlRUdR_K1ZL2DRj<#u?3RMrPh!%}% zqig%-m>V+@9ox0Geyoy9w0!eYy9@tfQS&=@F$j2iDKu? zz=7?Fm@q5^Pd>PYF(Z;du3em7JbE9uFCN97EvvAb>n08{ZNHvftRuK@sH>lsOXB%cp!_CN>J>s`h9?;r5xXCF{; z-h@Kk=OM7$JQOBfOY;!!3Q-qPe6CJ&F=F0&>|Vc^s&gkVd)Ly;dq<$KcS#0H35k{x zl36Y97Ef;_;WlB+2pdolj165=wsgK^e8u_Ii`vQYU&Pc?{L?L&6r=zbhKypQLD z+;eLuoiq(>GY>Jfuv)EZ6|UaB!CmAob2juLR4iY{?w7)#{LdcUhe!9Wb0@@O+zf;} z(;3FKt9TI6!jDyG_qi)4(Txio)c^D@dcO-N4seIX8+eD;nlz|mE=tj$6eah)^{%R| z0`!jy-_@%HIZQ5$m(c8}GNntQE>(|y+(u%|kWieU5-}jGpVf5%zM&Sl{Pg8h;`|S~ zk-o)e58vUE5$=aGAOb_UUrtEBzMPd*jT>Gy$Bs>Fh~wkj2z3*i<)x`V+TO!zi?f=Z z-oK4=$M@pcf$cbTcsI^-FTP$~+uQaG*0zQy2j^z`C27tow4wHu(F+yLy-`JV7+Wf_ zrS;Rb8A{}DsTgnYPvN`IA@R#H6v?b!=b>?|!`p8Dyi++yHF5SECbbgk-+%r9iJSR_ zfs(=8{-SuFSW~!*^jH8zlnjn1;V#0sxGgyN_DU?7JrP&9g;~pHO{}r>7V<53?c9;O zx@=_it;J4?{Cy;^In$>(3O9*R=^Rp*#^OBr_ivu!=#hh{F?a>aM=V3xki{t6Z4OHG znvaT+%TaN_3X}?6ih=XC;=3U`(b!Xts6GAghV6ME>sd9VjeQ09M+D|4?_aZR6KfNA>b@d%Y4Ycf?dSbB zasSqNbm`!1{i*As!l(Cd;bSg!S7#Z^eaG~kF5oYnI?U(Y#D`q;+_^oc43Hcgz&lof z>d8@Ea@e+z(l=_jfS1ahK|VtvUn0i5`RtMI&u{&hqBch zVfB_h*md|cw(UQT)2C07mrmjS?Mr5QG;iA2v|2qwj4*lJXopdL{|Y~_6Mg;keM(4e z2kh*;6KHloP7E0s;d}Pud$;hxovXNb@dB=0zm65F6OlWxI2yNTi*pw*;licMIDhdX zm#$tRL@wje``1mfMuj`yuuwVwZ^%=RA$PhQuR1Ulv~p!LneZpqSN--MQ$>Lv=*n0^ z*8~TJnNALT?WX_q{vDR-2mJc=r%-t%wgf1pIe+|sUBmC+U@)1}RdK6u+q};nyi14E zcibNOrFlF}_hHwR{Cj)DYTic)M>}Zj$YCb+R0h*y%+M@APOplXDH9Mwm3kNr%_@~E z+Q+AC(58soo0C3U-wN}#X^Lg{r~X7dPkgfXLrbB1ag`aWmSqGR6d+^U5nz#F^UL<2w5(RJ0C z>nDVGA#WIT@A9SaDJzOmn_6ni+KcjBhH^6kExPn8$ktuV*@t@mR!&-N7R1)5T&a=` zD`*>~sK9-WnQQ(SL~|>ixn-*CzrD)>ReGz zwZRW(0K{lREyj|$7HMIQSG`K>Nf;N|sRr_KXi`u6{>8@*KL7g-1-%A~ex;yWY8bcr zEhcP)_YcMelJLp|S`E}hgl^@c!BJhibml0Q(zsJE5)qrVK*ATDI`>fnGA#tp$!YS|M;53@H^Ux|5>wxLZ#P9v(-!}XGi)x$JfLdneAp*l?OcEaV$63hqM zq;W$mW3kt+T4I~g>ea1??1WZ9HWc$OrN!$!Nm4jiTSA-R(l?1BkWWmCRYO9L96j(S)87)wa0km3Wy zMJth??qJ6%giPxHlP8SBQ_jjby@w9z1DkN|_)aXF@65`OKT`alXFAVumXUa*0c4au zs$5ltPC4}^Vjt&iw6t0ew6{|(_FQI_%NU$Z=b~H9=k&W*(XHnycdeSAKPwt*md0Ww z9oNfZ=h?SWLi_f%aw?tPK=q_@o9j*cUcAx<%1Q6+s4)(wyDkUy0_(|4qn>PUM7>_) zF=ANNv_XYEMj$g}v(*GbIUyU=tBXX+lP&93*;?3g+`LVep6=B*65Kq*JgvF2bN}95 zF@NSXv~SyrJ**JsD5LCxvkPmTZE~QuT#~Bt{oKFzp7pU>HLGI?wi5X+*%q%r-_ERbg`FPtq zmBV=hOK!PXN(-e^MXGVs&^=yE>x)VxI#?z(y$hxWV;&;A`7;oq@cD-*RbYB&2H zh&4AAeYv+{JX3Mx{g;@y{SKn{yo;HK?jv&cdXD$&n3a3mVPqE}fn;p8v}#vbT6SsFTU>f^$MK~8OJbOfV$ZS1JKfQ( zT23i&HexgM^65(Be=FBJzwpwR(25TpjYpzdsOl2^V$He8kOqd z!v^uAi>=XtD^c3F)6vGh@bOluH%&2@J|P8Nm8fznfAul(iHrm_nn#&BoT69Fq4mK^ zFTBcnR#@p&3y$COO}x+b)D0Wevvt(53ue=y7=tO3#u39gES<`r=O{y!L*N;yx`Jd@)4z1VC{vua&w=l86S1%XZ`xCm)>mxzW?EC)UHGKAxCtb7WBd; zK(!|IMz!wIimd=s0^i_ZeL>A4$(9K@0&{0Wsp9HZ9QJ1`X(N}ibhoIxsm=A=uAMuW zk)w0Wv`O$xnP?j?Yns46DcKP?HY#3{)*^FJ3#jxawEWaXER-^N2T~u??-^?B7+;zc zic^$2m)?eTTF}|Am%ybuktK^WW8Kesg5K3%A*+7t^j$R?#QxY$oW-_I-xsW3?> zP9i|nsj9=oFtc^DRC;BtViCn9Szp9}VodY$RgjH<8Mv*d*z>bm7x8Kj-!rol6HGCb3!VCIY%goXqgIBm;B+XOMKGExSD z>LVJ`-|>5|pU_9MV*@|05qkh-#`9AY1tQiXZ?R!J&}se=j@U23tf`|hJhC@G9I=qQ zS#~n9q=(9EeRBT}c5Gh5{f(DkE5|{1Y+B6^xwNtw0WJxfwB}P)pArJXnT$apTiX!}%OOWyb!H_>krcZ1G}TvO zhm0@yXU)QiqKt@9te>ww4H@Yq+{V$w=4>N6FF(i6G~DiRzTCk*9P3S7W#hT(y=GSD zEX`02`f|n%2|+~f4wyY{44ora@bbw6nkUsAz!UfdWj2mJVgN4Y1M-P~0NLRny^!A3 zbc`gV`YT>+U9mUEyy${}1tGsqOjJ zZ}cLTEKPDO8%Bv)qg|4c`k=u+osg`QdimsfyMF8C3??js6-@gu+lJ5{E${W$W@VzL z8D^I$wT2acV58_`Z(nnG@ydxk=&<8kn{icqD^Pq3g&TRI!P~###-)>35j!12L%Z6Z ziGAsYQ~uH>G;!l4`RdDOAL8>z@8QMc_wn_Mk1&&7Z2?wqEa<#Njk#{^nrPghJ~VNs zdDBMR{k;K7mnn;)#i-2{rAb-1DA%SH;Xfx-xR^JTQ6XK_xd>AiN%lLiNHLV5_1?Ha zJv8DtZ9R@Y6=V0HHc52qk41*O&`w{KmEHPcGhH$z}~{QFP_k)RE^Ea!E528 z2penc2^7&B3nEzOz_F*1gF1w!r%Q$yD2P}ub_4XvYGl2m7ehj;`^(zf;w?n*x{8EX zKjvdiUu7$pB0)r1$55WMngw3R9ufAEGV)h_D9v;|D#^U&58tzMD5Nw#2oqZW3&MJg z^84Q)cD83y-*Gh{r<}@FP%#Oo6+Ime23fRcP~Vp4McrZVa?&Ict49*jik{CR~wEO zEu}4LJs|i{Hy*(@ijb%(&7`(+H4@L-jVB4TxhLi5E4xZM%F%hE$0RGz6R%i zfHdnXAeEt%jA2!~$yE0+4KUr zi9}B^84>w8)wTBe?}(p6{1Dm{4B<}e`}k?8Fm6^LqE#;X1l+gJnG2oU_?=EguVYb@ zd(>uzNphCvg6Qw(pT5AEWBYK1!-A)e?nSpg;Sdt*H0_AGJaqQdY0?3Hb((f?LOE*l zr+z8Ac9ZrzI(XAMan{u=#vwPE zYF$s#@99+KZoU5@5_cWN#(gKS?dUm7o5OjZUL8kzjiu*3&V62sjZCDrbdl#=^NQ9a zWc$1KT0h98)c+T*UFWW>9EnX=B~2UQ>_LE4tlK>GTYBM}3P= z*OkA(s=>!!s1y^e`2B~^@!1}?EO?`32M)j@do-IzJJMq!o3Fk zQ%CloYws{G=p7)}Bq`Ty*p>&+joPCI!?hag+zz#P&H2r9gEkiLc803;TO%TB7%rYX zfV1pSNB6yr(NTS=5q0C&$667tj^J>C@BM6>*JHtoaVsaO`7&4(FG=WxhxFy*-HZJ8 z<7wQva+==~JkKv7F1CE-%#cgMpr1$3*N08Cn8MY;1THr>wSY5PGMb-5eIIu(AH(}s zPvGJ0bJ)B(-de|{Z}+7HT=AD$)J2Lx+D}(3WYS0JO{e|Gtd;)(d(%1i=>fi}W=d%O zT@9*18fnq!f|iL2OY-UpFFH#wY398qIR|m1P`hTjMu$DsUc~X8=uHA$fV#}?0GLAlbm--D{Iv0n~q-Zb|l^7&^;67P?M`ji{{M0 z>Sgg*$xnr^SQ3Y|tND4|&``SP97lZZ+O=()ofS*tEX^vO*DOykD7zDN z+V{lxDbsQN#!Z|!c?z9+h8p-K6~yup178LEm{-6qeMJMCuc*}aJ%t$IPpC-(dPcV{ zRd0gc)CptA3;eVdZNtB~!cQNBJj$s)v!;7&0MMter1pWGYYZK*I}0-O5Mw^GGskm) z6n|1Ga?exz!h>4d)iXzoj07NGYJa_n5Mef<=`FgZ*g&2guY;VzzB`O#4SX40+7l{V zf^28x=XGa6oyXjY64an^$!nQE2(k96v z$I_*+F68*HtiJ3el+OIO60?G+yKB4L2ii7)O+u%a+!0a|qm?YB(#cC*SP!x4_i{)n zx9ZiE^h*DN_jfNG1%~hzmm9pv(^5*Rlb;V9I)Z%%4&%V#qd0!z1a928hS-FqIDY&j zw(Z!-P2nzcO8G|Ix_t|a7#~!(r71T)C5Bw?C^6#lV2p_9i2?n(`xw&U9>M2-Dlu8C zfxJy8cZ{l2=CxFosS~w^il12LOozW{INs+BiYpgRu=uqhcX5P5br0hP=YUY1OGYWlnUllc2P{6WcnTgh;=`s2f7%t(p$bvEZc z^mCrtIlz5oyYr~3Q;J1t<|MFo5hPI~nb(>17bG;G-g@4Rz|-^d$} zF%zTl;r)Av8aCE&x_13$ymRLcKHwN*=U!o0vV1iTA3bKc7yeBj@lx~!8l5K&?!dUg z{W1Ul@%0{XR#jK~{|rSsOhEzL04gF#2SIx8y$mx$@4ffVokFkDdlRW5-3o#zVu@X% zubP;|7)uiKCYl(NyzBpb*SY7;4Dt8p^BL~B=bpOvv!7M=T5CsU*^)U^V(KOD6+U06 zh-YeSN9i*khMiv2%TNNy8KU02sz{ql7oYO=e#v~>vT>a%sZ9^kL}g66PV(Ov*4eaX zK+)Vy_qHJeb-icL+2sqT?2`V7;@PI!o4@k33lqqk)cixUsgKh+%!5!D)JnqBw;UD&c zdNc-*%~_af@4oX3tI@EnEnBt0{`BqFwqw^m`=5_L64FQ8 znhjg+(u*%j8R_n3Xd`LfqsL8ko;i2&kZoU=ZL5~du#;MuW8=z9AHj|_-X@->6V_fS zE6dP_DSLTtUck4bpP`)=G!mgZcgp*n?4ibl)L~H~zo1EinV@M0d%;jAaeuk&Na<;J zn7dn3LJ$`QV1bnvSg@fF-93wmx69Axajyhh|MZ<3O0PV9+@|h-#qL`6iB($mkyX@R zm9@XJW;?&I6Q|GEp>4`ykbv5}VzDQf;q-CpET5041#m=A2ypZfM9@E#P{jW_gQImK$oSl5AWOQwDg#S1M#>BlhemkfUj$3 zU-13%(`P(XZ1u8CJ9=P`57ZNn@AFK4G(vtKp)eD|nz#pE721`a^`|O9KhwtykZ?Qp zsi*Y);cwwt&g>yN9Qi&FVxyT6A1?^^1h(Tcm=FAe6RJt~~T z?BE?|;f0e2ZGkemXOA0b8*}D*iRE3J)&#TYF;^Fyp-G-={~hX4hBxQE_zZN{AR`cZ zz&sz6(cc%c9gx<~skvKcc_P)X*fKG+7iX)IuJXWr6+Kvwq_92;PM~BaLX-!fi9msL z|B4pJRwl!$2Bbtp_TjzT)lkB^bp9Xy@`b&5>6A@5`KjHxPaat%Y~8QFirTKB&kHYH zvEzF-+N5E9lmR?fQNWE|80CGF7@f;+7(=_JJAZxiE&J&&U)o=#iNC9KmPJyWW(di% zW=>ZS<#Ywt54OI&d)iY+57<=+ia%C{6T{S)dx@)xi{|0aCD_WVhkdhC~W=Pt7d^X-)?Dq5u0zMt&e zvocNgY_N$#d)o#LYR_*MljlV@*AJCfw&@_AfFS6e-MTo^$a(0X7|Q0&n%Iy*Qj&%Y zl;vF8RSZ%`$dQLvdv)*XF%@(yZROM!7i{Tkm9YKzL`B;z*>L&7iGaryLb_+mI-lTs zT_L5Nlpfi;M>l)*@A*)o;|JQ9R~FG82-=RyP@Q=Mt=a0VDi$_S6Y3D?XDOFe9~(k2EkEOwO?t2Lc?e&d=FAt;5&{Y9S8E z`yw=$2d7qLo`_%bW19HypY&(;`DY(Frr~WoeR%%{4xivw<;hcLt$V+r);nXktjVXO zf$wqrju5jIv=xc{f5Yk*wbC)Sft}7PP6qQt(g+kv&Idwthp2H;MP?ti9g@f z0UX)@CgonJSw$;ZP67 zaD-O~(7iM8)@Z)r`#=3gMZ=ES*drfV1+n#gO1q^@=Uw}>z4Iq~N)6+hiUu{SxVLN5 z(it%9qTIL1H7ZeYef?Z7ZtLc#kjN(*RM1>9CEx_lUAqltfMT&%!bS@RkfX#~?*V?| zD%&4hYtNrO?y*A8oH=e=)-4zI>PSMoXv2pL@X6?RmqWs+(bfKSHDj>pz`9R;4? znbSw5!wi#adV=CSURTI}bHDDZo`6=%O{4?6HhEOTd#_(r$sW}RGDiR7%Y#aSz?Lyt7eTE5OE&z$eSHE7<&z2G{lw-s>K zo;<^zkQX^JO*~n2j=UzT7OT$5)Nz5=B#%=t#CN>b&vbnI!^eAv>0$j_c{gd~@`c|# zk!4QQ)qywfAK%*7zxk!TE|)m|RPvADY|tI9n}iz$!*7lR$g%~K?X*%p|MVLLBj`L5 zIUoQP#CyQvxRZPR>hP6s;U~t!v4di1`@5&)sosu#{n{Uzo8-}I?hPhVG8(G8(x5i>X?SiyLTOmUBZlGa4ycuV*> zxQ=o?c;Wu=6R0BxaBPIA;WIEgsfKoUIk|aMjimhTN5PSN>VY|Ehosvcol>l63<;&ioq}jbTLdH73 zzo*u3rpgIxvz97p|AbffIQzr_+o6PcuKVh9=M~d5%G$`g{kDMCQ(AvQ$ubtP-u#;~)h`c=@Pa;*u#qxBA8hbO}(6T1D^C`^2G6RiHR5Gf{0u zI^4kYRM(+-;mk^cPsvIZ?{z%zNsv0LaE+9F=ZulkU}-GBz3#&aV8Qh{Z)2C5;>vrZ zHFoy9aUO|Zv!+e4=}Ks-^`K_8E2!2?+0xdoSwmYebCNHGJALv*pL(09r$g({J2y&y z@q~_PX6yAvj%hW6zoou=pYkwqG>pcYMxAc~nCxYq~bs=C_vq?ScIH9lg z%NlKI%g5R3r?*+;)H+Mc8Eui1Yi#zREE}+5tSvwHn2p#t!-lS%Y&mB(TDp#%xI^XM zPOY`xONZMW9XIDtw)I*v%$A(cI-gr++hqN|`r;NFxN?HcKb&pZr`KEBvN4wZlzdu; zmsy6cvGT$uo49kn4P7_IR_WN08>d_M#Y3&z+(Fj3ZyV)sDI;IV4wmAk8v-2!@f>n; z_!*>?(^Sh)9t*(Lw2wCmU@i({FOAMz=6VWqr|Z#29L;w!N7-KN{MA=q+Ma`tic-%1f z1H9SQ*p>YbOp|7D`2@yout3X)=1m^ z_sq05s&&^SGsDvM&r!WQB^a(Au3~Gmt$}{;vT1@Zvr$ji=)H5AwbwOUs`B4}gY&GJ zs^L)yFMZ!^YqTWIdTyC$y>*{Pi~C#u-P5h}dPOBIk=4If>pvN;A`~?6y8+_)lQ3G|PlF;I9MBD1v5IL@rI9)51Q&aO- z6f<%~eyGceOTj^iN)pDR@CnR2_0F(wzWvJf9C*U2)@@;rA30&){rOLtu^ea(TXv1c zrsT${;4m36W|HErbY1CgPoF+wvnLJ}b*DSb!5CQcw^EPrY*M@xzv_ifqunT~if*|I zmc&s+nlpUqU0!wN@+^Dr{Wop&$l(Ekg})}UZk8)Zc*U}81q)|-z%U*v?ueoqYeO~U zz4@mRJghGFzHu~Q4)^t>{Fpah)Ik&Tt9Jtr8qc@b6Bo{fax~&kP;|AL!#p8?tKqKk z&QWKv4NtM3&Wl~^k>Fan>IT1X8Q8hSz)m*e*dn`sSPLtzdb!jEF3?@&z9zS~dIBev z;~$#S-Kx#)p@O7!tZrtSm7kzmze5{YgXM!%^|pzXpV-Fgs0e1E0rjo2j;ppb)e5B7 zwTB~VcGt9ymOQqFHC#Q^5=J$%d!}~K!d-)`*uVx>RmWCe(A$cp)v-ED`dLNYvxLrj zB+}o?jc8(Vogc7*9q+f|9jjVP4VsKC%2!md<(+asgvO<5J|&86Z%DUL@?$a= z*F{4Fd0X;G!dpnLfl?uRogY2(CzE?5ae2-Qkix@)%8oY2vVst|7JAzEKX#lcIA(wZNtbDcP;g^Hjz zwM0t%Pf;~zeNR$h>(VN7T}pMIlV){L!Sc3NMm4SzXLr=9H(CNfp9yoct<@D0=XSKx zvsC|De@R+1go4otI+pWFswjD)u9cu_*?wIWJ};x|Q=mLapQXn()|x7M7S*LL+P8+? z*5*D5iwV|rKnJ@$G1*04Ks3Sogq_a&LDKL5t>VgeZm;BSIix*?JwIE2Z4q!?G2rSk z?%YOAhNoL}3_csl=`niZ4Et7mef`xNn%H^E{`J$3wtd%LYtX#2JHtJWP~hehxC3q? zRsi>TS4jeJ6GjDBgTMgXuqWYB0axc5k&fq>x1UagTOATnsfEm@F4mi`Ustubajq#S zm&bGD?zU_$A7u6Dc*w!=t!?*16bhO%xI0(oDO|tTJQ+el|HZ}j`2Z-(Lxh+Hf3!S@ z(E2DBr0Mb*Vi#Qy?gi{9(A71cN30b4!{dS;bCm)pdy1E{l4IHBgM<^mb0?kvW3W!k zM{MApS(ebVrj^Lh(iG#G2)8XPae6CZOn+LWAyLapB=9$^^H+Yqw_u?bI_VJ0m7J(p3BX7 z(H@v!9=@Y<{TP>h`C%<3B&rVwY#k^e*&w?pevv_=CR+B&bq;H0;|B~M?+lJ=0!K$s zy-PjPLO>on$(==nbCVxCYy1!o+#S@fd(?dugs=v0AwB0X@Yt)d?9 zswTkih5itHR`Bc`!Z^@nm$S1VV}uPL&8Mf6%SEP)HLesNBKYSUDp$jH5dnI9*X<#W zLTsVW{U>S{^CA`4nXk_6TQNm}nGDXX_7W%se1B(10tVXM6F(y9?0lO!;6 zf}hAmG!T-sFjJBimhu~LBdv}BaEptGQFyA3Z)g2hjkQFj@6sy-(qQut$44Uq*ueaY zsbTKj^ae%*>X>kw&sNHUyL%Hv8@!{%Y8XlJjIOh{MKN3|nC>%xn;Mo%g6+|-3RxF%q z3ua7kCI(%h^yf+SmQhthUtp^&z;av2S(Ws19F`(@17{396}c~OaioLh@U;NF%r`zg zl{~^t3NZK~<`{}y9T0+}Hnu}Fo{Q6ZPLAGK`BG2<+5ezVz4`2wrW}8*G@P8J3$&R0 z0Gp%84w6IB-pJXXG;Wl=u6A8CZIsuf+_QC~Ua`EtgWs?q_oowa-**D_yF&&jELq*A6j61_#5_JC>%7Pl=+{nZ&J=!Xf7}QU_Bnsp&&3O?!H! zW?22kEv;s~#@3`od+XA@uddM7hL0F!+c&PVEgM$Z+T}}a$=s>7Me8lkn=#qRFH{s_ z9DBzdFC}5vF&f9pPP_T`tM*^^y2e zaZWPjbgpkFB=VVHkwo#37Mx172ww|R?-tdVPuvOwegotPh%OScb}p8qdb8jX19G5x z(YlVXN@07lCzN=xPwfMJRH1uKku{$9p|IJH6*8N%WWLSR^mcY+p#nPQ*-ix?uT_0? z;^eQ&5&_dx=VKxR2X%P;kbH8bYM#Yv^ez>wjpDD~z44N2FukM3dr2kF&e)~bF4~%R zRQ-L!cFSicpbh1bCOn8OIn#K17lTx!F!eRZP~h; zeg2!U9zb2^WQw^n^H6kNi0l5)bAseSY3a)MOlW1TmkqJm$CdrGWUfL>_NzL{a(iDB z>X)BB=Yhp&XpCA~0=cH@DV13ZPovtmfW31{0on*jN*aduQejAtgZlL9sVw3CZb5T| zAFq|{bT!P2!j&{&9#FcuCt6B3!`z}Uy;qt{en^9>ilk0T1Cjy%hqJG8P+?OIyLwpvB3eM{@mwz+j^)6Dnry)*mTG`DuGn&_D3%65Fn z{cXOCjsO*6A66&p$Ft=N1iEyfk2`zk(A;sfsFO(UR*bo6M>1Ak(=@XqTvIngq z!)&jBwN4WglxNiSll(%vTfaSJzkPVbQCYZm~eB0BjAeVQTOg)hHaN;1%oV2u^p`G8 zLo00E&DyAZ1LH|6^()Bd=#a!i1q2z8582YnrQxt56040?pW4~d*G^F6?wyWa-Um(C zC6W-vIOeT+t00Y@U%+1`8>KlGwEOF;+u#-qBt|-N4ESIqefaJ#w5ax5cKoQOgrZ{K zD{?4GG>j@X^mn%~fBc8)O#k&S_LuMeWPkqSHx~Jm{=56DKYVGQ zfBw0B^YvHug|M=mr_V@4q*FRsrd{V0cY_jkF_GkO&Kfbr0bcMGxkGFlx5<7o> zujMS)3Tv>s^e#jjfWjU{r;G8r^lctDd{mlJ_OmP!%o0!3<(nuSUSK!>(eOze%A2w0 zElsNVVEy-Bd?J3c%8lbHAEip6=_=1ZdgL(cqHwGw^JjV8zk}OW+wVVm!}cp9h(~kf zN7RwxeF|%ZI7k2Cd$XpEZAI1+Tcv5eWyps)Gi}+HY@7YudaFIVm(^K0(8|u1w*n11 z)JJYbI5-8b;1&!E%gF+E(pvqk8=${|mZX(*Gn4h-y=<{3S!-JR5gf^Q2$7Ha;;Ktj z?RL~_Of3x5ZC^4`iwq`>XlxDTBpltE7S5gFBv<3%haE+srpG)} z1XvY7I}7k7Cp;UaXmh%5n8F6%{>5wdzT!>^2$6mEmwZce*Ni3 z&ct+Yl&5sIZxv>w;1oM`{IGqfia8({^*oc|b6W@o@CVGTn(&ZEOgj{*Eywa@`^=O82;u@DE1>SH=q zMg?4;IlQ1M$m`auaC_wsU;Ne<&YxqyeE)4b`uIM3;n@o!ugC1Ok3V#_2WnYd>NdKZ z1rnHC{^bX6*$;pFi;WpM#9FmzMj*}IR>pCsd(hr!MT{NrOV_ew!a$WL8JO13sMr8& zIqAXjkRKz24Q2Y=BR;x47rBcU5FGpOT;vvi=gmv@^ts*k{x4s*&lD~3*>7*k8UC~# zKepY@o;hGkBQvB=qf1AzThw_M{0h6yyLuV!MsqNT5ZakMuaqt=*Tg`N@b!)m&`9_Y zu6**YRK9}^7?->!NoQ&vb?&#<&2f`4=EZ{~Ill|vMapAw@2l?JE zDiq7JZFNSVL09x11s?PSUQ~J^XURPKNufOd{{AalnYqBHs8Leg3(Qa{$Tv3FBlx** zF4O0WBa3alZfqs~@BjYK{`2pD+du!QP^y3aXg}%mUqAh1|M}0q_4gm!xnqZwC{f(k z;2{YvLYfxm}Q_(J4)~~Snig1aLeh^<*3M+)6caKK%I(^U?N%N zFMjvA*D9qx2=TX19^LP8gRjY(aOvVnpTnTd>65_j*E9ngC20KyiZrBd+^ahJk6(T& zXHi-Z)2^ez1{sqKFQ*kQhFgxnrjlFJ26G4#FeKfXo1x!TLifx&__LxIx>7@qh`$G_1b){HFdsw6FC^)jX1q7%-dz={+OO>(5H{psLx$xu>A9}QTpfl(=t@ZOK9rxvDs$`|)sXu@5i30CN`@I63a(Aj-WFl$(71PY`avr*tCKV*#UV zu!pmv^3Z)SlP9W%$K>(e*0dW7)M46}DO1K5J^}y)0Y@;c3Xp!r2IXCRPf>mgBz{og zf?vy(4;01F73Fgc1zq^6_W>lM#m|o;Y9o`A;<=JvmjmNDO0M6aRtI1MSffUcFjg|JV;x&HR`l$n*0y;=>mZL<^@pnX4Kz5TR$U5j9&l<`z!f6e(zbbw08`lI_}1c&lrUh{_)3O z+YjITO8JAo^HIRH0xza>CgkfDoUdmp_N?g1Ak-N7=$mf#DqlxWz2IclzZoKLovgExbv9Q@)>V_adR|PT6>C@|NWCbn_=$UGDo$NNark!E zWG~W^9tZ5P)tSZ;7B9VU(GAVeregRx3WY=;v9b6QS{jGg0%h>co<7N!1Mb{T>w2|p zY>_VVbtX_2t7qpn)?I7P^iXZ+uG-m6PSWn$=6kn}s$HjjJ#-Am@tyT)y67sMbrZ!hSYt$84=Z)J!QLJ-p!O)JfxPyxs32PuB+^_Zshr1g$s_z%zmnPcI=-o-igDOahDZ!zV zI9@79CI>_UsgDXVSmcWOd;H+;DutA46P2|&V{E!*%^GcO#g!kjX> zwMwjBbZCq9+_}WcZy0H%T!@dbQX7U@y=^mWfmRZp|M+H`dSJbkUpw3qwBUia!Lqw#fE9cwYj});KnId>*4Cwv`Hf& zO$)jTZRnT0IoRUUktZ&6<50wa))(kX@?%Jn^p)Xp{gtamYGgH?zpRE9)3}W?tq)0S zheeqxX3pk*HT?sk6lv+vMR)kMs^Xa<6e%b~7Dwz@VIEV}6{UE#@V&@ad%u-nR)ku0i$&g}%}hfKXfcrrgWjesKWMg;nmB!?PogM1N54 z>^C31A6&JK9~`xwyJuOSGg($a?36$-0Bj_NO3DT&FjT4)kMy>- z%9l8D^0;)|a|)6^YtQNP+0()Hv--YH6)q}o9A~B14z=Q9%8ol0+U3(1w1(MvJNe{E zyJyvKE0djW#g_IFv*p+e%ItmS%vpQs{4+LHI4y$3#XbGr(k%5HM3I%5-N7o(>1u7) zjzQP;MB>7cxg10Rxs>j&lm8n<j%db9-rQ^G`&kIf^8braVc*Q`KjDfTK!2|m(S3A_HLJx(VDm?L=nj{rjrM&PrR6v((mWK9uBT2eyuP7$vsXY*KHn zuec&RVw*RvQ!UV`ZcDMiG@}dXL#o{s1Tsl-cJ0b#9xyp>%t(=TusQ%!;iVXzjMnQ#I++ z{`;X5N9-PDG!$8^0P0l}bo?nhtv{{<+$Zc>ZbdaTl6^=-4Ig=s2yQGPw`{Rtk6JBJ z=a5ZP?O{#BGqFi#Ka+AT^)`%T^d~w2_NXpeJ$3SkmP(js=fncLcW-rOV1dQH!1MY` zQFzv{EZ|wFmR2qYqHtn}x=dh{0#K_6uRPbckkL^X{mi}_3})cp+Y7kx-)vP0lA~ce`d3#P+1wI_&2N2 z3bb6^I<-8~iIwB1sya zWG`jpGngHndUa&V1UcGIojhuV3l-L!TqpbZmmfG=(bx#~7U_wXuVH+mumh)~r!I zS26wa@+O7u*$}HvY#=8EH0t z>?ohZK%2);g(6GS&{W8>qel+guptAziqu*a$pLmXs#Wo8xX7=;6#*s<%dqBqivGBQ zH?pqAzCJyB*r)HYMC99w#kyv%D3SNYH=eQe?>}K(cPKmYNfE5H!31PVV2$^Lei-1z&CKj9Smv;aA7?`n(B?r-fj&CR9O<3}uc zahi?Umg55;!U*UZBi5Y)?qU&Z6u6;YN`yFaKSgrC^_r0`_g6;d*(o{C5A57%A1Ipm z^=p?DMS|Sd1cly|eu!x7fA`(DHhcC|J9Xly&6_>TK@k$`jaQ?@3UsBV1KZlHGq-Sw z)m^>T9-cZwOvF4T-l|~Ej}{I@IRvZ77-_HwfAreg(`PCcVzt$nyTI;IZ{P*xJPL7! zu+Ilv5pz|EzFOla_<1!KN9 z4#I#cg~0Z;_NABhw#wOq?8u4ZF2zw+Gd3@_Vv_Djndz38B?nZ_KwJ039*5~gL3iQ7 zEmlBIfp(AOLU*@Tf$g|%rfUIc701Ne`;HyE$Z8t(IaFuX&KKc6K$&g2*ROV>A`$jK?q*y19h6ntN6vA ztczTYEkF2Fr7{Ixkq)hRpUy=)aLJBVAkaoo3-0o&9`FB;pVjW0zuG;5^_}Ilf{}VV z7q$|AoUJDgb&9GYmljv9TUXt!!;fYa8)+?B3HR7g(HnMauOJ4&IWV?jIzqs^`COw9 zQ|oQ^xHQ$N8e$k)xSv)nm|z{{N8@x@F)wtX_mrri1yq1EWo;;DGiX4%BC^NW02xZ8 zy;syajiGf)L(f*+4#JK|wJC~l9W*dq(*J%3CD%gQW9jzq)5|)xZ);;l4fh#mW}#8p z7$~reYqUk!O3_tatVw)wHa0O`OQR{4^8p(QKZlW2lq`Epv(|gJthYTUcG%);Tdnbm z;nr-=RJ&b1^aT9qdHB~stT+&q1yoT$oDPT=3B(bBI6K1<1>&{x5TM2a;>7}SUjF60 zBPV4kg&ZwwYuM(cwooO6P#|I;Mzy^K#4vCv<(rk8(%zaXF?iC!#WqokUaeWSMDde@ z+;CkqZ?-F?!Qc;8F+)u}uy3bjW-YNNPaUzbGJxqbhIpzB*XvSkYm0en+ydhEzx~Ex z)#|;EEk!WHJOXy$6{ZEU4-4?sMKJ!!K5e(v@xZbDSKnDh?W-jAbl6H&K*7ia^<}~< zJft3JdHI@k(-|Fq__tMl^ifOEaDk)gLkOuy$Cmj3tdyH8(Urq);ojmWjy+-ZYdxe2 z7j>m9)V0P9YP-_FdQq?<0LCa|d?++QR2ujS#Bc%-gMm_6FUljeMIn6K6r{d;>v~%i znQIR|5Y%}G^60e;W)~yy7U%*P1ENzjJrAk{oTR1p116$sb0W0%sh>%dzMWGHMOFiLl zfA^7c2(J6W;4Ccu%JZk?_kF~h4alPQzp4`2Uw-zUMLt$2cB#*Q`3q$dtkRGuFTe&- zQi%2|&z|+=$#4GRnyMVXB3(5oq>a*U;aaLqu56eEVH4i{nSW(xjZ&eTi zw?WaN^0>}XKEQ^__JCU4J*|RAg9a*1DVam7M=)PYB3me$#+%cE5DTpsv_y)ce)~GJ zx=%}2z$A;H;1;MU9;_i|t0lN(LcH;Au4yBJ@>?t~Je^lH`X5poR}=q&$N+-X1xR5x z!05vYp=EajRxMc-qSk{}6}q**^5r6~i?C(r_9_PvhO{OYV}lYBgJPxlxU z4DKEcj8Z>&2vp!PM5J^AvF+Qm5z61vYUE$oZ$Ellt7ToV7nwVK_i^j8ZJPBs6|wU8 zUqxLpDs^9Is{8EguNmt|gf2r>H0$72+aMM8%qbjPr-WpDuzRiSI?Y6BwyNFM`K}p+ zNJWDfyggHh>|>=PsmA#+EkG`aqE6%CtQ77G{K4HtrS0W^?PhJ{f1Pt;xvf()>bWN$ zx4qleDmU&ed*a|;*L@g`v<0FgoS8y1NKwy(ZG?7^p5E_g2(^~V;|i2!mVOV^w>5imlNqwCVl(xha!Eo6#60XtTgc8kA%~o;fyk!~n%q z-3aFdqWrlM@D+j|1M~%?S6xb01R!OBy0{oC7JwDm1^)$d8THdGrzi$F3(v2gUYKKV zmD{4BF z8I2o=BHv)gS6;p%(yC@vU5u(qesy8Xp(fsA9#z+51D1P; zM1I+qBtIt)>+KWxQ#I=iN@tB9Xw4q2@7g6nB+N?D0^#gbz>xR)+jB)M`rE1GAhfdT zhnME^WyXE9f+796E+DIovvH2_9N6csD;5aZk3F8-s7P(CAENVUW6pOclph?=F8tpf zR5FvOCpw2}%zymdr=r*Ywg3IYuk7PrylQWMa>F+L^0@WhGuQf^&GAsDGQ{6SWA74) zDki#^xMdG@%CJ(}E~dXk%{P@_JIu<71WPG6gdhTLDE3NzF3wmP8Rzyj_6Gdby&+TUIRjq5`={2@( z{c?Lz$&P1F?6>d#_&d9J_DLDwHGPKJeQa2ZTwK{gXjT+KV z-#c0V-d(J}_NVsjq}lK;eok7SU|(7v1q^CmKmEovMh@<0{j{=S-|ij#c=mH%-|ij! z+FY+scU8=ep2K!V-!58V5QPq&!hi=y4^jo#@SP(fKrqI9NLm`22K8S#%r6jOD?Y?) z?ylUeIDYi6!Y?Iaf+ZhtJB7}Fh7&{rK~vv;*x-RSxPO0}uuydwH9JMPQ)Q`q6uC%H zu@wU25`~vU1bK*8!t#g}bpjk{iHa9ZP`qe@hnj?8c?32SD!Og7-AT|W-|~ixCJDWc z*!4oLu8_>tgjx?9L`4z0+7P+tMvWNi z?lWIA*>gaBlzIW%n35^v(mA~qBmcn%@A!l?tA;mk+Q_4unkd4F3eq0OB%gLB8-*GX z>!j(KW=$LF7p>H;X~oDRig}JSR8*6PHWeWR>d|P_6JbrnJ2erN)vsGie>%Q?z1kMv zKwAy8k;x%N8;SJUsHbB%cc3sy7!;GA#4<^~Uk&7Yls#j%PpNI&w_D-Dg^dVi;;4yc zWt#|mW(KeY(J4bWz9SO*5M0FazW4$#ATm%1IM^5BHpE(pNzfa^q?h4xsT~*F7i@7_ ze0UwdV?juhyM*&k-amJ8U8Vr0j34XEbWs|A%ur32MyA=MbITo!4{Crs8=(P-*Vy;@PvHk(_KHIOUU)fz)gf4uO@xcLrElXJ?11ThC^}eG8^F? zhdQb7lZTM*iiuL&Bfuk-^-u})0`7hn>6%&~vMTU`YBFC(dlXgl4Bq0_h$uIF1UZk- z%O}=LJ#${mAa+%w^c6Sv?qF#>Kz%txjg6T3gK)}6oSHBuAp|%RgJ+|7Ym^r?h65lO380PI~)ewtYiCj3V*sObN^e( z_D@`-$v1DhL#1#FL4HLEXZWiD67VpbBA$j3%WcjHeeEv!e0z zBkiI5xI~=i;xZXrqAH-pqFbUyfJ^C=BqNoPURil|7i%Z0d-0jIF2-2}>f%#}?ayC+ zW@n!~=4Ezq+2RTWe{jUuu_Nv3l}nn9p6q-XmU-Jz?-kSH1E0VcYe8#tvo5~C)-Z?MQAQVtdf&`3tL(5UbE!&Gzy;9Qiaj-4S4 zhrv(~CJyvmT*e49>c%Yf@{7;d^ih3f2o3bP&jphQ+vyd zYTLS%qD7lqzcJ}H_Q_1Ub3_X(C+}q<71kCAkWw@WHo}wXTq#kS2zq`tK@LFb&$B$m zipoDyJpBl(nh%e_R`JTtuF6&R6g%fiT{YxN)XFF(lL)>NE=x{sX~hRMP!)h4Hf+mu z4@9JhDWOj7Wx;_KxDpKDaiDEGYL4#3%g@;`1#(&5wZuX}UfOyZmhRgQ9_pDE=QF7$A`;vxD% zb&B3*yyTyKkA>vrnZgX?MN2V-IcI#DPhHN_6y~C-Lv79CNxnk1yM@G%up^2jenrGK z?3jx}&&vwQEJUJ96X68Bg#;I15mL)joi%@frTn^N9B1cptVUrJlh33bV7I$09OFOu?Hx+HGMZ+2RNBOzyEHT!7?$t z%XL1Tl%h|%m*?R+`9O{(&UrFXD$1t8bcX0LQTTMg{&!p+exy8r9T`nWDs%3s6V|D< zf-5_~diJlVi8i2#ol zDsfzfMM^l^Q#kWtQ^MS_nOoqY)WjBc#~3YTyi}>2nou93NW93x*`CU|WAg?N#wB?G z)eZE}_^efNR_mbUEMKC@rsEb_y3h$0eal_xa$DAxBNy@npUh$s(o|={B&*3>;gDgz zpl9Ha4yNW9@u-La6$+ds5#iOOuGSnm+G@<0Y1PM!4FZ~U7nTEcgn~{#GbleH$5K@* zMVe@h0Ryb&j2Tv4VNEIOY$8zZb_clbrw-0fs2fAa&#*jeUCx*#0xa8<6coU@#(aamxuV2?* ze&v!a*95{4l``aw8NnP6J_F$%@F%jJ@J6DR+J64Eb=Gu9i+4V9S0AC0Ts!1H%oZ2$ zAXBP<3wa^5^}8SWd2PS?i`^@0=uX+!v2eRQ+!-hbL8u zXasz^T~h@7@GXQIPXQ9aC?I!?-WG~|enGJckLJ^X=@-it?jle>#JM-fh2cA=(q#ac zS7zmgM$$enKYiA2{^Ew#$9&eFId#m=zjWGi-q>etSC6(%`({`<5h#^MeionvJfo3n zZU}c0WSXcNeE~>ud#1@^Gn0h$C5&{OAQ5R+?(y@UObZ_oUjX-Jz zmR5bIyH%i}<+33*^H`28TQb+4JhIQ$tz4=+&I_J}fC7VpMRSFN@SI$pOI5?8f4Y_k zX!5ALKAk=_Yo2e`2YAXR2cGS}_@l=a5ma}t+6#FIBq2(l_%6*%5Eg!Qoq-jEHQz=- zbwnc(RF@*pd_@hMkZ5Urr&(Pg6GWFH8mZOgmxE{|l_{yL*^_&v8ssI}9?I;@g{4#H zwIGu&N}aK6&O|Jt8Ke6tlx~og56iHb`dd7GglE!0o&*~IoTctsgdpOu0aa|ofy`V! zEWy4|))$jy9p#s_*GGyDq8wbRFt1yE7RtR$qpDn+an>j-L?BL3boO)W8aq6V; z%Hy1<*}d^Le)uq(l{4ENn^h+(eqSM-$*M@5076wkiAw4DXjB=MiH_2!$j8s*NEPBh zs)TkXCC1{wY=o^l9hnGoN2iVpiPP&c;5kyxXjJJ;oKKZ%QMdl6_?M_>DLJ-@f>Rq< zgZX`I+@1y2yL%TKIw(VtiT(UNSRe`l>?%yf$wwwlw&t9(e5F-aoDKVeDNbWyh(j0d2=&fEwWgxot6R}Q^;CnuxmWH@ zoTd8Zj?7TNQ|CNtG`TVw)J1oNG>T3T$8=Hzaty2YLX~;INc|cIWYh}Mr7+RGh?yJ) zNOUi)Dyg2NN1!BS@llPeU{6WYNgZv#hDlcb4tb{KWPuxQmzx=f3!tPG9hklrtCv(N zLeJ2eSTX^1_OsWbX1hZUTo%TmR8!T8!~w%#D;CI6#OKVl-<<(aun4uPo{@t0v8i~UODDme>6^fHQiDjdjxA=TA}Y6Ms?XFn&|s)DI>Q#{D1PFa7)<|v;PYE0R=y|2n)Ya8>3e2c$?gwZi6Qm9 zyg60IA)zu7moBzNOjHUfBU_!+<1)eq^Dfvyl--YD3>7XDwTKd!LqtCmy4a2&-HQ#y`;ZLm2&-Fxk=ZHU|_k^Lbk&A9B*`FBWFYIS?~EPjrU+h#~;1Crtd37rSruasj zM!3xcIYeR`H$+VoO!I z*B=?1)v8KzDl(nP$$TioSQ4vXdFKkzjVtFBy^gQ?;T0?E$oefB+F-2-RklxEE2dI!rAMh6_=KibdZIk7;+Aq+ zk^~#(c5zNw`Grce4{8%O%4lCXfe74Tag>vqS6bU;g}B?bT}tI~@6cy57+b6rJVb$D zD_Pj2m`G_s>vr+l9r`ORAzx0vl?Bs6Sb6+U(^Z{ZOH>pa^@tT8T-OSBs$xx*Zj_oi zI)*mhFxCc=9JzoC0{A_W7QMJITcOY;%MDb4j~pPT&@|2Zv6U}0?bZMxR}SNVoCm2D z4C8{rPmlhItEM<04^58;U;YiSd5SzGN^cda3JQ|N>`P(ZVlkK5vSo|M^OjO5Z>iG! zmGMtPzM*z35`=2#2zNK6C^QtT&P?$%5}oew33kzD>~_e-`!}G-MqKRBLMYsMk;X5M zAypy^L@7w)IzG6g3SJIZseONCDTR{T12#@kY;&p=Zl?v9`q#FSLmF6dEm+fV-EeEW zdx{nzX{zE}Bdp=3(dzA{)@t80tE|k*WVy)OKQY(J&gx_p^}Y4uv#i9VmR4ueD0_7G zWGkY@cbe~?ZdDZydFO&|*7^7XD?h)hRb8HL9goblGLu``BP!z2Z07{2ZB4E9?nzc_ zg}jv$np>9x(-lY2#cs=xZ!oon73%V!CHJUpLk`ckmi;?8x?-&m8-ZABPG=?jjb(I! zDZmxl%psvMNr<1XvhRN?#Z2jzkcJJhlR$;8{QZ1&JG_0vrQT?kXI$weEVMr5;?;zS=`)+}H`nPp!-S()sz zQcflkbP3nlv~j(y)I3XM-c*}6O>vP^wS?!y5jJDuaGN<{xE5UqX$`J^5}t@_R*Rw?3$|cCTs7MF@yY*eH=AmWQL7bxDUT^ z0{bHqMr2q#tGW1fCJaxv!V`5I3#A8PI;tt?VLFNVZQ58+S*e$=VAH00dKfnCLWSL~ zSu{x)42pj__QWmJUu^c-amP5!=BF5gImNm0;864$5OX7WF`@nQ3ZJ z$#ueQze15visseUFmW+|xsvXhVgg~19(GTKyR2qY#e{60W&`)B; z)1O&u{dP^W*)MFg@n@D>hD9UB*e248XfZxHj^Fr9>#c45PIOqm9`aghn<%k9`txWrMVt{mMl@N39Yr}S zI68 ztoZ)i(Hr&q0fdm$96};VG(RMBdHH%GY!t)N$P2I#XzUBm=Bk-kII2$<EK7Y*y%^Gew``6k}@~M6Mw?A4vEj!JS2V}52Ly-4i$f1Pbcn-Z&VcP*u;ELOy zNQ96naZX=<<*GZGk+g)#Mykqb7f(#>Lv9Gj#h1t~qHqYDMb;vR5x13Os}OvHL}ees z_yMUp_v!0*+vfNX^j-s27plj$wG`NfC3V-nuY^h%nac=q6Yg@NA}yv z!+Y)cq1{>n<&cMqhpSR?th0ebtr$9G%NEV-$o^e+^ZLtLPqf*;}XEC4^e)A)1Gj;-mqCf^U4k$y+I(4j~e0yS9t>&}F&K*Bu4@oh) zpj_E?%d$KV?2Rig*nqx$B`Dfz;hsxYuV!t@tkJ4E^rT$>gC%F=nbN>#gj{owd}*!U$z+&#;Sy4Yy0S}SJhAL z>^`MWo;!U?N$)egvHfivp;7vb1AD%uFP1P}izh8bL68M{vVZIBJW9&yexND1hu)+p)bjG|XcgVlhPwCvM zb7@Ah7il;D{MOe2A&rZyA3r0Hxf4RXIC$l4VHGqk7={)KTY|^SciTd_NKMKAOA{!5 z?~X0@uCRkg`|1l%s|@rZuZ?{3o!3=qsk_z%>R}(geZzgR3zR2xRoDX`hxYDJh2AZa zDfb$FD=LP}nm)z8`|4MU9BN^EH2M8M@4xP03^%SmuL3eheO~AHzrLwL4NE zSN(p)Myld2M1ayBjICguA!ky(Iqwrrl)|L!XCF#cm(Cr11+;CNa9@@kaqW|~z?>oG z5&sMZa?BYRhcnR4<>HvgIO~{_1EiQeZjb1b?_4J=T@+!8q!5T@gI_ojUDtyvl02G6 z-`JZkOhVV@4A2Tvolhmr(46VZTg$;jZJtEWD$U2I$wv+!QWdBBJPom4Eu|sWtY!^r zKP=!^j5=;Gs-x~fA(rOhHcn_Fe;&43lg9S-uRpM_K7Gp~Z(ccP1>br3Xp~^5t=s?@Td@dd-qiN*3a!%?_akYmrh&c#tWyd$bi&7`EZ{1to*E8nx9-DQ_ID0 ztA2FcNzw_v@LwmQ|pA@}F9p`sd zOZJ8kP2KPBl^3~FwXC~!(UkE2eedVMjHvREfsaHn8gEev3ztVv0IM$bqg?ApOJ+Q$ z0*)J1-}~y-OUB$E(jQEOuARVf9q_6nw4?|2=qlCal&&JQFw$X1rex8HXi*U7Xw`8b z*&RKF9@0@&r1w=8XG2%+&rH!JN&pED1=0~7kE>@7C$&kM<*Z5y>Y-u*2-Q2?8$=!c ztn6n-h0a5w$L#a+uU&iI7EO`+dge&4SxEfZ@_EY5Z{En$5*g~DE1TEn5orz@l5R&- zHCM;}`olNv`U|A&9kv(F9kmxP9Je&-(ga?(ug2HaAjja#Pv6&4D#z`jQb3g|%z<%-B3$}T~ zT5F*AmUrKH#e)th>hbn#FMF5Gn?1vxzi>v+a=V>8a>#awtQejAPC<{!6UN#PfBw>1 zs4(Zwt&iDj*DgDRZzz>=|E{fyO{i(V`|PF?DW_P6_HFG?fB4)|_0CkTp*wj(h>_N# z+ATN_v-tQV8lquV5UY2ms0VUb||`GZ$$k4oY4uw$(XHyh1Vqfa5~i z%=^j8uY(7q*_$uF;HzI{>0H*YS{_+ok2a_iOmPWooD&^$Q3cf*Wl*?3yk-DgA_=I? z6=(o~Mvyz%m>0I-IPbI3ZB!G z56_U1mg>jVty4#`^>HA>U444@@_`X@Xpq(y z1Uvb&MxU4MpMx+qC-1#(?Q%PEc)y~^(*=vW+z%D9X*e^3l&_`t3AU@4g8tV`&fpU}xbNc!PoF;6+mqYqxm* zil5i+FaNMgl3IlK@TBwx1Lo&7R;`%zU-nc5ICZf&HEUMDsf(v+P22h7t$jX&FIMBLfa|wxHofnPPi;BFq@Wd{(WBS`erKxEKS0 z8V%Qw1YCq>NOkh-=IA|@d;%}#FYY2ZCIj*QijjHG~)KPxpXP^Ai)2E@D z7~^_88c7f^uHq#%zZ1f>-S7V#4fy%Q0mt(p?lGc*Ihvs0kk3$;d|2ibs&1Q`p9KLw zfBc)>tAQN^{79vWDhZ(p20urb6e?9+ZPV)74L_@+{2G)X3WI(^^Q%Xvyg@(FxojCu zvGkl+&`&8=TWnCPsx@s`#~MGPG&QB=G;LT{O;*|2F6a_1BBbsBtb77gZ^U3iP~ZCY zQTDQUlM-CguaQfVvOI<^^b8 z?bP*BR07F?7LRSQHpfp`vsG&qtrJXQ13`csPC{m~QOx&hquHu8*81o%YrbuVRTI>! zNox(Jz*R3pS8ymN;78yLudksannp6MweHhm_g<@}2*HQM)eHb^GLG%pIS91KQ#2z` z1!(NRVHyoKkH_{eP@tein3F63& z512)31v@zI$HA^fu9r9CXo71_$>9a10(FM#aM6!}ErNBd>VR zXV@2sMfvE>a-)2LVl4pH3%L|?Zq>ICn$=Ykt-9`BUH1s%E=Z2d?5+tO_u>mS0Cr#P2{pfOJqoI^@UT_4V9^@6@oS z5z)LjIxr=oQpe}oylQ_b6a+HCXe!R;2|~UMpCSa}Yk4Aoq5&D=G_PqD1O$P!IGD_N z%^?*J-2s?P_Q!`<^aBbYjy;IiWwZQKL17lh7aSK2^C59t%efQNm>WzMGj~e7qNv-M zV{<2k$U{V1B&LyGWafaUO% z#9&mklo{Jkp7srER|uX{Wfs@fRM!6+Soth-hm})cSssRG$%irZOn@;cFfZi=c=B`9 z)$|y6q9@tMHrR;p&hfYyP!|1WiD1Yv=42PBcHEQmLIUIc_#R*^kmliYv5((e6}$^u zi4{r7oouWO#M;#*(eF}3W>QH7@s_f?%a*ZP4_308GLLJjt81#tJ;^c1GFLo>{-4Df zW_g~_M#9M$#<}&W+-IctvuLHNAl%kz47e47)dJk*R{hHYf46Z=D1bwe8lo_aF$>8p zs7mEk0}_3DT(-8FG@q-oR8ai4k0-!R9hItjD;b)RoMz%Br;OKv7mvoQWyhd*VKKS~2O+k}*%OCltBla8<7}q< z9MdL_(FEPY?j!Y6JT^Dhv2=2@bA!*I6b$mlB@v>lI8HY9@X%qm13z9M21gwTjQ&e4 z)YbjI1w#?EkH!>JkXg({79vh4oRnm;kzX={a3Hl#0p=-vKGIKB zsE~^N1hbQwOi31i(J{=pycVpu-{RQqoLu+;9Udmbpw7|VT4ERZn(OWvJ7!c+PO>}@ zoIG6X_KZolpzKeoEuJx2h0#=hTKtz1)#{-50D|{w5c3xddO%1b%CB#}X>VPB!Ct@m zjJ>YaF5l7i5G8Ez2#!4$h9&Uu43Ia3mH2LG2_LFVa`^R2=XJ}bT3-Ol4LAf5dW&q8 zIwjd99zvCZokFL5_~}Ylsa*KMU-*6k_`z(>hJs&sb_g==>JM6o4&z9E37^G*>FH=( z&sh-psOtiAKQEqR85+U25P+(bRoOgOIlLaW7r(wM51Cx+_S4_LvA4A-^8E9kT7@S} z{dnB0US<7P<%rqYYj4;&ExI*nRJvw0GkxtyBufZBw180c#ADK5lMSDIa?_SA%TlKH zQm^E@Wa)fcw0Mp!&>E3*=S;DgGbZS7oJ}LDXvTQ|oUSON`Lm~pK_)2ZV}#aZ7^70w zqiyn}kt%0RiSaSA7IDIkuu1xTB9TY>eX4$+Ic>bEZ4C9_$1D1X-zMwWv5FmOLy=)A>@Pok&;Ie}->7)RuYCEvfBfYO)$Cmvqe!6U z04>HtG3)rlx4*H!ef^pJ^{Y?)^B;futxXyqECmVn9T48raWUi+%!^J)(G3L;{w)mz zLtd+_DG={IMn3Qig|)PLzz3uNAfV=wej6`nz|laTz2OLSaaxFPF=zrr{rTXD2a>Tz zjQ2;>6&#jzLe-DoLsoq2`eily-|Zhie66YX^EUsq9DoPR?muXDpZ+T8uiE4Pu~U~{ zvC~I(D_m@VZ3UP!C;KAUJiXf|d4TDIL2ox|)KFWrWUkGfKf`7UY?B4DaRSRIU1Qkr z{x*1U9~(5Nj|~{8g{<_Kp*RS>j~g}EMh(xfj0}}q)qai}I;5`+;cu`~E&e~w-UG~v zqUqzEvrAMY=d`;-MMQ!~5D5xmz=((vR8U{ciPwmtyJQd$K|#ep&MZ0SEFvb598@xj zpkUUzzkkh{vkUrt_kMSuXZG~WbeiseS65e6SL?xf9XsOBsy&uTq-syh2RgN5IAE28 zRYg0lyY9Tn?&NCQww0yd*%tG8J;|+*9(N#F16%}^K*c9~O7z5HcSR0FH>gH96c?&} z^G!E$M8OXsHmkjbGu}LT@(?Y4JPOQaWE?J7o<%i5XLib|9`h+21=ccM5ug~zfJ zp{|?uAN9_#1U}V2KI_t#N~e2SJGI3nx9i7oZJKaNiI)8t+@)(IMRE1(%%bDOF#z!t zl0-Tj%RwTJuf~N*C#uBJ0>m-t(#I@iy3$AF^qko|uS-^i-#BBb5f&j)B{^0>im%qa zYGwTcd8O(pYp3E`Q4rQMz1I|^=bPEGDqoyG;~jS6%GvhJ^sQDBU{->DR^&<@C&2z~ zQClr8sTZGr)_(r^jOj>nCyVF3J>qRYqOo3`I(a} z*OEEYIhTjiMo6KKji9Pu&mln-MbgyDPL_&lQ7%?ae51mOuk-?po-4NVIq{xyLP`IG zY-C6{MMOhFDTKsD%Yks>B?nn`P)IpM;_h@|IwmA3;P|`HOXn`ao=R8ljy=*x^Y)fa zYr&q*qyNG7ZCP*ctUqMc-#cNcukEx719w^FA>Y`|9Ot_3i>>fCoUoQT){Y<8Zg0IY z&=@@xB|PS;X~YaRWtbaW{n$KQ+}^%($K@raEz9&hq>ftO>d$YO&Zm= zCRbqh*YI*nZ%m*-Q=TXf{YL3MO!CIWQp_f}Pt!pmI`L778leW(bA{7&lN828cBv=2 z$)TffHAM=OB6Ql=z}#K1r(pO>_ZMjx{rznN^^sF#?ZbrwjGDBx=wJ z8tN#eQ->z<&`pl0OGVlAMzPbCET(duf6!w`C}c1$D%}{Hkjkn2ilt)4ENTX!|eK2H(BYjnB}G7G8_ZVKK=Uh{0)2a zjX}hH-9}=f)Ctdo;j4{0F(XO_E#LWtCvsVWP_ph`yao=QTxfJl_*i4u@$SP z*$1PB0{a3!1R@!@4vA75t4HL9N}cbg-3Av{W%Z|eB&k2tmyT#f4pR8%@}xjeb0QSd zEnib8QJ_%IFf!ff=*XoGO^L%>)JtC&;nUOS7Kjupf<#zsDB;PD(vZ?d^iE}|l0v6a zO7as{I@^LhrV^ERy1pZ(kaF~L3pqt&XgXabx9C^HHS6=kdZ+|_Vgj!8S2V)>J7XdV z>M{2s8_QpXGh&Ua%C&=u*eL(xyT#jq-@k+k9xfXMPl#k$w4WH;B~ zjlR`64goZeLecD}L3Or%yO_J0^fi$_@Z}et0i9>K;&e5(Y5g2qJfCA)cxLB)we@3L zxOlw%`uj|uK3y-)TeE7JZN!f2^UprB?&x2{JgBqP!D`5;E7ZwOTD(7e z?VJ=fws(PU9AAmY+3=|^RBnM{d2cyY&8cU4B*;{SBA-Pr!CzS{<%&45k@8yvMF&aA zldTBQJ?+}!JGLG`EoWUi-{b2dnE~B@ZwCkU)yfbR~?rjT8gvyGz-FhBve4RdaeY~bgRbEeaKU2bJIEa<=#ILWO}VLaxit^T@x-C8B|# zOcc%OohUvnFHDNsxg~puV1d_tQ0UaWN_=vpQF69L9Nl@5Wsq_bZiRf+K`E+|V=!Q0^f2%IjT`-* z<;k7Lb$}AJd(-8VL1!pb3yDT5Z`5evl0i-99H#;_v!ptqDn!W5wk=KX19gGt>Zo)q zCb~w*{}0MkI;s%85b~O1do=2U_w2oQN7x$!dRlAtQ*~^6n|15@ zsJkNW`q+Q){C$Vj#KrxPzOOj>z45x{*1J1{^$Q~Np^FgIRN_h_y`pQ0QXa!D zjW4AXwjIUsvElSP`NF!FS*6P_w+fV0Uf-nl%jL@(?*7Fvb47mEQ@untI^EsgRxX-l zOXg0qrSmdv`GOg?eBn%6zKBCWm&~!{OXu2Z=xX{OMHj;N}-NSM`2sfVw`9JFumo}4WC3|gl9 zQTgGp89&=CnqBE6PD|M=-`mHlKWX)L7cW~xl|JxTdQFMYqIe(YkvGY zYq)r2!m*mrrq9SuBO@-<(Fq^Xc(WJ9HU9=9Xat+t)sMVx2b_D3eMt7 zcI;P7o9X2>+qvJ;uv3aGFV&Dj_1U~ae6Nsr1wl(V(+Bzb+qXeV>M2%RbE@7*S|5Tv z1fo{(y_M9bc4&DxEvlALdux}UlgdC(od(1)%B{cfv>`^-*CCt7)WN5zQ`H3?FLqWp zm5w@4coktv;FWx{ccB7ZO(j{ODs5tF5>e&7++q-WY`kse; ziV+2gcmt=bZu%bgY9;(K&|4e~k27uZO$*jkq55rs%m~_~l zJ+&)!py(lGcB&PUSkbRUN?+li1`qX)0-FQ*X)EBwcp0=>ltT zDf53%g<^VEgS&K{!|X9K^gMU?{1O-G3I>vJi-#2s04g3cYEHh!H7%rbw=hC zm)j?JSFCChyemV{#Zi1&t@`z?`NCy(-L@Upbm~kOJY5VPWz^v&M%W+4om{z%QI2L) zGws@K+wH2Q=<~@)i)RO*n|tI@x=0Fe5g*q0y$?Nli**~VDrL!B+&!h|6cLbFumtNa8!?fI_K6~92u=>H z9ty<-F#*mW`Af%TPVLVVe;Fz=@UqOes$Lo52?JrzL&Y^c=#f_iv5Ug0qrO&DP$19{ zQk4_b5_BmqeXFRYa#Isl<_O^kbxQ9|>h0#=<=gR8551E*@a66=*eAH#)Jj&z;c8}6 zj zlyV7mk$hB3(a@n<+})Mtr5v|7+OljcMfn2$_3&?WScH^GZRa8Qy*Pd2iCRZro_Gs} zn1l2vTupPAm|NmKa5jR}X5NZneD3rljdWs1#2PtkmP?`NiSQHlQHV(=d4bnKiJi_W zpuRne>!d%ubOwj&PRSl$X6)Lmc$7)()ZsnWjJ+7r;wA`QQiR3?NR#z0qJRoJYV#sm9{)up{ZUWYU3g(qDR6aC;F;$ zV&8{wt+t7lO2V&lNVIzN&0)_dZQ>vq#q%EIp=wwc8;E-K>V{ODF%n@mI+wgAJ1T@l z$E=?$8oLyD3b2v2Tun>Ttw^a5>-L#BB5SzFxL2@rzgY=?ZOSzwlM!IWvZl+L-Mwci zZAJ)L#Psq991_To)r>`xwKr}|U+LYerjGe%5^z|01aFIQ6f1^vQt@?6_SrdP=)*yv zEIn-;z5=#WxvJJnv#<;96%aT*PN1y&C|yFgsrMpG{@!^{59N}mK;yG_`pdYof7Nxa zI$=jJ@)`FWxM?!>e$e|wsFXs&qJA4UtjiXWI*u>#k0FPhrP>wuA{uf9G+0MF=ukgx zF4LZ7VMpwdXr99Q2H{Ni`n+&v(3GN4sOHtk^z~lea9I>@9O5UIMdT56L{?ksNs?|g zR9&d2a`FmzVzJslJe`9?E-Hvb3L{?$0Wn8ilJ=v8$|IgAkQ~7;f|YN|i3vi2UJoG+ zCv2h7u%2Xxo>ojfgguY%AXLJfqN-<8OFy|}MZh||w__=$578GnPTaYGAP{|Z)^8Tg zjGnPfV)|5DN0YQ3C_e{nppfIm=TPOUC!&%e2$|nBH#>Py4x+1*^zal%sm^F2KsM zXq|fqjKj=7DkN%ZrC#b(hl_ukZ?K8rB1mQD10#s(y|aBWh4eHF6>5i2+EKx>bUOY% zQ0!hR)Mc#-gp;k9r*OrQ)#7@q_@2@yXo+ET2+8SV-`HP29<{5lYT}cwGklJxEXo#( zD4Rb@ifEjEJ$f#|@BR+0?LQrFw+eKhW>$5nMu$rt^XN&2EDtcp_-5NiTf1ngEy^5i zGbg?0QhOJ4JMmFf9c*xb$|I_J_&lO{@s)Poe}XOqkJHL*sl9>ER}&~7<*Sjda&#}q zrQkPJa1+;fS)JP9js|_WACz+mD=?9>a3w|{Wb<@zgu610X{Hp@;&=I+*0E*|_tj_% zM9B43t0tLF=<7wjq^+VpX86reo%86eON;oGHT|8p;`fdTMAL0#%aOBCT(T1ZCi*TX zGO<*?L{EHPb!_I=28mQii9S-VghLgl*-(gc;ufeW!cYQ*IkJdcR(E)w4kZ`+Dp^>v zLMah|DKu~&Fq<;!EqnKk zK9~wra*H5=CIXBDl=e$Z$4Mg65jFJoVdqIWF^B!D)(e+F(U?{q-UPYSWQrX%RCaiV zBUUtA&fa#j;r4-h+uJQSTw}Mky2ftCt5HU)mdz}71OINgrkSN*kDT>+ zh245%3yw;{@P=tR>0xo38Zd zc?MT2lg9X}ywa{|*2r$AphvI^l}Vj+li_}ff-A%o`poL>;X7dTg{dqd)7Uv%p&HA* znhe5v)vR)(ORP$>ORehFHLVI)Rl<5!>GF$+gLPLmbZexkf?6;fxRt!c9IXYSwo3qx zw)AKGI({Q6N>6(Yvb|TlbI|Wv=|o;p-^9~6jn&9?8XJ-i|32@^n3Aao@3!1Ryb_3+ z)MVT3xvnsmm-&5Swsye!yzL;##&z$vfsc<=GU51;L!gY+`>xC8A@GM+!+NpS<mWLpQASpw=$m%&+MY1FrVn7{Noea@#v|36HEXTOSk~i3>OzwYKDt9iRa)a zRjZ!j(M26Xn3e*jvIAMSZY8UkaJ|!83z#KY}CnzKV&w#510!dDQ&mZ=`^ z!T=PwX#&%*V%tz9W6w(5pB7Iez=mfus-vQ~8lr+}miOS$Ghwx8ku6ndY843RC1id@ zb$hyJR~tNLu)RKQn7uylE$g>rsC8dD$gZFIh+UugsNFW}X?u0$>(+hA0Q>LEbbDq( zck4HKpgq$6DXV%zZL51-L+kYLJ$6a$OWZ3%1PIB=wf<1^3A9?9ilNbZwLWqRNlElf z%`b|icoF^RA%-uIEe5L8a_szw+uk{;4f#?BDD9Y-2OXQvsD)OR8VY$uJ{3diN$HPk zBBs*<$dL#G8X?k&Wr9)lS>MG*(R(MWC4}9|Xc*PDvQ^V6N2`DT%s8djr`D-)kzJa; z+RBYGOBrdFiq(4BD<50QVugL0bIda13w;qul^(>u%)c?FS85T5SBVIMKIr(a?DEa* z3_+Aim5@B>>gG-D+UuL!<@GLeu3GJ@rJJ^-hHCS0-Qy-pIiqE`RzU)zLy*$kT+xBJ7`c23G)wPM^sh7Rw{j+mYDyhFuxQk z+eeIcS|#W!(5=`2aLf0}Gl z{$6O4Pt3KCj%>6U+cRzV@y{%CeWsOdThpHG-&J-Z*73fMR;YLpEVLWgKK540rHeKL zhry*<_<#-Q*UQ$gU1`&%O!QNVwtlhMMUQUj7Kg9usE-jxrw>#2h?-<5;MVBs zB=6+hg1uu1jB6OE+e#rxl(11<<*|~4VX*>g9^ZoD;#8F>bdG&*g!}c>usT}{G(fK% z(+W6GP(0$~%2R?1mRx%m%`h5(s6~qxvXm#LTg9>Lvv|*}(il+OZLJk8l-~vS8hQFM zeMbVlJaee}C=672zbzdh_uStE(M|9L*`%H{pPEJ-;p|z{?c}NBcKYX&HV@l~a^*uC zZbxyOxC$t~diO7nOKaT5FBALT`+W2N~j`_s~QFL92c|nQv51JQ8XDWrHfD& z5gv8t?7L$)G`({ItdS@ZO^VRyDHLTmHKPU2#&Nj*uUoKip+3qvttv&;X2@Js!>YHx z!am-*8e=Az;+?W1XTG()r}u%|r8dvj*k`uYKINKit8Bul1-9nMM>c=o0{rdnwJDpX zTiU}7?V;E3;m2R6hdW!LQbq9v*wBt2IcQzkCZt{HqE|BUmI?H(?O(Df_PFiav(r6W z?%wg0)kYR9Z^!B=VXGFDav26GU$TSoiw(>1^|iu2U%!k^pG$pb&elzl$W&5{%>U9^H z$zpMxI-j#nbNcNN&l{2Kh|IUcCv|HUGSWM_6raJSf_yqhnvQ#eVg;@IV^ggX8;Y_6 zzDOMKPOi@ZygoF{CCVyD+&cW7mKW2v>Unm;9q||m!VL!{?nln&c5M9u&x&2`D%viZ z3sKS-&RL>L5P&rP41XEg6NEa94md~W92$@gi zU4~3g!kt5aRs&NCi*S&TQiPh6RgorCi~e3`>0jD*tGU?L+q6@QZT`2*Y~qfocHra=oAmKCtH5bB4-Je! zj;mBaE~f%Ne1F`&*}vP49QxM!_w8wu#*eX8%NE+Nznr#B8`jz<8`oO@K0WP+6UXrk z!h)Pn7E>X@D=&qozUIX7KaZIm-DW4gT4M)3UT6n4EwXPmF0{j+VgGt3=b)UQ+fs`a zvb5rbt!&}^R`24fcHq<1_UEB(_S-jG?99H;Jv^L~Y)f2_7ZY3}1{F(U*j}}4Ny}HY zEGEOHih249C5l)YZ_1S_;UXWon-$H9aO=n0aR^P1T2&xIwfPrQs8;1P);!Up(h5~6 z&DoE*Q7B#Te9u|srIEXrz;C%C1*}D#i>+zDk1Xv2unj9xRxC;Sr&hW|C=e1b-Mj#S zUKOfZEft?)r7^HzDy*Q3e0u06U7_X*>Dv;oJzUs7?xOOgtXfJLt5OE5C?f02qx<4C z-~)HIw#CyY*p;S)=c@$xXPMX3YEa)AFJEg{?cHMyX3ld<6Ybm+ z@SG$=L&Q!9p~AFVnt*R{+l^+;C*59agd4ANupLV0s|!asV}rEWrvZ5u=fE**FnXL_ zwP!aLR-aoc9a9=xlTh^+T1rJEJ=^K$EApX3=qoys2Cw6+Nkb}g^X2yO7poxY+VOeP z_MhBoJ5TMhAvW3i*%(WI%cfbaem2%#J2uKzA6RFTw@$II4sW!Ht0!66cD3yBeou>@ zTW9Pw#h8eoA3OZ5wPPb*@1E%p_X9R_>IA%B-f9!ajbelL<8CD=S0hUo&$sPcK66)J zVqo+MP4G4T`K}%I-kzh@dC8Y{$E=U+_RMu$>#g;4erIg3s=de9d5`wD0#6R&gs9go z{}ThP>`U+3i(maWu6{jCA+qKv@qty$c;Bm{Y8CnK8&jUmWZo5yY!-%2U}(>spC>{%gga9cqQirLS_xP|bs^kg`uN_UteY*5X6z z7bT>-!d-`OR83#IZRRKT;Ea`4wpKmIc&QTEndxxdr}dv(`kiAb6&<%L>^W|s$&Ovo zWmg%<^bCd?x_tH4U7@Aa(UVqA1PlB|YZstQGsskU3 zW%z!vBheHluMv?vSZyN#Mh*V?65r`HE5o!J@HkgqVyo6Iu;0!cu`@p%v>(qLw$s0z zu*D}=+3lO2u{N8Zvo2eD+9$t#X1jjgVJA)>v;*I5XGi%V`+#EwN?&!M-Q4LmTexVh zU5S*h7z0T@B)&g>#CGre3U>OSO+d;d&6h-~X$;I1XAr{8ATkHn3Q-mJrCv%|tMKrv zR&?F(7L57Ug5ldOczc(n2k-8-q+sM83r6m?VD#6P5sW*)lko>E7)QL39%rZJQYd(L zrv)GGv+!*^#@KJkg)H+2qlrKI8w*BpeYoF(soz=t6+hd(;}+WE_uq?Lzm{E!7`S?a zD=q)qt1Vb?nz|78gZ<>7L`qFw-&l{pbEN_q!Fc^6l&*@U>qUl&yC8UPuLUEvTJYX> z%Q^3)UH8#3`(XSiyM!(fCsw6gX)Af}vz9#fm<7|nqZlea>T9x4J(Y!L79{fSqtA+| zl<*NHd9(~wtB6-{#10E4AF-VCzqjId;|ib6&oZG-7*a70`6>{7MJ-IHui3EKZa93{ zn&G;$3Xt>l9;#Pq#oS*`x$xl1&}Yt7ikX*K|-7zwCFEZq$R`|%pwAAs@8?oD_K(0V@fjhhNjyAqbh}L`Z_zvI8KQR=AMP-H8ipI<1 zVubvO-YAA*D#b&j?m{jPaCM##=ByHKqoikMSupR6mB0M~t8*d#-*C)!!N`xmJaD-4 zEeqPbZ9&H|7IYeK!F{Av9uJb=!{qxY*W+2W$xv0&gRayf3{kssUXjPC%%en9A|?J0 zncPoi%2b)R8DT+NPCaAL)!*VT`Pe9=Ny?za0ZSpJs<&(1!lSxD>6LO%Mqe`%KV zL}ffw`u|(QP#-mny5Kp=WJWH0EiNNCd}iG`WOZ?VIud9PbT359WZSf+4~WuWAL=<`s&Uve4oVLSDrhekq< zf3X={7J%{IzLpMMe=#Bi@-k4tlnYsYvv914a-)2G_Ww4y*s5Mr%PzdGwpG2hmZe>N ziKRBKW+}WYR|`S(Mfh!mTa*Gsd1x8ti<6vUq*8#nET{zFXu;vaVlP*V0j+Q^;^^#r z!&g}_aFYc$GGRV6&w{S&EO=p~1uyaJl}{|l*la=1Pc7)f)$cP427FF@u0dZ|@cNgQ z^u`vT^u|{H4cTHT!Qd~$*RK(!Khc$}7g=PG)vH`De@ynk_P=Yx;#6$k4c27+No&=x zj-}qn;aBs|gplsQz^rE%0!``)WE?tT%YEsbqrJ!3W51mf|$|*40DGKw<-vR9uF%g;%xE$hs zG`skv$O^*W#>;Yvg^N}r;EU0aEJBc%`>veRnM$9W0eOYWJx?d5!*uk9&FBxiF_77N z2u#9IuD8C18R2>t9^gI5><3&QG8d0N#9Yt6v|!XBo|2p1jwF_159b<2>LJYQ%54BS z_kl^tpp@r9u}bYa+s=odty3Lq`G+%@ypLIMI}Gv@%NZd+q$dnbU(&orjRup)8|3vS zd5$3OcPM8h<-Je29~`7c2dT}dgVctQ*XI3rZQdcaQoN<_A&1w=Njdi0ZLwavEY^LC z#hzFO;F&rm9JUhocf*fg$$x2|ZL|-y>Ccx8B)z^&?V~Tv-aaaq_URFfI$*^V@)rC5 z(Kf-Tt=9gYj<#X#3g5*jxJPzo4*TRRmc#d$dLujAjj19xZ&3UoT&F+QQ#eXZ$Hgyciuuy(+HBPp;2tr#WmA#i~ ztdfwY)~;T`a@4#SXRH^(R8+>488TcUEiP-zSss*!c#aIoLW=^&by75%5@Vroc9CmU zShEV8$CM)zB>Wd*-i5ibJ9z4&o~OrNr^klUOT+1#cZ6Hv2Mmus40Cw|N;TmKJi(-+ zAPPvP1(U#~9*rf=7%m}9X_R&Z`3wV#uaoaU5YZQ8s4SKF%v?J^^8gx?>Q?sA9u`db z-h%cY!XK;$+c2yBsgKeOp+0Ythw{o^AC)zhI*sR|{ET4YVXGjF`jc_0jcU%NQSdIQ zN07@~TyK!$U}`jg+%<|+;@zW3cgTwT=T)nS?ltEO@=3G~lR_VA{u=T1B|}L+JgNeKDL_6OiGEYn)+qLJhNHxO_b4++$1_;<)sh&GR zyv*Egb`!TOb6(gMY%1Yh+@`W_8l+aBt&~<8=bz=RF$(c(8&$TOnpU*CuB~F7ZmDh$ zw8r}Dw(54zjThRTJiDoBC2QUw&FWoR&T3p#jsuy|Af;&!T4@(&Mxk zX2~h6d@r*y52cg)3E(%zf)_su3Hl)73Zf2r(hItpK%n2jSg!G06SyXEO@^??_?N0s zj3+TL7fc}bSgz4rnvi_jA*TrZgQyV%-b?H>j`)YID8Rok6}fIE=@V^4jbCFJ>I*cC z1^Rc%Qv-_H#Ks+_JT6)wHu;dH$EF;zVzH@*EH;(8apSe(O>7dEV$w#M8vT2e(?8mX zUQrvpu#ghIvfDefw~a9CQq84b2H%}@*=4n@4y*Ax>@dx!O(0jD_>IU5Dj#FZk`M3$+2TqYLIA0@$&DR}h~9n5Q2%Av>7KHG^j}1@&3_H}i<41k>p=`ZbtBvdLT`vm*GK z7=-n=$vPtRy(#W-h}VmYEZ3yH9QX$V^GJ^n=l6~c+4}*IQ(;_)6b8hsh#3%KCB>M) z{lss;&DS7Hf)D+RP5Ig?=~j2aBtSWlUqzL;N1~w*xx`DTIuY2#&Ahyk1@Cy`965?@@RMkym}bRjM*LqINmTxpJKNgVdw0;EFWTb|-D6!kvHAJ#HaMKP zoo)R%K5Tmv+x>60yHQEpeHRy-RP^i~!cRWf5&xm>{64+i?KfE74tH>9D}j#uDjcT1 zi9=m)wD#O9wa)s@P^A3r+T6equdR5~%3~|sk-U}i&eqp)U2k`D|M>lPIhoCFs@Fln z7}0tSglaf+zN|)?U3=w)_SMIW(XHU`kTd;${(c*tHaFnPaEKk=_K+Rf@uVHw{Tx0! zhuYB{Z`!w8rrFjNZ`cptth1GK-nE;Xl(in+y4cTWe#C+k&l@EriZ6}VrYY!q_SnLC zvu!)-vR2o(w0*mG+A<`KKmPC?`kr-2Ay07e-XAeg~5i)+qzT*oao_oyY!V?fL$&Kyub8%WF|%}jo0aEV?{=iOB0 z!39lpmOq*S#4Pka3{~gp@JJ4uS(^L*5j3K z*7}wk?LYT*LiKsfPn-OF^T#+`Xlj!ujIj;tR@mvEPFkNHuh?fiuSMgO!hFg*mZpt$ zrFjSJfHDFCai1TkI|N%nAGpsHcfuwd94wnMeHDBE+-yGabwX)HBIN z17QYlGZ`RahgcQ(0MMWkY=#5F*BEeJffdjyvFHTn;MBG<5%?bf{1T05?W&o{fe$zY z5}246Q-H&HJS)rbHU_2`c0>K2>l!;LAiGX$j-#3BS6Ub4iBUXsz zW@4gJX&IZ4UQYBOTdd2gmWE0;YA3Jl07}yg;_XCjM91Uc*F=~+L)W)lz&w)yHH~s7 zQ~pG1I7xNkn#BFooxEq*`f$)-As;bDV$(E%YL-z;sjR4_US6CS2J3JD;v79Zx_Er& z{+-9KA$vASAH}@`S@G>M()#B~vymQOF?4crR%~|ZR0-`2-9*M+4$5vIU4oNXG(;jx zL**atgVVb8#+KQ2|Gvgup09A>f_*~$4M$bis9;w&zz)Av^{m0bDX+hu{>FYe`8n1o znOrLv41e#ko9*vacILa8c4+$)+xO{6`wiXyrz<|Rr`lDs!9BY8V0eVVkW#J$Mk=M; z$NkQ2TkX4}hiupzgWc`8>;ZK8$9o*-I(htPJH?!!BUq0eIfVb>C#?)?fn?}W@G^tp z83w~37JqMZFP?u4FrFA62(uUfbD_-(xt8c+Ff2J{u|-h5g$L|{MPCEueO6-OUaoys ze8GOpIfo9^+%TJb;G2RO%8N@wLQ6k&v}pTafbuM5cVA*TC+@KtEdQN5(p=DGd?*N& z7{{5kI7pn^XE?y}ohOk#-m zu=twcKz>>)FsJyC&@g-dpDh)P+Ge*iE39WBtU17q1sDL4z(+&Gm%o)Ip44pMhOvTc z9N=!lC_3-7KBVW-tf9qkIDE8iE%aa@ZH_Fvq_UL_uJTD(Fp`JjYam4ixEc~-+Li8K z+*hq^h^asynUrasxD?4we>nn^^ogDRZX>1xLjkgW5AxnP?BO0}3Oog~5MH@#iGBRhI(z!@ zM{orCnjZoo>#yO%2HSt1e!^C9{`Q+gU&j;tL!|uMhT{yh3>qz8HFRH$sGDmDY{f_| z*N(t^0DfkOBnC#({2v$yCoNdYwfqMQRxntW9ktjJx^mt=dv^Qx*5k)N{<1Pn*U_0w z7r{J!rOAYya`sBYLcFnnB#J+TVfZ{idu55`n6TR}u7c{~p>%-7ka%bUvKNHrk|X*s z1#|+R7L`*-J9(d#oxRr%|MG|R`|yfhFc@$9oX zRC>X*X$H73S`&1qCeLxHR-(+3--@Y2c^bg>IKwBn&t|~S*kk!-qh{WA%=VoA&HluH zbA~#jh(h~#(&MXRmVX9w$<$rU1C*+DnFfs(QAn<05;aI#maPp0cCkPXcI1`iu^xg1yLw4C-%}p=48~WL=;=MUn#z8qmisWA$IAJR5dJ zbzTADFD$X7VHgp7z_M-}eEyW=UkwL)`u+nVpsSYMTx zvi#U-E0`HVIhZae^Gz&@CI5;c81`>euKLDTm+&3H`0kFjj&pp)yN3o|k+$hl7rO|M z;uk__g=!pyv)kN8V0Q6jvNk>nzU9k@UZm4ykyupfpD}sP2 zJ!pfTYG6a2X<%=?c$H5PW;Ln;KbWNQuk@pO@I_ICAfSIAU`q1fm{M0SH?CbhnP44 zS+!7YJ|wLV8ES}-))_D@*5?Yyd+gn>Plex@wCebeHelv2?dD4PC>2!R{bPyk5Jl&@7}lmfCr38^c#~bRXqlxjPsn1? z_oOf)#JZdf>bMpP38woQa$psSBsXa(rR|cc<*Y$%Y;x*Vu;%s4yQIGDwbiWM4HsLx z>#JGo<}m$D(yT=ToY~jr6y0h#pCU~)sC>l=fRphQs@^^Ov(hxbAj?=puF<5#nu4jbw65cJy2dx*R26$ z%bDiqY_%7+9}YXUZ1W8OiUW6Iivh+`ptppW3xVhy;G78?BCdQ402vN=UZ!KAR|Qzi zKG38X;5q)aGtZ5blYs#PrrsGr+okG z@3!E;aa(!x2U~gUl&u7CE5AE!tG@r)hU}xxbD2NpQnIfRsKrz+L05{=fk6GKsg!;c zdHgHkqEt{9^k|phEov+JE}^Xkqz083tNEm7fnIxE{QGk(JW6X#-M}}lU}jrsncsdF zGA0+EhBYcbe>cN~fesrJWKtJ~Tued$ZxPv;#wFB%8_dxZo6gSy6ayXGUCC3hc7~YLi;^gzh!X zs-tPGf$mkjxiqhr64o;@G2+=J;MA_aj0Aqu70RtVwSz&%<*JA(mAxE~#d#RaBT$0u zQ1@mYPIHUWNzEkDqn4eE#aRQDHG(|}PFxPul>j}#9*e9=6+8tzGL-49xTN#UVqGb@Bh(8 zAO6XfpZMAK{rtP#^f6@$_*2&d=Vf-|$}hrpD%oZuB~D`i&0?UPmjuq$9;Sqsp&{Bno2`te6=x^iu}2MU>s3mbXw+JATOP+ZA$c)Ub3&DVV7 zNm`JU1*#jFh%I*oEXkr@tzA8xo&lw1bLNu{6S}VtS=EO4_hF3qs8E7`xB!E)FP8$g zrz6xUak87yP(h6>fs*qGQsQn#QWVl{NR?$$;Gtxp+5sGAO&q{6J&_r5c-lb%Q1u?dIGtiC?TVR9C)q(*lS=*FzgD}1N?OWV>J+53a30{Gq&d#iir0t z-{K=JBk8=QfP6W*2;@sh#bPv&v?l7vw*_)_!b_m>i;=P{1VS^n*j=0U+wTC~Yf$C&9S1PSS<65LTr&auTqGj%VHw0M zxqy^f%_bM+s@X*V9|XXkp6c{m0IyKG1co!j7r@VHmn4|1qKD-K8o$BwxW@2Ip)F&&jo~YG#+UY-zQd zHFFV+Z@)@XBux=AA@gH53-}#RWoJ{Xabr(Yr}@?Hqge)N?huAwrM%_(t6kNawVEvG zHZxg{ARN+3vdWbqfY!btbQ1(Qi?zrK#UeOojSBblsYR_eu?y3}Hd&Ro;tKg@H5l#` ztq+jsIJ21%?=iKb)^k(iNS+63B_Uh^4p(!Dxn4(`uc4P$paoe38JxC}of8;_`zp$j zJRc-4hkIB-E-OeaQObfil0_h+9(yH3vb3mj=35e;AeccsA$f2d$-twtmziSk-P}3%qKUg0hFtz zC5g^eT6QFtkqH>z_%H1e1IaN|2(iT{n69{3ImgyeqqXF<7L2X|pDU=^>AnaIGeLoT8;lE%0zBR^e4C(+1U zAjGh9+{1=}QrBK(HQ^`wU$LAlF2gDsv!AeLo- z7;Z7%3d`+>?qx+#0%MsX9A1`;nmWh;R3bia?}4qQanFUaNUOSRHQm38?pjV~EZGS! z0MVPY&R+a-f7nf_|AaEobSML75#@h_G9vFvxZE#(|I1lKIXjfaoJUX=8C=eMzXHO% zLcEV^q8a>itG{ZyZU5<)uqG9c|MrL7upUTdq6wN0`9?_ZL|IUt4V0DZ{{ZE*i0k+l zC@0N6VMz?k*b**=cx*LrW{Afa;<5GAY8^vhB}#x*yR9FatDgR1zfJt+cv!0fAHkF4 z5g&wnGMG!uIShbEE$}}=d8w0Ku>wwY^9XSQu%k8GZ{iuK4DB5weEJ(=`cTM~T|^!s zKFX_?lDI=)1teX(C5~Y2a+4_)4uY4*z1W6ObdsAR0;Tg8E{H^Fl!e=f8AzZt79rVb zcpfDeF7=gT-Wy@_XHKz^Zw}^glBeu)YfhN4A$S3omYvI~NdmzvC6_YpG%d{B zY{lkow#51kEdWSFJpq-!2DOSO^ut8pB=O^bk zklDCdEv{{|;Fm*Si;$^hp5WF~51j`Hu_(q>&lAY>^tnYn>(#Bxp|Jbul0WS09iQ3) z4qa-}_zGv!(=|wn$)HT;?t^;2Y9Fm$Y$e$$7QBp_jJ9x8A}&avQd23bmS71qV=2!U zd~02{eQyVU{li|{bIdMWNNbEY!g$xCf>*}dL34hZS^))>q zbeRQ-P;QUKBSq-Y<|dcZ3Q3aJve$Ci1uV;YM>O;7-*C@k$k1jn0#Tfv3WR)b^hmTd z#Hyr=m$Rqn_}4qY>KWVd#Ri)>c{CnxLU%jvEunyL+BdzMtynzUN-RewCY-XmPI?>a ziPFR8MW1!SsOHOswBlm=moeXE%W>JNaMYtzYfpc?(=tBa6ZS^M=IcS}oE`Kb6htC6 zX6s-PbW@8vQDcNyzUUJ*(rW(Y1y*70@AmQ9<@U^SP=;Nd%N- zg>{+36tA6@WM`o?k~v5WCT>Bk!sv}LW@1qCEM5fZ@N)86!kAe=jb?vpFTvo?i70vL zQTrHaQyAB%-yNlMsFlWxEG#u!X)zqN3-XxQ=Z@$$w$E(O?p?Nb?;hL79`?O^ zcYD}>_b9yEpYP+n;_ThC$I=xD6zc6Ey$he69qOUC`SvOo;)bcu4lDkm1#?_f8*U0q z6%VldY!234TsQ!eLg_-NGxsN1JZjbg%%3^+^=Ur@Z5=!I^>%P|+Ce)D&^89NQfr2w zmG0&&(7ps{B^e&R$CBJq1AvOX1S~FEav>FsI(wfz0%)CJ1gHOquXidn*R(ndk}AfK zb$&t~41$u)V~k8jm6!0GHY)35iB*9z!TT ze1gTin-8I!Lp+90&N*MQ^S z6ZTk{3YG2ZCXM_Uk@oo7Y=;SJ`*wGlhq+HzAgR5c-o;bi@WlW5yF1zK;jwrTwBtoj zMd4XIl%%(M)S>-d;k%q2JG8Ur&6_z{)pRZ?RLK%0SIU)hFJD<@!7f?r`4FHu_kjuM zp%e~Ar>9vl{aJ`=(b(LPSNR_f?gpX1*q*H)+w7@h{p17R*CrOAkQ^>a)-9B-SvD^u zt=$&5N-F71P@2%<#)rKoDKT?G2`$`=rNfS&ezQIzuVtEJC*#CI;?jl0lKGuv3klU5 zXizUlsy8OpT-mLMrbBp9y#)inr}hgZteLNCTwR#T0GQ!PDXR$WeVR*m|Ey z^1UT?KAM8>5azo1LfWiDKQggzr~ko1LeEPbM7TzR$^oRzrj)COw%-k^BcwBAW@RaRDf6{RSX+Bs^Z5CVk$!qMlNXT5M z&vsg4GRT}s$%t;<+;A$bBqNfuT4kwA{Zgw|vr_Pg#Zid)o)Cq((q#+~Xs1Xo-R9G+ zzvoFJ9Dl~D-SX$p@B2*jF4|ub=8?#)heCl0O81bWh9RxN9g{J^6gs*r7O5k$$YipN zFrrea(i|p&2pWC{n^K8o4_i=Q42XY9c9-^8>u4>xE zZoR3M4TLwHHGP5=Uv?T$0?bJ1FKZLcaGDV{GipUTn_qQ}^rf@**m<+ITf6o9ZS#pU z)++?)Y5nm$@4XFhT8Ey?FPTT+>=fvGv=4}G#!xPLm*UHF2`wt@S zL+U5YsAJeu2AH?qz3E5@(Bwsjez3}r&axBM*of`%IlffyuPAdI;G7CLr%(0KJNoON;ZR84 z_}x!deBwGw8o9)t+^{pO*#$3dq17hwt(km_Y&!XdP;1TaIqe|vUFAzIWh+#imva%j zXp?$g=x{)|CdmySkZ`K=v-f>!#P#Knc(T>?*IL^)t=-@(h5M|@H>QY6=tM3HXhDiH z&2L$Sfl2At$l9(#TQPaasgkh9jNJ zvBr^OFo(A|;-cCUTo>n6m$KKUdJT5uXx_sn)9oT(r%`2gCF-F?tjw;Y(${PxS)f=c z%}_IlH{lCAZ}O)$3=@W)f@#_2t9gT|RWOSj+!B*+5*rsSSOpQ~J_KqaBQGFvfi@ws z<;E@YWpei5c#OkUk1&0Asp+dH9%?kVe*kPpYm8>x5u!cbL zOq9fLb9q7%X<1)HhqZFa=WSRZ(HvVbVN0YmhtR4tUMQ~cERR#~ocEb7W4Y)F`j%Qki(SQeiVxf`bR z=!qKC#gtx#l5RUZj?JtfO54icA-;_Jm39J`_6CB&*klBe5YDDc_uFv@Tpu4ZQs%ao z7-$S6ReMJ!Qj*N($0!#rjThMn_hiu}J2i}RLUnC6llgPoLHJTT$TkcT9g`8}6!amG z%r|$P2rbHr{`XV9Z#>@wryWcthRigxkCN=)jOtqU(v_;$;PBY+>>Txsqmy~hwpI%E(AOb6|^Uw^id?+mv`AMTRiFNKB#ln94; zi$84J<~AELc%Z%U`XIMF*J9ttMK(&TF@zsWrv3Qh-ys|*Q%7MeLT5N2RH;CZJPW74 zz4RZEuPuDP+;0t+kWa-*MO#r6-&KZ%797qlr+0CgcZgmYSPp%oTvnCV;I1aSS7!- zINbktaeV)uPSunxJ@dQG`u0a_wL*2E z-I@4(i{eD;pNKyu>C7IokQY z>~8awL&DBL_OEO$iao*AXS>CQK{u>1`>H37<|Npb zwuwkLJ-4O0Ev8p?*bTSd$}Z1m?4}#8bCJ8;y?4I5y(=x-wQa*W z-_O`BH{RfiQthk|5<*%Y=R*V!r;cJOwH|NQxRLGHw#9yjmbbq3M(03nDGa`D8`Nk$E z$AX~Iq?3itNG{QCaQ?m^_mxQv0inCPsyGAYf*s7_qt zg;I?-l}q`FdZ|v-aqLds^Nu*dc=AyirBxoX(NvyiwG|^tZS?~4?FZPPzWkzX+qjgo z*6(AlLJRwH{Zbp$=M^i4U|>Mc?zVo(Ond3sCoGp(23hM0URAMW5xXfupTLRp#M0o) z8TR|{jD;Y-T~v;Tmxx$)A1~TeR!V5((xKJfJO#P4qSGe#$ZZg+QB2%P)x{p zE?h#ewf~S+PVznTknBm2Zf62WAtqEXid_Kj!!r?;2(AMl;TdTD<<^58{W&LQ zb2=~u$lg7g?%4p*qr2r%COd4^og!4qTSQ9)RWKABfn`Q8cCV!dV+ByIu{_1cqq~X} zNCgOaej35$KxIIv1o>rBiJitV*Z`}RcfP}v0Y@7J4^vZo9tW!VVB$xv5CnKl5Ya#q z@I>av$+_gX{racs_;{fxA2Ym;@F@jHwA1^4X&}uck3RXRO&U4aTHlBn7wXLShxW0q zkKTtD*Mjz7r*`)Ku)fy0V;esxS^$(nK%FkSC3u}f)RF~Tt&+5(B7`uJaz-Fa{KkQo z4Y^@tQfJ}Kmw95HlO@5hU+4wAagv7*=}*2f^C%p*OZ@+jEaeZUHE zJ*rKpRX=JK!CBme@`8I!04NS=ypqb_7QjxAL0ro_b&ZgsokB_%QCU$>IbMaRc?`92?3mFnOU?9^;CTUaWv3 zW?Pi~H$;9vw0jdKTc1L{52`?!bS2^n{iOBsJxdo^eE4QkXa-$X%st=npVMb zO8E2C4CvrQs1H;3t4zV}J&tMFy~ok%k@vXakd??^+eoM#DySqVU3!dv6=EO2gh*HW z9&g@NOfIE(lN`?S9tZvF1%zH@a(woqu;iy^T0!>s)T?o^m3!z_7;D6Gt>0quTn0k{ zlrn&HZzkV_2RUHq9`?vz;xexl<*HVcpAo$OwWTQ(<4NpYp1u>0DPMNO;@>1@*uCqK zvj&YydTc3PN{9PWu;{(dxeoa3HloI_!b&g*Vtv^};%!82{?SHRwdtYSq^dSvKh=i% z#=LE)jZ!8&>-|gHbe)B|agS9)76{!AJR{UoyJFymABrC zIwwW?483w#W<@HjNQ|W)Fd!S8J9qASu~_W9AP8byN&FSclP6EJqD6|n&pP*4RXrMm ziK>!k^eo%VphwPoX#HDMXxDd8ZzoUZ51a=U>A6;eLgM}OYM5B&VY${i%M~Z0EQw#G zDbPkqsk7L8lY}K=hHS*s+)hBsG`&?U#nvYI43=|RT!|I!My}66jGtZ=mZnmNerXrH zzR>DaC~H-2xWi)dQ`&K)1$T`KaVMXq&yz-JyK5|xUr(;yXYyP(meSF&$n6}ff63(A(;CSOS#pVI$lZa ztlI9JY`)%%cHkOYpKXt<=MriHl#LaQfnE;=T3YMJVrB#K1l z<=WR$s!1#C@BVg$L(qCC{xs>C4ot3EPIVd^x&ivn_)z)q5WkO12o<`IL9-v{!sI(c zMqO#LnF;h%>R!cCY^f~%GcFXbbtboa$h9N=uToSRLat)$r=GZOlQpZ47h=pB3JqC^ z5aa~$-odXZbXcr~IAzsHc}P^(g-dxq%=IW`MYW+0)Miq=HmaZ3h#1oGsYXgE?=JU| zQzvp%&MHAA36+^AEnnXmmRg$5rhQ5`xxr$~)jmt8@vwON@CDvJq?el{eW7aeFYVJq zwJG?2ZkyX_o9E|S!A)k3?|aOu<5kvS>1KX@?o2MJEkan90G1*3iD<2Ny@S9>R2F+l zJi!OzHxOc%zqjC%L!c~Bpg=c3^QV9#7<&$Afg_lQqJ~ha#%s?uSA_TIR}(y>e=S)T z?x(Diz<3onhrJpHPKjME64B3p`;|n+VVYZ>F+@aD@v>E{&BIL0OqnvLlf(?&eTIAk z#oP`3tRJmsF#9J){;ZRX{3(Ylr^_4&1T%j?zsbd?lS zQF@G{EmmQRrtnhBNzsmRMho*-|-cM z$;7kkuZ%D7M~cRcmlluWbt9@*cKY{Ldd+XvbNMH@yt&Nh?7q@}=9ITpp{Eo?O&i@M z?h$%?cJB!_$yyz_CcC#*>Or{Xp0%HbbjDd{Sr zKr!lC`pTA;h93zbBLz-98Y5|(j#D1{krLFQNXMtGI4S#ove!C|pKm4Zea2K$y2=a` z>Z?$pau0N~3J-O+1}_h?VtiQvYEXn<9pO;AGqvJZ-<7{bTYLJYm+kw598c4zJ}n*k zk&&Y@eWR0}yxKLW^A9A^jEIkPPU;)6`B7iT(E~EP?_#0~9QBp?ntD41=^3gg@mLYY z5>uXF!_qn%Y~t`sGicO{1EWlaD-)M&I!pq!lZSGPf<#!63y~`t)aPWu4OajDA(nb; z500+9y_e;vaC;xC+4dEyQ?-H>%bUZ>6}kW#*X<=;keuWN)^x%bV| zuDHWW=LtM!N|A!$iAw1eiWd$;=cN@ZY^4k3x0|oK#t!b^p!n<#1VjZq)WaSHAV5Re)Z{;~fDUGW3 zRN={f_z}~UABnB;sHV6;W7e^Q-X={)8x<{Rl{k&*_|}hX{IGt0qEgLDDONp=?G9<> ztY*a&uUUFnGwSFy)7s2$F+>O)gaMf@#@u(f7TXD=by{U$4b4+YWkwEENFCT zU8OAB43~G2kDLYRBPCjX^09|(^ZMnu8SLzqZYo~`UKRZ>62eb7@-L(N3s#zjjT%Oa zP&Ztnj#(Y&of%VF?BHe&ipa+hJ@I$W*i17nq-@oWm@NUt$l}|>Z$o$ zVkH@k_>QHZ5;MMsa>}JaL%f2#Ie37L|KJ^~&s3(BeOAW}6uml6TU$i_uW!-VuB=}t zj!X`eq3M*rzz}_-579ua=HKqO=j)TB2>Mlm>(D(2zS>43^r*)iJ%|(ftJnfnB}9NV zkv#et+L#`kKNqao@-gVn`d=J)0l&D!)rAC~A zBO)g7>x=#FEF)5Vy}m}hE`V;^yw2VpI?#dUx=?{7NvIJ>RIlC&VuXKCP&YU{z$Z(rky*OVh{Lv$a`7kU zW}3t-qx@Az8Q*Qil)e z@BORN6FjO{BgBP}B3uZQDdo%3;^>MWW)Sjt=9t(;Kqu%#J7$`qpJtlrMn)AitNWfO8abXc022n9;3mE!d+ukpbm znyqhiwa7W>IhQ#VEkQo`uy=Y41l{PZqfgHQ78A{cBxKgjDd}gG>aUU&Nq3a@9lUXg zkii9ewQ18oyo)`ehg>aLHcArxs_`8KzLRe|P7l9l*U53SU%v~(zjCke-#>BC=VQ)! zc!yD}h`0vWy&cum&dxvoe0%TRxBs8Q&OFAe>WbsP4HyO?qBG+F!a&hj zOifMNR1?!w3sQ>|DAkH0f=eZ85v!tNUHTgsoH~Hwu4zS>X<39}7Q|Lt7Yd>Uo6@)> zVx`eUtxIujQmx*8Ki~Je@68No|Co8_cb9X|J@4pv^Oc6AGwerre<>9WdN<;XO`cf1yvAz_~^9b<)USnb- z_6IzS0bX!cia6j~U$ib(z{44aF@aTf@D4+1{*j+o0m(*wVgQ(4Rc=eH3R~KQ5Mx-_ zFcC6z=+I`b_aVll?_tNJ)_&is983&aU{SmI7D*lM41;@~)2QQ65laMF4LH*}f@g9Vg?4 zRY*Mvj~(`Piuerph;de9ST)cvK!mY@@=nxF?(@5M`OCLQYqgNZ7*$a%4I=Cv{m~2 z&TT;P<4|?wW%GOxofH#gU>{t+CUkdh(uX*fItRM3ZhdDAK66i-1?cMQlM6T)&^_lG zp=;n>b*-Um!*9cyRriG(7hVyjU$`KQ zJ7rE7cKozZf84b2wNuYi*p*@a#TSJ0&OY5=3%TmDi|vO}ngN@4gR1;Y>3OQbieUmQ zP0X&K|E4WNmQV1g3IbG4gXLVJ%`LN0@X%?C_1bkSCA$(r)?hY@otRRcBS+nxEk^+! z6-~MRePWIMbeJW5$|qsb(2JSF22%jZV)8gYp@$Pr-^C$5W#R-4SmV9D&iu+t_O?%U zsE6W$)2s1hpure``l_~sjvPD2y_TC~S#4p9e(x)L45)v9^g&qG(j3k|_nffnnH|aC zmcRbmtNmJw{f{zD>RMamgAmouip(d9>?uCR0Rzrxj_AZEE{ecah8hmcAb7^w!j3Rl zVM}Mu__3t>NPnM(eQ&-Tw(BI~wDr1y@qrMISQWxpJ)x(p|1j+O)9=HbOUvPBb7zLt z_bk&&!nbYr;g!e_l}FJ??mEaq*#LYtXi)WxWcxx6(}|M!Bht8a-IBn8>3U8ZS0(++ z$?nK#C>b?~?2MHHX=Oy#$?DZ7o3N!)akNb4qin)v2((Z+gz~WD!W>%xRWGi|+eQi^ zJq7lBX8Fz2oumq#M*B_%s!CH}yBQ%sM+@-CW<~=*3VK(+ayrZdXu-sAbG2WrEdFKZ z)0%4~D{hF9bdi+Gj&3L}IeeMjSr#SX$(W0Tm_P69d zS(~Nzt?g(EBd@>qVt9PZhA_G9?Qpp6p)Zfs!h99fq_%hU;_2qFqWQWo@BA~ueJhrD zH3dAUQkT(Bk)J)a8&LuzM}0ha@IekO3qer5mb`)QVi39npF?$+VY;wThp_e4DldYCHWg34n; z-K5sH!ib2vA)xO2t?$TQb?dV@*M^H{|0t}ytEHDs>M11}jm_Gpd9;R<*h#(V(xI8& z#6rF>s1bd$f#H||j*VNY3u2;9)Cd^6F7sBT5?$E8js~21mW@=Zd=@-{|JXs)5c-}=9dL!ocWz9wMQt%6B&pIoBIlrx1?Ao-! zlSukP+JW+@o?q^U>fDtXy%3IE`)mN#mxU(%@1B?z?Y*{MUO;jE#^EQJBUs2*57-EcElOVtAhPK8-i4;kI& zg@i@LKY*u|77?5(HkT^Z66VO3z$dMYlVrv#OHwg(%0aFJ<#!6RGc}IFNXrwMaOx>1 zhNHyqojf5txOPq0xM6+hXx|XdJ9lZ%|Yw??r&Kqu2U(Iot-*e4=wA)nCca^l1Er(wnAwfaUIip zSYAwgZJYvQ3a9;Ga(HR?GvV*g?F`R9yFKjO_Q%k@?Qdb~Pn*K<(ft!-Op@IzYQ5xnrXjZgK8VK-?QdUQWZlI6D8oNeL!4<7daDT zq?AEMN0PU{)`0XVThN$0FJ?3P4Pgq1#anfm5^dNFv0gnVgO6Rx|C@PWtaPkP%t6if zD?ZaqCWyndra*Gpc=_3^OEEX&sihXJtj!76$Z2CE?1qI`g|p>MGuYm-{AM-uQQ=fw zncLD-_G0LYo0o(oj5y4!~Jha3ZJ*%ZdHF{K<^M=aq4GZdgSY^A^H zs|y)8U(8K?-}t&FJvyk+FswF=(%-lv8hkwhaV+BCfN(Sg07S*x2vnwOJ(?S_`wT^{ zK|bcQ-issycG^04Qlsf1hSXw4*wT=}LoSVIj7l)HvbHm25ShwivoIH$+S6Wz=OfoF zbsr9vu@sZ_d^#pah^fMUaW2o1>%Wz2-Q81jvQu~Tf2QA>rFHF%*Doyjz({e%j70`Ehnd-dGg?zF(Y0}MI3nlwxr%!Izh*x&Xg<10P9do?Q$|I6U|fx z)i0@2rVP7ilzgDfUdPMopB3Dv5a-QelY+-24)y0cmT{-d!cbd;4qFD_=FG1Y>IS)26{Hj8!9ZlbKQDpa)61#}F%28CD==GLE}(F&sT9((LD{+v&A z56v+jQ#gHrZV=;dA}Rw?);JmEOcg;@iZz&zqBt_)42srFCHhn`t9Ftu zty(f;Ld9wgN&9Ebnof2jc<$b>fB*i+Ftb+F4)ypCRkF8S^%3~d5&;dF8Y9Zb4HFU4 z*u^R3GpvsN@^l&JWzI|6FNG>Vp;U}rGa+Tlukh6oPyLikNRot+-sz;E(cw17LfxED zO4kCFxJV*MpD29Pe^kytgus<-IBV)Sz-v=p^y;Ud{W;>ME#^6#((sVWw(^b literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini new file mode 100644 index 000000000..8b4174f60 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini @@ -0,0 +1,55 @@ +[General] + +; Network settings +listen_on_host = 127.0.0.1 +listen_on_port = 40200 +send_to_host = 127.0.0.1 +send_to_port = 40100 + +; Channels enumerator, applicable for the AeroSIM RC version 3.90+ +all_channels = Ch1-Aileron Ch2-Elevator Ch3-Throttle Ch4-Rudder Ch5 Ch6 Ch7 Ch8 Ch9 Ch10-Retracts Ch11-Flaps Ch12-FPV-Pan Ch13-FPV-Tilt Ch14-Brakes Ch15-Spoilers Ch16-Smoke Ch17-Fire Ch18-Flight-Mode Ch19-ALT-Hold Ch20-FPV-Tilt-Hold Ch21-Reset-Model Ch22-MouseTX Ch23-Plugin-1 Ch24-Plugin-2 Ch25-Throttle-Hold Ch26-CareFree Ch27-FPV-Roll Ch28-L-Motor-Dual Ch29-R-Motor-Dual Ch30-Mix Ch31-Mix Ch32-Mix Ch33-Mix Ch34-Mix Ch35-Mix Ch36-Mix Ch37-Mix Ch38-Mix Ch39-Mix + +[Input] + +; Map CopterControl channels to simulator channels +; To use internal simulator channels just comment the mapping here +cc_channel_1 = Ch1-Aileron +cc_channel_2 = Ch2-Elevator +cc_channel_3 = Ch3-Throttle +cc_channel_4 = Ch4-Rudder +;cc_channel_5 = Ch27-FPV-Roll +cc_channel_6 = Ch13-FPV-Tilt +;cc_channel_7 = Ch12-FPV-Pan +;cc_channel_8 = +;cc_channel_9 = +;cc_channel_10= + +; Control TX or RX (before or after mixes) +send_to = RX + +[Output] + +; Map simulator channels to GCS HiTL/CopterControl channels +; Only mapped channels will be sent to the GCS +sim_channel_1 = Ch1-Aileron +sim_channel_2 = Ch2-Elevator +sim_channel_3 = Ch3-Throttle +sim_channel_4 = Ch4-Rudder +sim_channel_5 = Ch23-Plugin-1 +;sim_channel_6 = Ch27-FPV-Roll +sim_channel_7 = Ch13-FPV-Tilt +;sim_channel_8 = Ch12-FPV-Pan + +; take values from TX or RX (before or after mixes) +take_from = TX + +[Video] + +; Windowed simulator mode configurations +; Each resolution defines the upper left corner and width/hight. +; User can cycle through all resolutions using the menu command. +number_of_resolutions = 2 + +; x, y, width, height +resolution_1 = 50 50 640 720 +resolution_2 = 0 0 800 480 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt new file mode 100644 index 000000000..901e5c50a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt @@ -0,0 +1,86 @@ +.NAME "CopterControl" + +.HELP_EN "\ +OpenPilot CopterControl HiTL plugin for AeroSIM RC" + +.IMAGE_OFF "cc_off.tga" +.IMAGE_ON "cc_on.tga" +.IMAGE_OFF_MOUSE_HOVER "cc_off_hover.tga" +.IMAGE_ON_MOUSE_HOVER "cc_on_hover.tga" + +.MENU_ITEM_00_NAME "Enable" +.MENU_ITEM_00_TYPE CHECKBOX +.MENU_ITEM_00_HAS_SEPARATOR 0 +.MENU_ITEM_00_MOUSE_RECT_XY 89 91 +.MENU_ITEM_00_MOUSE_RECT_DXDY 48 48 +.MENU_ITEM_00_HIDE_MENU_ITEM 0 + +.MENU_ITEM_01_NAME "Transmit data" +.MENU_ITEM_01_TYPE CHECKBOX +.MENU_ITEM_01_HAS_SEPARATOR 0 +.MENU_ITEM_01_MOUSE_RECT_XY 110 166 +.MENU_ITEM_01_MOUSE_RECT_DXDY 52 34 +.MENU_ITEM_01_HIDE_MENU_ITEM 0 + +.MENU_ITEM_02_NAME "Receive data" +.MENU_ITEM_02_TYPE CHECKBOX +.MENU_ITEM_02_HAS_SEPARATOR 1 +.MENU_ITEM_02_MOUSE_RECT_XY 36 166 +.MENU_ITEM_02_MOUSE_RECT_DXDY 52 34 +.MENU_ITEM_02_HIDE_MENU_ITEM 0 + +.MENU_ITEM_03_NAME "Change window size and position" +.MENU_ITEM_03_TYPE COMMAND +.MENU_ITEM_03_HAS_SEPARATOR 0 +.MENU_ITEM_03_MOUSE_RECT_XY 0 0 +.MENU_ITEM_03_MOUSE_RECT_DXDY 0 0 +.MENU_ITEM_03_HIDE_MENU_ITEM 0 + +.MENU_ITEM_04_NAME "Move to next waypoint" +.MENU_ITEM_04_TYPE COMMAND +.MENU_ITEM_04_HAS_SEPARATOR 0 +.MENU_ITEM_04_MOUSE_RECT_XY 0 0 +.MENU_ITEM_04_MOUSE_RECT_DXDY 0 0 +.MENU_ITEM_04_HIDE_MENU_ITEM 0 + +.MENU_ITEM_05_NAME "no action" +.MENU_ITEM_05_TYPE COMMAND +.MENU_ITEM_05_HAS_SEPARATOR 0 +.MENU_ITEM_05_MOUSE_RECT_XY 0 0 +.MENU_ITEM_05_MOUSE_RECT_DXDY 0 0 +.MENU_ITEM_05_HIDE_MENU_ITEM 0 + +.MENU_ITEM_06_NAME "Blue LED" +.MENU_ITEM_06_TYPE CHECKBOX +.MENU_ITEM_06_HAS_SEPARATOR 0 +.MENU_ITEM_06_MOUSE_RECT_XY 6 40 +.MENU_ITEM_06_MOUSE_RECT_DXDY 15 12 +.MENU_ITEM_06_HIDE_MENU_ITEM 1 + +.MENU_ITEM_07_NAME "Green LED" +.MENU_ITEM_07_TYPE CHECKBOX +.MENU_ITEM_07_HAS_SEPARATOR 0 +.MENU_ITEM_07_MOUSE_RECT_XY 6 52 +.MENU_ITEM_07_MOUSE_RECT_DXDY 15 12 +.MENU_ITEM_07_HIDE_MENU_ITEM 1 + +.MENU_ITEM_08_NAME "FlightMode 1" +.MENU_ITEM_08_TYPE CHECKBOX +.MENU_ITEM_08_HAS_SEPARATOR 0 +.MENU_ITEM_08_MOUSE_RECT_XY 40 19 +.MENU_ITEM_08_MOUSE_RECT_DXDY 38 38 +.MENU_ITEM_08_HIDE_MENU_ITEM 1 + +.MENU_ITEM_09_NAME "FlightMode 2" +.MENU_ITEM_09_TYPE CHECKBOX +.MENU_ITEM_09_HAS_SEPARATOR 0 +.MENU_ITEM_09_MOUSE_RECT_XY 78 19 +.MENU_ITEM_09_MOUSE_RECT_DXDY 38 38 +.MENU_ITEM_09_HIDE_MENU_ITEM 1 + +.MENU_ITEM_10_NAME "FlightMode 3" +.MENU_ITEM_10_TYPE CHECKBOX +.MENU_ITEM_10_HAS_SEPARATOR 0 +.MENU_ITEM_10_MOUSE_RECT_XY 115 19 +.MENU_ITEM_10_MOUSE_RECT_DXDY 38 38 +.MENU_ITEM_10_HIDE_MENU_ITEM 1 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h new file mode 100644 index 000000000..4adf7c16e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h @@ -0,0 +1,215 @@ +/** + ****************************************************************************** + * + * @file aerosimrcdatastruct.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef AEROSIMRCDATASTRUCT_H +#define AEROSIMRCDATASTRUCT_H + +#include + +const quint8 AEROSIMRC_MAX_CHANNELS = 39; +const quint16 DBG_BUFFER_MAX_SIZE = 4096; + +#define MAX_DLL_USER_MENU_ITEMS 16 +#define OBSOLETE_MIT_COMMAND (1 << 0) +#define OBSOLETE_MIT_CHECKBOX (1 << 1) +#define OBSOLETE_MIT_SEPARATOR (1 << 7) + +#if defined(Q_CC_MSVC) +#define PACK_STRUCT +#define MAX_PATH 260 +#pragma pack (push, r1, 1) +#elif defined(Q_CC_GNU) +#define PACK_STRUCT __attribute__((packed)) +#endif + +struct simToPlugin +{ + quint16 structSize; + float simTimeStep; + float chSimTX[AEROSIMRC_MAX_CHANNELS]; + float chSimRX[AEROSIMRC_MAX_CHANNELS]; + uchar *OSDVideoBuf; + quint32 simMenuStatus; + float initPosX; + float initPosY; + float initPosZ; + float initHeading; + float initPitch; + float initRoll; + float wpHomeX; + float wpHomeY; + float wpHomeLat; + float wpHomeLong; + const char *wpHomeDesc; // (m, deg, string) + float wpAX; + float wpAY; + float wpALat; + float wpALong; + const char *wpADesc; // (m, deg, string) + float wpBX; + float wpBY; + float wpBLat; + float wpBLong; + const char *wpBDesc; // (m, deg, string) + float wpCX; + float wpCY; + float wpCLat; + float wpCLong; + const char *wpCDesc; // (m, deg, string) + float wpDX; + float wpDY; + float wpDLat; + float wpDLong; + const char *wpDDesc; // (m, deg, string) + float posX; + float posY; + float posZ; + float velX; + float velY; + float velZ; + float angVelX; + float angVelY; + float angVelZ; + float accelX; + float accelY; + float accelZ; + qreal latitude; + qreal longitude; + float AGL; + float heading; + float pitch; + float roll; + float windVelX; + float windVelY; + float windVelZ; + float eng1RPM; + float eng2RPM; + float eng3RPM; + float eng4RPM; + float voltage; // V + float current; // A + float consumedCharge; // Ah + float capacity; // Ah + float fuelConsumed; // l + float fuelTankCapacity; // l + // ver 3.83 + qint16 screenW; + qint16 screenH; + // Model Orientation Matrix (X=Right, Y=Front, Z=Up) + float axisXx; + float axisXy; + float axisXz; + float axisYx; + float axisYy; + float axisYz; + float axisZx; + float axisZy; + float axisZz; + // Model data in body frame coordinates (X=Right, Y=Front, Z=Up) + float velXm; // m/s Model velocity in body coordinates + float velYm; + float velZm; + float angVelXm; // rad/s Model angular velocity in body coordinates + float angVelYm; + float angVelZm; + float accelXm; // m/s/s Model acceleration in body coordinates + float accelYm; + float accelZm; + // ver 3.90 + quint32 OSDVideoBufSize; +} PACK_STRUCT ; // normal - 592, packed - 582 OK (3.81) + // normal - ???, packed - 658 OK (3.83) + // normal - ???, packed - 662 OK (3.90) + +struct pluginToSim +{ + quint16 structSize; + const char *dbgInfoText; + uchar chOverTX[AEROSIMRC_MAX_CHANNELS]; + float chNewTX[AEROSIMRC_MAX_CHANNELS]; + uchar chOverRX[AEROSIMRC_MAX_CHANNELS]; + float chNewRX[AEROSIMRC_MAX_CHANNELS]; + float newPosX; // m + float newPosY; + float newPosZ; + float newVelX; // m/s + float newVelY; + float newVelZ; + float newAngVelX; // rad/s + float newAngVelY; + float newAngVelZ; + float newHeading; // rad + float newPitch; + float newRoll; + quint32 modelOverrideFlags; + quint32 newMenuStatus; + quint8 isOSDShow; + quint8 isOSDChanged; + quint16 OSDWindow_DX; + quint16 OSDWindow_DY; + float OSDScale; + float newWindVelX; + float newWindVelY; + float newWindVelZ; + float newEng1RPM; + float newEng2RPM; + float newEng3RPM; + float newEng4RPM; + float newVoltage; + float newCurrent; + float newConsumedCharge; + float newFuelConsumed; + quint8 modelCrashInhibit; + // ver 3.83 + qint16 newScreenW; // Simulator window position and size on screen + qint16 newScreenH; + qint16 newScreenX; + qint16 newScreenY; +} PACK_STRUCT ; // normal 516, packed 507 OK (3.81) + // normal ???, packed 515 OK (3.83 & 3.90) + +struct TPluginMenuItem +{ + quint32 OBSOLETE_eType; + char *OBSOLETE_strName; +} PACK_STRUCT ; + +struct pluginInit +{ + quint32 nStructSize; + char *OBSOLETE_strMenuTitle; + TPluginMenuItem OBSOLETE_atMenuItem[MAX_DLL_USER_MENU_ITEMS]; + const char *strPluginFolder; + const char *strOutputFolder; +} PACK_STRUCT ; // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90) + +#ifdef Q_CC_MSVC +#pragma pack (pop, r1) +#endif +#undef PACK_STRUCT + +#endif // AEROSIMRCDATASTRUCT_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h new file mode 100644 index 000000000..31abb1e0a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h @@ -0,0 +1,102 @@ +/** + ****************************************************************************** + * + * @file enums.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef ENUMS_H +#define ENUMS_H + +// Custom Menu Item masks +enum MenuMasks { + MenuEnable = (1 << 0), + MenuTx = (1 << 1), + MenuRx = (1 << 2), + MenuScreen = (1 << 3), + MenuNextWpt = (1 << 4), + MenuCmdReset = (1 << 5), + MenuLedBlue = (1 << 6), + MenuLedGreen = (1 << 7), + MenuFMode1 = (1 << 8), + MenuFMode2 = (1 << 9), + MenuFMode3 = (1 << 10) +}; + +enum EOverrideFlags +{ + OVR_POS = (1 << 0), + OVR_VEL = (1 << 1), + OVR_ANG_VEL = (1 << 2), + OVR_HPR = (1 << 3), // Override Heading, Pitch and Roll + OVR_WIND_VEL = (1 << 4), // Override Wind velocity at model + OVR_ENGINE_RPM = (1 << 5), // Override RPM of all Engines or Motors + OVR_BAT_VOLT = (1 << 6), // Override motor Battery Voltage + OVR_BAT_AMP = (1 << 7), // Override motor Battery current + OVR_BAT_AH_CONSUMED = (1 << 8), // Override motor Battery AmpsHour consumed + OVR_FUEL_CONSUMED = (1 << 9) // Override Fuel consumed (gas & jet engines) +}; + +enum Channels { + Ch1Aileron, + Ch2Elevator, + Ch3Throttle, + Ch4Rudder, + Ch5, + Ch6, + Ch7, + Ch8, + Ch9, + Ch10Retracts, + Ch11Flaps, + Ch12FPVCamPan, + Ch13FPVCamTilt, + Ch14Brakes, + Ch15Spoilers, + Ch16Smoke, + Ch17Fire, + Ch18FlightMode, + Ch19ALTHold, + Ch20FPVTiltHold, + Ch21ResetModel, + Ch22MouseTX, + Ch23Plugin1, + Ch24Plugin2, + Ch25ThrottleHold, + Ch26CareFree, + Ch27FPVCamRoll, + Ch28LMotorDual, + Ch29RMotorDual, + Ch30Mix, + Ch31Mix, + Ch32Mix, + Ch33Mix, + Ch34Mix, + Ch35Mix, + Ch36Mix, + Ch37Mix, + Ch38Mix, + Ch39Mix +}; + +#endif // ENUMS_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp new file mode 100644 index 000000000..e2100f608 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp @@ -0,0 +1,394 @@ +/** + ****************************************************************************** + * + * @file plugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "plugin.h" +#include "udpconnect.h" +#include "qdebughandler.h" +#include "enums.h" +#include "settings.h" + +bool isFirstRun = true; +QString debugInfo(DBG_BUFFER_MAX_SIZE, ' '); +QString pluginFolder(MAX_PATH, ' '); +QString outputFolder(MAX_PATH, ' '); + +QList videoModes; +QTime ledTimer; + +UdpSender *sndr; +UdpReciever *rcvr; + +const float RAD2DEG = (float)(180.0 / M_PI); +const float DEG2RAD = (float)(M_PI / 180.0); + +//extern "C" int __stdcall DllMain(HINSTANCE hinstDLL, DWORD fdwReason, LPVOID lpvReserved) +extern "C" int __stdcall DllMain(void*, quint32 fdwReason, void*) +{ + switch (fdwReason) { + case 0: +// qDebug() << hinstDLL << "DLL_PROCESS_DETACH " << lpvReserved; +// free resources here + rcvr->stop(); + rcvr->wait(500); + delete rcvr; + delete sndr; + qDebug("------"); + break; + case 1: +// qDebug() << hinstDLL << " DLL_PROCESS_ATTACH " << lpvReserved; + break; + case 2: +// qDebug() << hinstDLL << "DLL_THREAD_ATTACH " << lpvReserved; + break; + case 3: +// qDebug() << hinstDLL << "DLL_THREAD_DETACH " << lpvReserved; + break; + } + return true; +} + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_ReportStructSizes(quint32 *sizeSimToPlugin, + quint32 *sizePluginToSim, + quint32 *sizePluginInit) +{ + // debug redirection + qInstallMsgHandler(myQDebugHandler); + + qDebug() << "AeroSIMRC_Plugin_ReportStructSizes"; + *sizeSimToPlugin = sizeof(simToPlugin); + *sizePluginToSim = sizeof(pluginToSim); + *sizePluginInit = sizeof(pluginInit); + qDebug() << "sizeSimToPlugin = " << *sizeSimToPlugin; + qDebug() << "sizePluginToSim = " << *sizePluginToSim; + qDebug() << "sizePluginInit = " << *sizePluginInit; +} + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_Init(pluginInit *p) +{ + qDebug() << "AeroSIMRC_Plugin_Init begin"; + + pluginFolder = p->strPluginFolder; + outputFolder = p->strOutputFolder; + + ledTimer.restart(); + + Settings *ini = new Settings(pluginFolder); + ini->read(); + + videoModes = ini->getVideoModes(); + + sndr = new UdpSender(ini->getOutputMap(), ini->isFromTX()); + sndr->init(ini->remoteHost(), ini->remotePort()); + + rcvr = new UdpReciever(ini->getInputMap(), ini->isToRX()); + rcvr->init(ini->localHost(), ini->localPort()); + + // run thread + rcvr->start(); + + delete ini; + + qDebug() << "AeroSIMRC_Plugin_Init done"; +} + +//----------------------------------------------------------------------------- + +void Run_Command_Reset(/*const simToPlugin *stp, + pluginToSim *pts*/) +{ + // Print some debug info, although it will only be seen during one frame + debugInfo.append("\nRESET"); +} + +void Run_Command_WindowSizeAndPos(const simToPlugin *stp, + pluginToSim *pts) +{ + static quint8 snSequence = 0; + quint8 idx = snSequence * 4; + + if (snSequence >= videoModes.at(0)) { // set fullscreen + pts->newScreenX = 0; + pts->newScreenY = 0; + pts->newScreenW = stp->screenW; + pts->newScreenH = stp->screenH; + snSequence = 0; + } else { // set video mode from config + pts->newScreenX = videoModes.at(idx + 1); + pts->newScreenY = videoModes.at(idx + 2); + pts->newScreenW = videoModes.at(idx + 3); + pts->newScreenH = videoModes.at(idx + 4); + snSequence++; + } +} + +void Run_Command_MoveToNextWaypoint(const simToPlugin *stp, + pluginToSim *pts) +{ + static quint8 snSequence = 0; + + switch(snSequence) { + case 0: + pts->newPosX = stp->wpAX; + pts->newPosY = stp->wpAY; + pts->newPosZ = 100.0; + break; + case 1: + pts->newPosX = stp->wpBX; + pts->newPosY = stp->wpBY; + pts->newPosZ = 100.0; + break; + case 2: + pts->newPosX = stp->wpCX; + pts->newPosY = stp->wpCY; + pts->newPosZ = 100.0; + break; + case 3: + pts->newPosX = stp->wpDX; + pts->newPosY = stp->wpDY; + pts->newPosZ = 100.0; + break; + case 4: + pts->newPosX = stp->wpHomeX; + pts->newPosY = stp->wpHomeY; + pts->newPosZ = 100.0; + break; + default: + qFatal("Run_Command_MoveToNextWaypoint switch error"); + } + pts->modelOverrideFlags = 0; + pts->modelOverrideFlags |= OVR_POS; + + snSequence++; + if(snSequence > 4) + snSequence = 0; +} + +void Run_BlinkLEDs(const simToPlugin *stp, + pluginToSim *pts) +{ + if ((stp->simMenuStatus & MenuEnable) != 0) { + pts->newMenuStatus |= MenuLedGreen; + int timeout; + quint8 armed; + quint8 mode; + rcvr->getFlighStatus(armed, mode); + debugInfo.append(QString("armed: %1, mode: %2\n").arg(armed).arg(mode)); + + if (armed == 0) // disarm + timeout = 1000; + else if (armed == 1) // arming + timeout = 40; + else if (armed == 2) // armed + timeout = 100; + else // unknown + timeout = 2000; + if (ledTimer.elapsed() > timeout) { + ledTimer.restart(); + pts->newMenuStatus ^= MenuLedBlue; + } + + if (mode == 6) { + pts->newMenuStatus |= MenuFMode3; + pts->newMenuStatus |= MenuFMode2; + pts->newMenuStatus |= MenuFMode1; + } else if (mode == 5) { + pts->newMenuStatus |= MenuFMode3; + pts->newMenuStatus |= MenuFMode2; + pts->newMenuStatus &= ~MenuFMode1; + } else if (mode == 4) { + pts->newMenuStatus |= MenuFMode3; + pts->newMenuStatus &= ~MenuFMode2; + pts->newMenuStatus |= MenuFMode1; + } else if (mode == 3) { + pts->newMenuStatus |= MenuFMode3; + pts->newMenuStatus &= ~MenuFMode2; + pts->newMenuStatus &= ~MenuFMode1; + } else if (mode == 2) { + pts->newMenuStatus &= ~MenuFMode3; + pts->newMenuStatus |= MenuFMode2; + pts->newMenuStatus &= ~MenuFMode1; + } else if (mode == 1) { + pts->newMenuStatus &= ~MenuFMode3; + pts->newMenuStatus &= ~MenuFMode2; + pts->newMenuStatus |= MenuFMode1; + } else /*(mode == 0)*/ { + pts->newMenuStatus &= ~MenuFMode3; + pts->newMenuStatus &= ~MenuFMode2; + pts->newMenuStatus &= ~MenuFMode1; + } + } else { + pts->newMenuStatus = 0; + } +} + +void InfoText(const simToPlugin *stp, + pluginToSim *pts) +{ + debugInfo.append( + QString( + "Plugin Folder = %1\n" + "Output Folder = %2\n" + "nStructSize = %3 " + "fIntegrationTimeStep = %4\n" + "\n" + "Aileron TX = %5 RX = %6 RCMD TX = %7 RX = %8\n" + "Elevator TX = %9 RX = %10 RCMD TX = %11 RX = %12\n" + "Throttle TX = %13 RX = %14 RCMD TX = %15 RX = %16\n" + "Rudder TX = %17 RX = %18 RCMD TX = %19 RX = %20\n" + "Channel5 TX = %21 RX = %22 RCMD TX = %23 RX = %24\n" + "Channel6 TX = %25 RX = %26 RCMD TX = %27 RX = %28\n" + "Channel7 TX = %29 RX = %30 RCMD TX = %31 RX = %32\n" + "PluginCh1 TX = %33 RX = %34 RCMD TX = %35 RX = %36\n" + "PluginCh2 TX = %37 RX = %38 RCMD TX = %39 RX = %40\n" + "FPVCamPan TX = %41 RX = %42 RCMD TX = %43 RX = %44\n" + "FPVCamTil TX = %45 RX = %46 RCMD TX = %47 RX = %48\n" + "\n" + "MenuItems = %49\n" + // Model data + "\n" + "fPosX,Y,Z = (%50, %51, %52)\n" + "fVelX,Y,Z = (%53, %54, %55)\n" + "fAngVelX,Y,Z = (%56, %57, %58)\n" + "fAccelX,Y,Z = (%59, %60, %61)\n" + "\n" + "Lat, Long = %62, %63\n" + "fHeightAboveTerrain = %64\n" + "\n" + "fHeading = %65 fPitch = %66 fRoll = %67\n" + ) + .arg(pluginFolder) + .arg(outputFolder) + .arg(stp->structSize) + .arg(1.0 / stp->simTimeStep, 4, 'f', 1) + .arg(stp->chSimTX[Ch1Aileron], 5, 'f', 2) + .arg(stp->chSimRX[Ch1Aileron], 5, 'f', 2) + .arg(pts->chNewTX[Ch1Aileron], 5, 'f', 2) + .arg(pts->chNewRX[Ch1Aileron], 5, 'f', 2) + .arg(stp->chSimTX[Ch2Elevator], 5, 'f', 2) + .arg(stp->chSimRX[Ch2Elevator], 5, 'f', 2) + .arg(pts->chNewTX[Ch2Elevator], 5, 'f', 2) + .arg(pts->chNewRX[Ch2Elevator], 5, 'f', 2) + .arg(stp->chSimTX[Ch3Throttle], 5, 'f', 2) + .arg(stp->chSimRX[Ch3Throttle], 5, 'f', 2) + .arg(pts->chNewTX[Ch3Throttle], 5, 'f', 2) + .arg(pts->chNewRX[Ch3Throttle], 5, 'f', 2) + .arg(stp->chSimTX[Ch4Rudder], 5, 'f', 2) + .arg(stp->chSimRX[Ch4Rudder], 5, 'f', 2) + .arg(pts->chNewTX[Ch4Rudder], 5, 'f', 2) + .arg(pts->chNewRX[Ch4Rudder], 5, 'f', 2) + .arg(stp->chSimTX[Ch5], 5, 'f', 2) + .arg(stp->chSimRX[Ch5], 5, 'f', 2) + .arg(pts->chNewTX[Ch5], 5, 'f', 2) + .arg(pts->chNewRX[Ch5], 5, 'f', 2) + .arg(stp->chSimTX[Ch6], 5, 'f', 2) + .arg(stp->chSimRX[Ch6], 5, 'f', 2) + .arg(pts->chNewTX[Ch6], 5, 'f', 2) + .arg(pts->chNewRX[Ch6], 5, 'f', 2) + .arg(stp->chSimTX[Ch7], 5, 'f', 2) + .arg(stp->chSimRX[Ch7], 5, 'f', 2) + .arg(pts->chNewTX[Ch7], 5, 'f', 2) + .arg(pts->chNewRX[Ch7], 5, 'f', 2) + .arg(stp->chSimTX[Ch23Plugin1], 5, 'f', 2) + .arg(stp->chSimRX[Ch23Plugin1], 5, 'f', 2) + .arg(pts->chNewTX[Ch23Plugin1], 5, 'f', 2) + .arg(pts->chNewRX[Ch23Plugin1], 5, 'f', 2) + .arg(stp->chSimTX[Ch24Plugin2], 5, 'f', 2) + .arg(stp->chSimRX[Ch24Plugin2], 5, 'f', 2) + .arg(pts->chNewTX[Ch24Plugin2], 5, 'f', 2) + .arg(pts->chNewRX[Ch24Plugin2], 5, 'f', 2) + .arg(stp->chSimTX[Ch12FPVCamPan], 5, 'f', 2) + .arg(stp->chSimRX[Ch12FPVCamPan], 5, 'f', 2) + .arg(pts->chNewTX[Ch12FPVCamPan], 5, 'f', 2) + .arg(pts->chNewRX[Ch12FPVCamPan], 5, 'f', 2) + .arg(stp->chSimTX[Ch13FPVCamTilt], 5, 'f', 2) + .arg(stp->chSimRX[Ch13FPVCamTilt], 5, 'f', 2) + .arg(pts->chNewTX[Ch13FPVCamTilt], 5, 'f', 2) + .arg(pts->chNewRX[Ch13FPVCamTilt], 5, 'f', 2) + .arg(stp->simMenuStatus) + .arg(stp->posX, 5, 'f', 2) + .arg(stp->posY, 5, 'f', 2) + .arg(stp->posZ, 5, 'f', 2) + .arg(stp->velX, 5, 'f', 2) + .arg(stp->velY, 5, 'f', 2) + .arg(stp->velZ, 5, 'f', 2) + .arg(stp->angVelXm, 5, 'f', 2) + .arg(stp->angVelYm, 5, 'f', 2) + .arg(stp->angVelZm, 5, 'f', 2) + .arg(stp->accelXm, 5, 'f', 2) + .arg(stp->accelYm, 5, 'f', 2) + .arg(stp->accelZm, 5, 'f', 2) + .arg(stp->latitude, 5, 'f', 2) + .arg(stp->longitude, 5, 'f', 2) + .arg(stp->AGL, 5, 'f', 2) + .arg(stp->heading*RAD2DEG, 5, 'f', 2) + .arg(stp->pitch*RAD2DEG, 5, 'f', 2) + .arg(stp->roll*RAD2DEG, 5, 'f', 2) + ); +} + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_Run(const simToPlugin *stp, + pluginToSim *pts) +{ + debugInfo = "---\n"; + // By default do not change the Menu Items of type CheckBox + pts->newMenuStatus = stp->simMenuStatus; + // Extract Menu Commands from Flags + bool isReset = (stp->simMenuStatus & MenuCmdReset) != 0; + bool isEnable = (stp->simMenuStatus & MenuEnable) != 0; + bool isTxON = (stp->simMenuStatus & MenuTx) != 0; + bool isRxON = (stp->simMenuStatus & MenuRx) != 0; + bool isScreen = (stp->simMenuStatus & MenuScreen) != 0; + bool isNextWp = (stp->simMenuStatus & MenuNextWpt) != 0; + // Run commands + if (isReset) { + Run_Command_Reset(/*stp, pts*/); + } else if (isScreen) { + Run_Command_WindowSizeAndPos(stp, pts); + } else if (isNextWp) { + Run_Command_MoveToNextWaypoint(stp, pts); + } else { + Run_BlinkLEDs(stp, pts); + if (isEnable) { + if (isTxON) + sndr->sendDatagram(stp); + if (isRxON) + rcvr->setChannels(pts); + } + + // network lag + debugInfo.append(QString("out: %1, inp: %2, delta: %3\n") + .arg(sndr->pcks() - 1) + .arg(rcvr->pcks()) + .arg(sndr->pcks() - rcvr->pcks() - 1) + ); + } + + // debug info is shown on the screen + InfoText(stp, pts); + pts->dbgInfoText = debugInfo.toAscii(); + isFirstRun = false; +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h new file mode 100644 index 000000000..a590c8a24 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h @@ -0,0 +1,53 @@ +/** + ****************************************************************************** + * + * @file plugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PLUGIN_H +#define PLUGIN_H + +#include +#include +#include +#include "aerosimrcdatastruct.h" + +#define SIM_DLL_EXPORT extern "C" __declspec(dllexport) + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_ReportStructSizes( + quint32 *sizeSimToPlugin, + quint32 *sizePluginToSim, + quint32 *sizePluginInit +); + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_Init( + pluginInit *p +); + +SIM_DLL_EXPORT void AeroSIMRC_Plugin_Run( + const simToPlugin *stp, + pluginToSim *pts +); + +#endif // PLUGIN_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro new file mode 100644 index 000000000..ca149d262 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -0,0 +1,28 @@ +!win32 { error("AeroSimRC plugin is only available for win32 platform") } + +QT += network +QT -= gui +TARGET = plugin_AeroSIMRC +TEMPLATE = lib + +# Don't depend on MSVRT*.dll +win32-msvc* { + QMAKE_CXXFLAGS_RELEASE -= -MD + QMAKE_CXXFLAGS_MT_DLL += -MT +} + +HEADERS = \ + aerosimrcdatastruct.h \ + enums.h \ + plugin.h \ + qdebughandler.h \ + udpconnect.h \ + settings.h + +SOURCES = \ + qdebughandler.cpp \ + plugin.cpp \ + udpconnect.cpp \ + settings.cpp + +#DLLDESTDIR = ../CopterControl diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp new file mode 100644 index 000000000..bb9617511 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp @@ -0,0 +1,64 @@ +/** + ****************************************************************************** + * + * @file qdebughandler.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "qdebughandler.h" + +void myQDebugHandler(QtMsgType type, const char *msg) +{ + static bool firstRun = true; + QString txt; + + switch (type) { + case QtDebugMsg: + txt = QString("Debug: %1").arg(msg); + break; + case QtWarningMsg: + txt = QString("Warning: %1").arg(msg); + break; + case QtCriticalMsg: + txt = QString("Critical: %1").arg(msg); + break; + case QtFatalMsg: + txt = QString("Fatal: %1").arg(msg); + break; + } + + QFile outFile("dbglog.txt"); + outFile.open(QIODevice::WriteOnly | QIODevice::Append); + QTextStream ts(&outFile); + QTime time; + + if (firstRun) { + ts << endl << endl; + firstRun = false; + } + + ts << time.currentTime().toString("hh:mm:ss.zzz") << " " << txt << endl; + + if (type == QtFatalMsg) + abort(); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h new file mode 100644 index 000000000..d41dc6a67 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h @@ -0,0 +1,37 @@ +/** + ****************************************************************************** + * + * @file qdebughandler.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef QDEBUGHANDLER_H +#define QDEBUGHANDLER_H + +#include +#include +#include + +void myQDebugHandler(QtMsgType type, const char *msg); + +#endif // QDEBUGHANDLER_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp new file mode 100644 index 000000000..6c19f91dc --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp @@ -0,0 +1,98 @@ +/** + ****************************************************************************** + * + * @file settings.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "settings.h" + +Settings::Settings(QString settingsPath, QObject *parent) : + QObject(parent) +{ + settings = new QSettings(settingsPath + "/cc_plugin.ini", QSettings::IniFormat); + // default settings + sendToHost = "127.0.0.1"; + sendToPort = 40100; + listenOnHost = "127.0.0.1"; + listenOnPort = 40200; + channels.reserve(60); + for (quint8 i = 0; i < 10; ++i) + inputMap << 255; + for (quint8 i = 0; i < 8; ++i) + outputMap << 255; + sendToRX = true; + takeFromTX = true; + videoModes << 1 << 50 << 50 << 800 << 600; +} + +void Settings::read() +{ + // network + listenOnHost = settings->value("listen_on_host", listenOnHost).toString(); + listenOnPort = settings->value("listen_on_port", listenOnPort).toInt(); + sendToHost = settings->value("send_to_host", sendToHost).toString(); + sendToPort = settings->value("send_to_port", sendToPort).toInt(); + + QString allChannels = settings->value("all_channels").toString(); + QString chan; + int i = 0; + foreach (chan, allChannels.split(" ")) + channels.insert(chan, i++); + + // inputs + QString num = ""; + QString map = ""; + for (quint8 i = 0; i < 10; ++i) { + num = QString::number(i+1); + map = settings->value("Input/cc_channel_" + num).toString(); + inputMap[i] = channels.value(map, inputMap.at(i)); + } + + QString sendTo = settings->value("Input/send_to", "RX").toString(); + sendToRX = (sendTo == "RX") ? true : false; + + // outputs + for (quint8 i = 0; i < 8; ++i) { + num = QString::number(i+1); + map = settings->value("Output/sim_channel_" + num).toString(); + outputMap[i] = channels.value(map, outputMap.at(i)); + } + + QString takeFrom = settings->value("Output/take_from", "TX").toString(); + takeFromTX = (takeFrom == "TX") ? true : false; + + // video + quint8 resolutionNum = settings->value("Video/number_of_resolutions", 0).toInt(); + if (resolutionNum > 0) { + videoModes.clear(); + videoModes << resolutionNum; + for (quint8 i = 0; i < resolutionNum; ++i) { + num = QString::number(i+1); + QString modes = settings->value("Video/resolution_" + num, "0, 0, 640, 480").toString(); + QString mode; + foreach (mode, modes.split(" ")) + videoModes << mode.toInt(); + } + } +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h new file mode 100644 index 000000000..5bc39135d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h @@ -0,0 +1,67 @@ +/** + ****************************************************************************** + * + * @file settings.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef SETTINGS_H +#define SETTINGS_H + +#include +#include +#include +#include +#include +#include + +class Settings : public QObject +{ +public: + explicit Settings(QString settingsPath, QObject *parent = 0); + void read(); + QString remoteHost() { return sendToHost; } + quint16 remotePort() { return sendToPort; } + QString localHost() { return listenOnHost; } + quint16 localPort() { return listenOnPort; } + QList getInputMap() { return inputMap; } + QList getOutputMap() { return outputMap; } + bool isToRX() { return sendToRX; } + bool isFromTX() { return takeFromTX; } + QList getVideoModes() { return videoModes; } + +private: + QHash channels; + QSettings *settings; + QString sendToHost; + quint16 sendToPort; + QString listenOnHost; + quint16 listenOnPort; + QList inputMap; + QList outputMap; + bool sendToRX; + bool takeFromTX; + QList videoModes; +}; + +#endif // SETTINGS_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp new file mode 100644 index 000000000..06e77b163 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp @@ -0,0 +1,228 @@ +/** + ****************************************************************************** + * + * @file udpconnect.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "udpconnect.h" +#include "enums.h" + +UdpSender::UdpSender(const QList map, + bool isTX, + QObject *parent) + : QObject(parent) +{ + qDebug() << this << "UdpSender::UdpSender thread:" << thread(); + outSocket = NULL; + for (int i = 0; i < 8; ++i) + channels << 0.0; + channelsMap = map; + takeFromTX = isTX; + packetsSended = 0; +} + +UdpSender::~UdpSender() +{ + qDebug() << this << "UdpSender::~UdpSender"; + if (outSocket) + delete outSocket; +} + +// public +void UdpSender::init(const QString &remoteHost, quint16 remotePort) +{ + qDebug() << this << "UdpSender::init"; + outHost = remoteHost; + outPort = remotePort; + outSocket = new QUdpSocket(); +} + +void UdpSender::sendDatagram(const simToPlugin *stp) +{ + QByteArray data; + data.resize(188); + QDataStream out(&data, QIODevice::WriteOnly); + out.setFloatingPointPrecision(QDataStream::SinglePrecision); + + // magic header, "AERO" + out << quint32(0x4153494D); + // simulation step + out << stp->simTimeStep; + // home location + out << stp->initPosX << stp->initPosY << stp->initPosZ; + out << stp->wpHomeX << stp->wpHomeY << stp->wpHomeLat << stp->wpHomeLong; + // position + out << stp->posX << stp->posY << stp->posZ; + // velocity (world) + out << stp->velX << stp->velY << stp->velZ; + // angular velocity (model) + out << stp->angVelXm << stp->angVelYm << stp->angVelZm; + // acceleration (model) + out << stp->accelXm << stp->accelYm << stp->accelZm; + // coordinates + out << stp->latitude << stp->longitude; + // sonar + out << stp->AGL; + // attitude + out << stp->heading << stp->pitch << stp->roll; + // electric + out << stp->voltage << stp->current; + // matrix + out << stp->axisXx << stp->axisXy << stp->axisXz; + out << stp->axisYx << stp->axisYy << stp->axisYz; + out << stp->axisZx << stp->axisZy << stp->axisZz; + // channels + for (int i = 0; i < 8; ++i) { + quint8 mapTo = channelsMap.at(i); + if (mapTo == 255) // unused channel + out << 0.0; + else if (takeFromTX) // use values from simulators transmitter + out << stp->chSimTX[mapTo]; + else // direct use values from ESC/motors/ailerons/etc + out << stp->chSimRX[mapTo]; + } + + // packet counter + out << packetsSended; + + outSocket->writeDatagram(data, outHost, outPort); + ++packetsSended; +} + +//----------------------------------------------------------------------------- + +UdpReciever::UdpReciever(const QList map, + bool isRX, + QObject *parent) + : QThread(parent) +{ + qDebug() << this << "UdpReciever::UdpReciever thread:" << thread(); + + stopped = false; + inSocket = NULL; + for (int i = 0; i < 10; ++i) + channels << -1.0; + channelsMap = map; + sendToRX = isRX; + armed = 0; + mode = 0; + packetsRecived = 1; +} + +UdpReciever::~UdpReciever() +{ + qDebug() << this << "UdpReciever::~UdpReciever"; + if (inSocket) + delete inSocket; +} + +// public +void UdpReciever::init(const QString &localHost, quint16 localPort) +{ + qDebug() << this << "UdpReciever::init"; + + inSocket = new QUdpSocket(); + qDebug() << this << "inSocket constructed" << inSocket->thread(); + + inSocket->bind(QHostAddress(localHost), localPort); +} + +void UdpReciever::run() +{ + qDebug() << this << "UdpReciever::run start"; + while (!stopped) + onReadyRead(); + qDebug() << this << "UdpReciever::run ended"; +} + +void UdpReciever::stop() +{ + qDebug() << this << "UdpReciever::stop"; + stopped = true; +} + +void UdpReciever::setChannels(pluginToSim *pts) +{ + QMutexLocker locker(&mutex); + + for (int i = 0; i < 10; ++i) { + quint8 mapTo = channelsMap.at(i); + if (mapTo != 255) { + float channelValue = qBound(-1.0f, channels.at(i), 1.0f); + if (sendToRX) { + // direct connect to ESC/motors/ailerons/etc + pts->chNewRX[mapTo] = channelValue; + pts->chOverRX[mapTo] = true; + } else { + // replace simulators transmitter + pts->chNewTX[mapTo] = channelValue; + pts->chOverTX[mapTo] = true; + } + } + } +} + +void UdpReciever::getFlighStatus(quint8 &arm, quint8 &mod) +{ + QMutexLocker locker(&mutex); + + arm = armed; + mod = mode; +} + +// private +void UdpReciever::onReadyRead() +{ + if (!inSocket->waitForReadyRead(8)) // 1/60fps ~= 16.7ms, 1/120fps ~= 8.3ms + return; + // TODO: add failsafe + // if a command not recieved then slowly return all channel to neutral + // + while (inSocket->hasPendingDatagrams()) { + QByteArray datagram; + datagram.resize(inSocket->pendingDatagramSize()); + quint64 datagramSize; + datagramSize = inSocket->readDatagram(datagram.data(), datagram.size()); + + processDatagram(datagram); + } +} + +void UdpReciever::processDatagram(QByteArray &datagram) +{ + QDataStream stream(datagram); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + // check magic header + quint32 magic; + stream >> magic; + if (magic != 0x52434D44) // "RCMD" + return; + // read channels + for (int i = 0; i < 10; ++i) + stream >> channels[i]; + // read flight mode + stream >> armed >> mode; + // read counter + stream >> packetsRecived; +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h new file mode 100644 index 000000000..82b944e77 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h @@ -0,0 +1,90 @@ +/** + ****************************************************************************** + * + * @file udpconnect.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UDPCONNECT_H +#define UDPCONNECT_H + +#include +#include +#include +#include +#include +#include +#include "aerosimrcdatastruct.h" + +class UdpSender : public QObject +{ +// Q_OBJECT +public: + explicit UdpSender(const QList map, bool isTX, QObject *parent = 0); + ~UdpSender(); + void init(const QString &remoteHost, quint16 remotePort); + void sendDatagram(const simToPlugin *stp); + quint32 pcks() { return packetsSended; } + +private: + QUdpSocket *outSocket; + QHostAddress outHost; + quint16 outPort; + QList channels; + QList channelsMap; + bool takeFromTX; + quint32 packetsSended; +}; + + +class UdpReciever : public QThread +{ +// Q_OBJECT +public: + explicit UdpReciever(const QList map, bool isRX, QObject *parent = 0); + ~UdpReciever(); + void init(const QString &localHost, quint16 localPort); + void run(); + void stop(); + // function getChannels for other threads + void setChannels(pluginToSim *pts); + void getFlighStatus(quint8 &arm, quint8 &mod); + quint8 getArmed() { return armed; } + quint8 getMode() { return mode; } + quint32 pcks() { return packetsRecived; } + +private: + volatile bool stopped; + QMutex mutex; + QUdpSocket *inSocket; + QList channels; + QList channelsMap; + bool sendToRX; + quint8 armed; + quint8 mode; + quint32 packetsRecived; + void onReadyRead(); + void processDatagram(QByteArray &datagram); +}; + +#endif // UDPCONNECT_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro new file mode 100644 index 000000000..ca9b90870 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro @@ -0,0 +1,14 @@ +QT += core gui network + +TARGET = udptest +TEMPLATE = app + +HEADERS += \ + udptestwidget.h + +SOURCES += \ + udptestmain.cpp \ + udptestwidget.cpp + +FORMS += \ + udptestwidget.ui diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp new file mode 100644 index 000000000..744e4bf25 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp @@ -0,0 +1,38 @@ +/** + ****************************************************************************** + * + * @file udptestmain.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin test utility + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include "udptestwidget.h" + +int main(int argc, char *argv[]) +{ + QApplication a(argc, argv); + Widget w; + w.show(); + + return a.exec(); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp new file mode 100644 index 000000000..9135d5a29 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp @@ -0,0 +1,537 @@ +/** + ****************************************************************************** + * + * @file udptestwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin test utility + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "udptestwidget.h" +#include "ui_udptestwidget.h" + +Widget::Widget(QWidget *parent) : + QWidget(parent), + ui(new Ui::Widget) +{ + ui->setupUi(this); + + inSocket = NULL; + outSocket = NULL; + screenTimeout.start(); + packetCounter = 0; + + autoSendTimer = new QTimer(this); + connect(autoSendTimer, SIGNAL(timeout()), this, SLOT(sendDatagram()), Qt::DirectConnection); +} + +Widget::~Widget() +{ + if(outSocket) { + delete outSocket; + } + if(inSocket) { + delete inSocket; + } + delete ui; +} + +// private slots ////////////////////////////////////////////////////////////// + +void Widget::on_btReciveStart_clicked() +{ + on_btReciveStop_clicked(); + + inSocket = new QUdpSocket(); + QString host = ui->localHost->text(); + quint16 port = ui->localPort->text().toInt(); + + if (inSocket->bind(QHostAddress(host), port)) { + connect(inSocket, SIGNAL(readyRead()), + this, SLOT(readDatagram()), Qt::DirectConnection); + + ui->listWidget->addItem("bind ok"); + ui->btReciveStop->setEnabled(1); + ui->localHost->setDisabled(1); + ui->localPort->setDisabled(1); + ui->btReciveStart->setDisabled(1); + } else { + ui->listWidget->addItem("bind error: " + inSocket->errorString()); + } +} + +void Widget::on_btReciveStop_clicked() +{ + if(inSocket) { + delete inSocket; + inSocket = NULL; + ui->listWidget->addItem("unbind ok"); + } else { + ui->listWidget->addItem("socket not found"); + } + ui->btReciveStart->setEnabled(1); + ui->localHost->setEnabled(1); + ui->localPort->setEnabled(1); + ui->btReciveStop->setDisabled(1); +} + +void Widget::on_btTransmitStart_clicked() +{ + on_btTransmitStop_clicked(); + + outSocket = new QUdpSocket(); + outHost = ui->simHost->text(); + outPort = ui->simPort->text().toInt(); + + ui->listWidget->addItem("transmit started"); + ui->btTransmitStop->setEnabled(1); + ui->simHost->setDisabled(1); + ui->simPort->setDisabled(1); + ui->btTransmitStart->setDisabled(1); +} + +void Widget::on_btTransmitStop_clicked() +{ + if(outSocket) { + delete outSocket; + outSocket = NULL; + ui->listWidget->addItem("transmit stopped"); + } else { + ui->listWidget->addItem("transmit socket not found"); + } + ui->btTransmitStart->setEnabled(1); + ui->simHost->setEnabled(1); + ui->simPort->setEnabled(1); + ui->btTransmitStop->setDisabled(1); +} + +void Widget::readDatagram() +{ + while (inSocket->hasPendingDatagrams()) { + QByteArray datagram; + datagram.resize(inSocket->pendingDatagramSize()); + QHostAddress sender; + quint16 senderPort; + quint64 datagramSize = inSocket->readDatagram(datagram.data(), datagram.size(), + &sender, &senderPort); + Q_UNUSED(datagramSize); + + processDatagram(datagram); + if (ui->autoAnswer->isChecked()) + sendDatagram(); + } +} + +// private //////////////////////////////////////////////////////////////////// + +void Widget::processDatagram(const QByteArray &data) +{ + QByteArray buf = data; + QDataStream stream(&buf, QIODevice::ReadOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + + // check magic header + quint32 magic; + stream >> magic; + if (magic == 0x4153494D) { // "AERO" + float timeStep, + homeX, homeY, homeZ, + WpHX, WpHY, WpLat, WpLon, + posX, posY, posZ, + velX, velY, velZ, + angX, angY, angZ, + accX, accY, accZ, + lat, lon, alt, + head, pitch, roll, + volt, curr, + rx, ry, rz, fx, fy, fz, ux, uy, uz, + chAil, chEle, chThr, chRud, chPlg1, chPlg2, chFpv1, chFpv2; + + stream >> timeStep; + stream >> homeX >> homeY >> homeZ; + stream >> WpHX >> WpHY >> WpLat >> WpLon; + stream >> posX >> posY >> posZ; + stream >> velX >> velY >> velZ; + stream >> angX >> angY >> angZ; + stream >> accX >> accY >> accZ; + stream >> lat >> lon >> alt; + stream >> head >> pitch >> roll; + stream >> volt >> curr; + stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz; + stream >> chAil >> chEle >> chThr >> chRud >> chPlg1 >> chPlg2 >> chFpv1 >> chFpv2; + stream >> packetCounter; + + if(ui->tabWidget->currentIndex() != 0) + return; + + if (screenTimeout.elapsed() < 200) + return; + + ui->listWidget->clear(); + /* + ui->listWidget->addItem("time step (s)"); + ui->listWidget->addItem(QString("%1") + .arg(timeStep); + ui->listWidget->addItem("home location (m)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(homeX, 7, 'f', 4) + .arg(homeY, 7, 'f', 4) + .arg(homeZ, 7, 'f', 4)); + ui->listWidget->addItem("home waypoint"); + ui->listWidget->addItem(QString("%1, %2, %3, %4") + .arg(WpHX, 7, 'f', 4) + .arg(WpHY, 7, 'f', 4) + .arg(WpLat, 7, 'f', 4) + .arg(WpLon, 7, 'f', 4)); + ui->listWidget->addItem("model position (m)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(posX, 7, 'f', 4) + .arg(posY, 7, 'f', 4) + .arg(posZ, 7, 'f', 4)); + ui->listWidget->addItem("model velocity (m/s)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(velX, 7, 'f', 4) + .arg(velY, 7, 'f', 4) + .arg(velZ, 7, 'f', 4)); + ui->listWidget->addItem("model angular velocity (rad/s)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(angX, 7, 'f', 4) + .arg(angY, 7, 'f', 4) + .arg(angZ, 7, 'f', 4)); + ui->listWidget->addItem("model acceleration (m/s/s)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(accX, 7, 'f', 4) + .arg(accY, 7, 'f', 4) + .arg(accZ, 7, 'f', 4)); + ui->listWidget->addItem("model coordinates (deg, deg, m)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(lat, 7, 'f', 4) + .arg(lon, 7, 'f', 4) + .arg(alt, 7, 'f', 4)); + ui->listWidget->addItem("model electrics"); + ui->listWidget->addItem(QString("%1V, %2A") + .arg(volt, 7, 'f', 4) + .arg(curr, 7, 'f', 4)); + ui->listWidget->addItem("channels"); + ui->listWidget->addItem(QString("%1 %2 %3 %4 %5 %6 %7 %8") + .arg(chAil, 6, 'f', 3) + .arg(chEle, 6, 'f', 3) + .arg(chThr, 6, 'f', 3) + .arg(chRud, 6, 'f', 3) + .arg(chPlg1, 6, 'f', 3) + .arg(chPlg2, 6, 'f', 3) + .arg(chFpv1, 6, 'f', 3) + .arg(chFpv2, 6, 'f', 3)); + ui->listWidget->addItem("datagram size (bytes), packet counter"); + ui->listWidget->addItem(QString("%1 %2") + .arg(data.size()) + .arg(packetCounter)); +*/ + + // matrix calculation start + // model matrix + QMatrix4x4 m = QMatrix4x4( fy, fx, -fz, 0.0, + ry, rx, -rz, 0.0, + -uy, -ux, uz, 0.0, + 0.0, 0.0, 0.0, 1.0); + m.optimize(); + + // world matrix + QMatrix4x4 w = m.inverted(); + + // model quat + QQuaternion q; + asMatrix2Quat(m, q); + + // model roll, pitch, yaw + QVector3D rpy; + asMatrix2RPY(m, rpy); + + // sonar + float sAlt = 5.0; + if ((alt < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) { + float x = alt * qTan(roll); + float y = alt * qTan(pitch); + float h = QVector3D(x, y, alt).length(); + sAlt = qMin(h, sAlt); + } + + ui->listWidget->addItem("sonar altitude"); + ui->listWidget->addItem(QString("%1") + .arg(sAlt, 8, 'f', 5)); + ui->listWidget->addItem("vectors"); + ui->listWidget->addItem(QString(" X Y Z")); + ui->listWidget->addItem(QString("R: %1 %2 %3\nF: %4 %5 %6\nU: %7 %8 %9") + .arg(rx, 8, 'f', 5).arg(ry, 8, 'f', 5).arg(rz, 8, 'f', 5) + .arg(fx, 8, 'f', 5).arg(fy, 8, 'f', 5).arg(fz, 8, 'f', 5) + .arg(ux, 8, 'f', 5).arg(uy, 8, 'f', 5).arg(uz, 8, 'f', 5)); + ui->listWidget->addItem("CC model matrix"); + ui->listWidget->addItem(QString(" %1 %2 %3\n %4 %5 %6\n %7 %8 %9") + .arg(m(0, 0), 8, 'f', 5).arg(m(0, 1), 8, 'f', 5).arg(m(0, 2), 8, 'f', 5) + .arg(m(1, 0), 8, 'f', 5).arg(m(1, 1), 8, 'f', 5).arg(m(1, 2), 8, 'f', 5) + .arg(m(2, 0), 8, 'f', 5).arg(m(2, 1), 8, 'f', 5).arg(m(2, 2), 8, 'f', 5)); + ui->listWidget->addItem("CC world matrix"); + ui->listWidget->addItem(QString(" %1 %2 %3\n %4 %5 %6\n %7 %8 %9") + .arg(w(0, 0), 8, 'f', 5).arg(w(0, 1), 8, 'f', 5).arg(w(0, 2), 8, 'f', 5) + .arg(w(1, 0), 8, 'f', 5).arg(w(1, 1), 8, 'f', 5).arg(w(1, 2), 8, 'f', 5) + .arg(w(2, 0), 8, 'f', 5).arg(w(2, 1), 8, 'f', 5).arg(w(2, 2), 8, 'f', 5)); + ui->listWidget->addItem("CC quaternion"); + ui->listWidget->addItem(QString("%1, %2, %3, %4") + .arg(q.x(), 7, 'f', 4) + .arg(q.y(), 7, 'f', 4) + .arg(q.z(), 7, 'f', 4) + .arg(q.scalar(), 7, 'f', 4)); + ui->listWidget->addItem("model attitude (deg)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(roll*RAD2DEG, 7, 'f', 4) + .arg(pitch*RAD2DEG, 7, 'f', 4) + .arg(head*RAD2DEG, 7, 'f', 4)); + ui->listWidget->addItem("CC attitude calculated (deg)"); + ui->listWidget->addItem(QString("%1, %2, %3") + .arg(rpy.x(), 7, 'f', 4) + .arg(rpy.y(), 7, 'f', 4) + .arg(rpy.z(), 7, 'f', 4)); + + screenTimeout.restart(); + + } else if (magic == 0x52434D44) { // "RCMD" + qreal ch1, ch2, ch3, ch4, ch5, ch6, ch7, ch8, ch9, ch10; + stream >> ch1 >> ch2 >> ch3 >> ch4 >> ch5 >> ch6 >> ch7 >> ch8 >> ch9 >> ch10; + quint8 armed, mode; + stream >> armed >> mode; + + if(ui->tabWidget->currentIndex() == 0) { + if (screenTimeout.elapsed() < 200) + return; + ui->listWidget->clear(); + ui->listWidget->addItem("channels"); + ui->listWidget->addItem("CH1: " + QString::number(ch1)); + ui->listWidget->addItem("CH2: " + QString::number(ch2)); + ui->listWidget->addItem("CH3: " + QString::number(ch3)); + ui->listWidget->addItem("CH4: " + QString::number(ch4)); + ui->listWidget->addItem("CH5: " + QString::number(ch5)); + ui->listWidget->addItem("CH6: " + QString::number(ch6)); + ui->listWidget->addItem("CH7: " + QString::number(ch7)); + ui->listWidget->addItem("CH8: " + QString::number(ch8)); + ui->listWidget->addItem("CH9: " + QString::number(ch9)); + ui->listWidget->addItem("CH10:" + QString::number(ch10)); + ui->listWidget->addItem("armed:" + QString::number(armed)); + ui->listWidget->addItem("fmode:" + QString::number(mode)); + } + screenTimeout.restart(); + } else { + qDebug() << "unknown magic:" << magic; + } +} + +void Widget::sendDatagram() +{ + if(!outSocket) + return; + + float ch[10]; // = {0,0,0,0,0,0,0,0,0,0}; + quint8 armed; + quint8 fmode; + const float coeff = 1.0 / 512.0; + + ch[0] = ui->ch1->value() * coeff; + ch[1] = ui->ch2->value() * coeff; + ch[2] = ui->ch3->value() * coeff; + ch[3] = ui->ch4->value() * coeff; + ch[4] = ui->ch5->value() * coeff; + ch[5] = ui->ch6->value() * coeff; + ch[6] = ui->ch7->value() * coeff; + ch[7] = ui->ch8->value() * coeff; + ch[8] = ui->ch9->value() * coeff; + ch[9] = ui->ch10->value() * coeff; + + armed = (ui->disarmed->isChecked()) ? 0 : (ui->arming->isChecked()) ? 1 : 2; + fmode = ui->flightMode->value(); + + QByteArray data; + // 50 - current size of values, 4(quint32) + 10*4(float) + 2*1(quint8) + 4(quint32) + data.resize(50); + QDataStream stream(&data, QIODevice::WriteOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + + // magic header, "RCMD" + stream << quint32(0x52434D44); + // send channels + for (int i = 0; i < 10; ++i) { + stream << ch[i]; + } + // send armed and mode + stream << armed << fmode; + // send readed counter + stream << packetCounter; + + if (outSocket->writeDatagram(data, outHost, outPort) == -1) { + qDebug() << "write failed: outHost" << outHost << " " + << "outPort " << outPort << " " + << outSocket->errorString(); + } +} + +void Widget::on_autoSend_clicked() +{ + autoSendTimer->start(100); + qDebug() << "timer start"; +} + +void Widget::on_autoAnswer_clicked() +{ + autoSendTimer->stop(); + qDebug() << "timer stop"; +} + +// transfomations + +void Widget::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q) +{ + qreal w, x, y, z; + + // w always >= 0 + w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0; + x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0; + y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0; + z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0; + + x = _copysign(x, (m(1, 2) - m(2, 1))); + y = _copysign(y, (m(2, 0) - m(0, 2))); + z = _copysign(z, (m(0, 1) - m(1, 0))); + + q.setScalar(w); + q.setX(x); + q.setY(y); + q.setZ(z); +} + +void Widget::asQuat2RPY(const QQuaternion &q, QVector3D &rpy) +{ + qreal roll; + qreal pitch; + qreal yaw; + + const qreal d2 = 2.0; + const qreal qss = q.scalar() * q.scalar(); + const qreal qxx = q.x() * q.x(); + const qreal qyy = q.y() * q.y(); + const qreal qzz = q.z() * q.z(); + + qreal test = -d2 * (q.x() * q.z() - q.scalar() * q.y()); + if (qFabs(test) > 0.998) { + // ~86.3, gimbal lock + qreal R10 = d2 * (q.x() * q.y() - q.scalar() * q.z()); + qreal R11 = qss - qxx + qyy - qzz; + + roll = 0.0; + pitch = _copysign(M_PI_2, test); + yaw = qAtan2(-R10, R11); + } else { + qreal R12 = d2 * (q.y() * q.z() + q.scalar() * q.x()); + qreal R22 = qss - qxx - qyy + qzz; + qreal R01 = d2 * (q.x() * q.y() + q.scalar() * q.z()); + qreal R00 = qss + qxx - qyy - qzz; + + roll = qAtan2(R12, R22); + pitch = qAsin(test); + yaw = qAtan2(R01, R00); + } + rpy.setX(RAD2DEG * roll); + rpy.setY(RAD2DEG * pitch); + rpy.setZ(RAD2DEG * yaw); +} + +void Widget::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy) +{ + qreal roll; + qreal pitch; + qreal yaw; + + if (qFabs(m(0, 2)) > 0.998) { + // ~86.3, gimbal lock + roll = 0.0; + pitch = _copysign(M_PI_2, -m(0, 2)); + yaw = qAtan2(-m(1, 0), m(1, 1)); + } else { + roll = qAtan2(m(1, 2), m(2, 2)); + pitch = qAsin(-m(0, 2)); + yaw = qAtan2(m(0, 1), m(0, 0)); + } + + rpy.setX(roll * RAD2DEG); + rpy.setY(pitch * RAD2DEG); + rpy.setZ(yaw * RAD2DEG); +} + +/* // not used + +void Widget::ccRPY2Quat(const QVector3D &rpy, QQuaternion &q) +{ + float phi, theta, psi; + float cphi, sphi, ctheta, stheta, cpsi, spsi; + + phi = rpy.x() / 2; + theta = rpy.y() / 2; + psi = rpy.z() / 2; + cphi = cosf(phi); + sphi = sinf(phi); + ctheta = cosf(theta); + stheta = sinf(theta); + cpsi = cosf(psi); + spsi = sinf(psi); + + q.setScalar(cphi * ctheta * cpsi + sphi * stheta * spsi); + q.setX(sphi * ctheta * cpsi - cphi * stheta * spsi); + q.setY(cphi * stheta * cpsi + sphi * ctheta * spsi); + q.setZ(cphi * ctheta * spsi - sphi * stheta * cpsi); + + if (q.scalar() < 0) { // q0 always positive for uniqueness + q.setScalar(-q.scalar()); + q.setX(-q.x()); + q.setY(-q.y()); + q.setZ(-q.z()); + } +} + +void Widget::ccQuat2Matrix(const QQuaternion &q, QMatrix4x4 &m) +{ + float q0s = q.scalar() * q.scalar(); + float q1s = q.x() * q.x(); + float q2s = q.y() * q.y(); + float q3s = q.z() * q.z(); + + float m00 = q0s + q1s - q2s - q3s; + float m01 = 2 * (q.x() * q.y() + q.scalar() * q.z()); + float m02 = 2 * (q.x() * q.z() - q.scalar() * q.y()); + float m10 = 2 * (q.x() * q.y() - q.scalar() * q.z()); + float m11 = q0s - q1s + q2s - q3s; + float m12 = 2 * (q.y() * q.z() + q.scalar() * q.x()); + float m20 = 2 * (q.x() * q.z() + q.scalar() * q.y()); + float m21 = 2 * (q.y() * q.z() - q.scalar() * q.x()); + float m22 = q0s - q1s - q2s + q3s; + + m = QMatrix4x4(m00, m01, m02, 0, + m10, m11, m12, 0, + m20, m21, m22, 0, + 0, 0, 0, 1); +} +*/ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h new file mode 100644 index 000000000..eeca63555 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h @@ -0,0 +1,94 @@ +/** + ****************************************************************************** + * + * @file udptestwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup 3rdParty Third-party integration + * @{ + * @addtogroup AeroSimRC AeroSimRC proxy plugin + * @{ + * @brief AeroSimRC simulator to HITL proxy plugin test utility + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UDPTESTWIDGET_H +#define UDPTESTWIDGET_H + +#include +#include +#include +#if defined(Q_CC_MSVC) +#define _USE_MATH_DEFINES +#endif +#include +#include +#include +#include +#include + +namespace Ui { + class Widget; +} + +const float RAD2DEG = (float)(180.0/M_PI); +const float DEG2RAD = (float)(M_PI/180.0); + +class Widget : public QWidget +{ + Q_OBJECT + +public: + explicit Widget(QWidget *parent = 0); + ~Widget(); + +private slots: + void on_btReciveStart_clicked(); + void on_btReciveStop_clicked(); + void on_btTransmitStart_clicked(); + void on_btTransmitStop_clicked(); + + void readDatagram(); + void sendDatagram(); + + void on_autoSend_clicked(); + + void on_autoAnswer_clicked(); + +private: + Ui::Widget *ui; + + QTime screenTimeout; + QUdpSocket *inSocket; + QUdpSocket *outSocket; + QHostAddress outHost; + quint16 outPort; + quint32 packetCounter; + + void processDatagram(const QByteArray &data); + QTimer *autoSendTimer; + + void asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q); + void asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy); + void asQuat2RPY(const QQuaternion &q, QVector3D &rpy); + +/* // not used + * void ccRPY2Quat(const QVector3D &rpy, QQuaternion &q); + * void ccQuat2Matrix(const QQuaternion &q, QMatrix4x4 &m); + */ +}; + +#endif // UDPTESTWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui new file mode 100644 index 000000000..a060a6042 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui @@ -0,0 +1,940 @@ + + + Widget + + + + 0 + 0 + 440 + 525 + + + + udp_test + + + + + + + + + + + + 60 + 0 + + + + Connect + + + + + + + true + + + + 0 + 0 + + + + + 50 + 0 + + + + 40100 + + + 5 + + + + + + + true + + + + 0 + 0 + + + + 127.0.0.1 + + + + + + + sim host + + + + + + + local host: + + + + + + + local port: + + + + + + + false + + + + 60 + 0 + + + + Disconnect + + + + + + + true + + + + 0 + 0 + + + + 127.0.0.1 + + + + + + + sim port + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + 40200 + + + 5 + + + + + + + + 60 + 0 + + + + Transmit + + + + + + + false + + + + 60 + 0 + + + + Stop + + + + + + + + + 0 + + + + raw data + + + + + + + Terminal + 10 + + + + + + + + + channels + + + + 0 + + + 9 + + + + + send data + + + + 6 + + + 9 + + + 0 + + + 3 + + + + + true + + + answer on recieve + + + true + + + + + + + true + + + auto send + + + false + + + + + + + + + + Flight mode + + + + 6 + + + 9 + + + 0 + + + 3 + + + + + 6 + + + 1 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 1 + + + + + + + + + + Armed state + + + + 6 + + + 9 + + + 0 + + + 3 + + + + + Disarmed + + + true + + + + + + + Arming + + + + + + + Armed + + + + + + + + + + Channels + + + + 9 + + + 0 + + + 9 + + + 3 + + + 3 + + + + + CH1 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + CH2 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + CH3 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + CH4 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + CH5 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + CH6 + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + Ch7 + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + Ch8 + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + Ch9 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + Ch10 + + + Qt::AlignCenter + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + 0 + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + -511 + + + 512 + + + 16 + + + 32 + + + Qt::Horizontal + + + QSlider::TicksAbove + + + 128 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro index 58475b05f..132fbe8ee 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro @@ -1,27 +1,5 @@ -TEMPLATE = lib -TARGET = HITLv2 -QT += network -include(../../openpilotgcsplugin.pri) -include(hitlv2_dependencies.pri) -HEADERS += \ - aerosimrc.h \ - hitlv2configuration.h \ - hitlv2factory.h \ - hitlv2gadget.h \ - hitlv2optionspage.h \ - hitlv2plugin.h \ - hitlv2widget.h \ - simulatorv2.h -SOURCES += \ - aerosimrc.cpp \ - hitlv2configuration.cpp \ - hitlv2factory.cpp \ - hitlv2gadget.cpp \ - hitlv2optionspage.cpp \ - hitlv2plugin.cpp \ - hitlv2widget.cpp \ - simulatorv2.cpp -OTHER_FILES += hitlv2.pluginspec -FORMS += \ - hitlv2optionspage.ui \ - hitlv2widget.ui +TEMPLATE = subdirs + +SUBDIRS = plugin aerosimrc + +plugin.file = plugin.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro new file mode 100644 index 000000000..2d375e426 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro @@ -0,0 +1,32 @@ +TEMPLATE = lib +TARGET = HITLv2 +QT += network + +include(../../openpilotgcsplugin.pri) +include(hitlv2_dependencies.pri) + +HEADERS += \ + aerosimrc.h \ + hitlv2configuration.h \ + hitlv2factory.h \ + hitlv2gadget.h \ + hitlv2optionspage.h \ + hitlv2plugin.h \ + hitlv2widget.h \ + simulatorv2.h + +SOURCES += \ + aerosimrc.cpp \ + hitlv2configuration.cpp \ + hitlv2factory.cpp \ + hitlv2gadget.cpp \ + hitlv2optionspage.cpp \ + hitlv2plugin.cpp \ + hitlv2widget.cpp \ + simulatorv2.cpp + +FORMS += \ + hitlv2optionspage.ui \ + hitlv2widget.ui + +OTHER_FILES += hitlv2.pluginspec From fc18749d1a7fdf89f01516bd577dcae046f7eeb6 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 20 Jul 2012 16:48:57 +0300 Subject: [PATCH 010/165] AeroSimRC: resemble the AeroSIM-RC directory in build/ground ... to make easier to copy plugin files into AeroSimRC folder. --- .../plugins/hitlv2/aerosimrc/src/plugin.pro | 49 ++++++++++++++++-- .../{res => src/resources}/cc_off.tga | Bin .../{res => src/resources}/cc_off_hover.tga | Bin .../{res => src/resources}/cc_on.tga | Bin .../{res => src/resources}/cc_on_hover.tga | Bin .../{res => src/resources}/cc_plugin.ini | 0 .../{res => src/resources}/plugin.txt | 0 .../plugins/hitlv2/aerosimrc/src/udptest.pro | 5 +- 8 files changed, 50 insertions(+), 4 deletions(-) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/cc_off.tga (100%) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/cc_off_hover.tga (100%) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/cc_on.tga (100%) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/cc_on_hover.tga (100%) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/cc_plugin.ini (100%) rename ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/{res => src/resources}/plugin.txt (100%) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro index ca149d262..b31d6881b 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -1,9 +1,19 @@ -!win32 { error("AeroSimRC plugin is only available for win32 platform") } +!win32 { + error("AeroSimRC plugin is only available for win32 platform") +} + +include(../../../../../openpilotgcs.pri) QT += network QT -= gui -TARGET = plugin_AeroSIMRC + TEMPLATE = lib +TARGET = plugin_AeroSIMRC + +RES_DIR = $${PWD}/resources +SIM_DIR = $$GCS_BUILD_TREE/../AeroSIM-RC +PLUGIN_DIR = $$SIM_DIR/Plugin/CopterControl +DLLDESTDIR = $$PLUGIN_DIR # Don't depend on MSVRT*.dll win32-msvc* { @@ -25,4 +35,37 @@ SOURCES = \ udpconnect.cpp \ settings.cpp -#DLLDESTDIR = ../CopterControl +# Resemble the AeroSimRC directory structure and copy plugin files and resources +equals(copydata, 1) { + + # Windows release only + win32:CONFIG(release, debug|release) { + + data_copy.commands += -@$(MKDIR) $$targetPath(\"$$PLUGIN_DIR\") $$addNewline() + + # resources and sample configuration + PLUGIN_RESOURCES = \ + cc_off.tga \ + cc_off_hover.tga \ + cc_on.tga \ + cc_on_hover.tga \ + cc_plugin.ini \ + plugin.txt + for(res, PLUGIN_RESOURCES) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$RES_DIR/$$res\") $$targetPath(\"$$PLUGIN_DIR/$$res\") $$addNewline() + } + + # Qt DLLs + QT_DLLS = \ + libgcc_s_dw2-1.dll \ + mingwm10.dll \ + QtCore4.dll \ + QtNetwork4.dll + for(dll, QT_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() + } + + data_copy.target = FORCE + QMAKE_EXTRA_TARGETS += data_copy + } +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off.tga rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off_hover.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off_hover.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_off_hover.tga rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off_hover.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on.tga rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on_hover.tga b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on_hover.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_on_hover.tga rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on_hover.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_plugin.ini similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/cc_plugin.ini rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_plugin.ini diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/plugin.txt similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/res/plugin.txt rename to ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/plugin.txt diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro index ca9b90870..ac63be5ae 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro @@ -1,7 +1,10 @@ +include(../../../../../openpilotgcs.pri) + QT += core gui network -TARGET = udptest TEMPLATE = app +TARGET = udp_test +DESTDIR = $$GCS_APP_PATH HEADERS += \ udptestwidget.h From 8d8a3d0155f9e2e77e1d3bea737b135f01756fc7 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 20 Jul 2012 22:37:36 +0300 Subject: [PATCH 011/165] AeroSimRC: add plugin option to Windows installer Translations are welcome. --- HISTORY.txt | 8 ++++++++ package/winx86/openpilotgcs.nsi | 17 +++++++++++++---- package/winx86/translations/strings_de.nsh | 3 ++- package/winx86/translations/strings_en.nsh | 3 ++- package/winx86/translations/strings_es.nsh | 3 ++- package/winx86/translations/strings_fr.nsh | 3 ++- package/winx86/translations/strings_ru.nsh | 3 ++- package/winx86/translations/strings_zh_CN.nsh | 3 ++- 8 files changed, 33 insertions(+), 10 deletions(-) diff --git a/HISTORY.txt b/HISTORY.txt index d0492dd1f..838f25d05 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,13 @@ Short summary of changes. For a complete list see the git log. +2012-07-20 +AeroSimRC simulator plugin is now included into the Windows distribution +(will be installed into .../OpenPilot/misc/AeroSIM-RC directory). Still +being an experimental development tool, it could be used to play with +HITL version 2. Other platforms include udp_test utility which can be +used to check the connectivity with AeroSimRC plugin running on Windows +machine. + 2012-07-10 On Windows the installation mode was changed from per-user to per-machine (for all users) installation. It is recommended to completely uninstall diff --git a/package/winx86/openpilotgcs.nsi b/package/winx86/openpilotgcs.nsi index 363760ec0..2a032870d 100644 --- a/package/winx86/openpilotgcs.nsi +++ b/package/winx86/openpilotgcs.nsi @@ -38,6 +38,7 @@ !define NSIS_DATA_TREE "." !define GCS_BUILD_TREE "..\..\build\ground\openpilotgcs" !define UAVO_SYNTH_TREE "..\..\build\uavobject-synthetics" + !define AEROSIMRC_TREE "..\..\build\ground\AeroSIM-RC" ; Default installation folder InstallDir "$PROGRAMFILES\OpenPilot" @@ -161,7 +162,7 @@ Section "Core files" InSecCore SectionEnd ; Copy GCS plugins -Section "Plugins" InSecPlugins +Section "-Plugins" InSecPlugins SectionIn RO SetOutPath "$INSTDIR\lib\openpilotgcs\plugins" File /r "${GCS_BUILD_TREE}\lib\openpilotgcs\plugins\*.dll" @@ -169,7 +170,7 @@ Section "Plugins" InSecPlugins SectionEnd ; Copy GCS resources -Section "Resources" InSecResources +Section "-Resources" InSecResources SetOutPath "$INSTDIR\share\openpilotgcs\diagrams" File /r "${GCS_BUILD_TREE}\share\openpilotgcs\diagrams\*" SetOutPath "$INSTDIR\share\openpilotgcs\dials" @@ -183,14 +184,14 @@ Section "Resources" InSecResources SectionEnd ; Copy Notify plugin sound files -Section "Sound files" InSecSounds +Section "-Sound files" InSecSounds SetOutPath "$INSTDIR\share\openpilotgcs\sounds" File /r "${GCS_BUILD_TREE}\share\openpilotgcs\sounds\*" SectionEnd ; Copy localization files ; Disabled until GCS source is stable and properly localized -Section "Localization" InSecLocalization +Section "-Localization" InSecLocalization SetOutPath "$INSTDIR\share\openpilotgcs\translations" ; File /r "${GCS_BUILD_TREE}\share\openpilotgcs\translations\openpilotgcs_*.qm" File /r "${GCS_BUILD_TREE}\share\openpilotgcs\translations\qt_*.qm" @@ -229,6 +230,12 @@ Section "CDC driver" InSecInstallDrivers ExecWait '"$PLUGINSDIR\dpinst.exe" /lm /path "$INSTDIR\drivers"' SectionEnd +; AeroSimRC plugin files +Section "AeroSimRC plugin" InSecAeroSimRC + SetOutPath "$INSTDIR\misc\AeroSIM-RC" + File /r "${AEROSIMRC_TREE}\*" +SectionEnd + Section "Shortcuts" InSecShortcuts ; Create desktop and start menu shortcuts SetOutPath "$INSTDIR" @@ -277,6 +284,7 @@ SectionEnd !insertmacro MUI_DESCRIPTION_TEXT ${InSecUtilities} $(DESC_InSecUtilities) !insertmacro MUI_DESCRIPTION_TEXT ${InSecDrivers} $(DESC_InSecDrivers) !insertmacro MUI_DESCRIPTION_TEXT ${InSecInstallDrivers} $(DESC_InSecInstallDrivers) + !insertmacro MUI_DESCRIPTION_TEXT ${InSecAeroSimRC} $(DESC_InSecAeroSimRC) !insertmacro MUI_DESCRIPTION_TEXT ${InSecShortcuts} $(DESC_InSecShortcuts) !insertmacro MUI_FUNCTION_DESCRIPTION_END @@ -301,6 +309,7 @@ Section "un.OpenPilot GCS" UnSecProgram RMDir /r /rebootok "$INSTDIR\firmware" RMDir /r /rebootok "$INSTDIR\utilities" RMDir /r /rebootok "$INSTDIR\drivers" + RMDir /r /rebootok "$INSTDIR\misc" Delete /rebootok "$INSTDIR\HISTORY.txt" Delete /rebootok "$INSTDIR\Uninstall.exe" diff --git a/package/winx86/translations/strings_de.nsh b/package/winx86/translations/strings_de.nsh index 234a1fe3a..71ee8c489 100644 --- a/package/winx86/translations/strings_de.nsh +++ b/package/winx86/translations/strings_de.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_GERMAN} "OpenPilot firmware binaries." LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot Dienstprogramme (Matlab Log Parser)." LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot Hardware Treiberdateien (optionaler OpenPilot CDC Treiber)." - LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Installiere OpenPilot CDC Treiber (optional)." + LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "OpenPilot CDC Treiber (optional)." + LangString DESC_InSecAeroSimRC ${LANG_GERMAN} "AeroSimRC plugin files with sample configuration." LangString DESC_InSecShortcuts ${LANG_GERMAN} "Installiere Verknüpfungen unter Startmenü->Anwendungen." ;-------------------------------- diff --git a/package/winx86/translations/strings_en.nsh b/package/winx86/translations/strings_en.nsh index 3e640ad4d..e8aa794b0 100644 --- a/package/winx86/translations/strings_en.nsh +++ b/package/winx86/translations/strings_en.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_ENGLISH} "OpenPilot firmware binaries." LangString DESC_InSecUtilities ${LANG_ENGLISH} "OpenPilot utilities (Matlab log parser)." LangString DESC_InSecDrivers ${LANG_ENGLISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_ENGLISH} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecInstallDrivers ${LANG_ENGLISH} "Optional OpenPilot CDC driver (virtual USB COM port)." + LangString DESC_InSecAeroSimRC ${LANG_ENGLISH} "AeroSimRC plugin files with sample configuration." LangString DESC_InSecShortcuts ${LANG_ENGLISH} "Install application start menu shortcuts." ;-------------------------------- diff --git a/package/winx86/translations/strings_es.nsh b/package/winx86/translations/strings_es.nsh index 21aeb31d4..6ac59f0d8 100644 --- a/package/winx86/translations/strings_es.nsh +++ b/package/winx86/translations/strings_es.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_SPANISH} "OpenPilot firmware binaries." LangString DESC_InSecUtilities ${LANG_SPANISH} "OpenPilot utilities (Matlab log parser)." LangString DESC_InSecDrivers ${LANG_SPANISH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_SPANISH} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecInstallDrivers ${LANG_SPANISH} "Optional OpenPilot CDC driver (virtual USB COM port)." + LangString DESC_InSecAeroSimRC ${LANG_SPANISH} "AeroSimRC plugin files with sample configuration." LangString DESC_InSecShortcuts ${LANG_SPANISH} "Instalar accesos directos de la aplicación (menú inicio y escritorio)." ;-------------------------------- diff --git a/package/winx86/translations/strings_fr.nsh b/package/winx86/translations/strings_fr.nsh index 3b1c9efb0..c0919405e 100644 --- a/package/winx86/translations/strings_fr.nsh +++ b/package/winx86/translations/strings_fr.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_FRENCH} "OpenPilot firmware binaries." LangString DESC_InSecUtilities ${LANG_FRENCH} "OpenPilot utilities (Matlab log parser)." LangString DESC_InSecDrivers ${LANG_FRENCH} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_FRENCH} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecInstallDrivers ${LANG_FRENCH} "Optional OpenPilot CDC driver (virtual USB COM port)." + LangString DESC_InSecAeroSimRC ${LANG_FRENCH} "AeroSimRC plugin files with sample configuration." LangString DESC_InSecShortcuts ${LANG_FRENCH} "Installer les raccourcis dans le menu démarrer." ;-------------------------------- diff --git a/package/winx86/translations/strings_ru.nsh b/package/winx86/translations/strings_ru.nsh index f62e708d2..0aa90b31a 100644 --- a/package/winx86/translations/strings_ru.nsh +++ b/package/winx86/translations/strings_ru.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_RUSSIAN} "Файлы прошивок OpenPilot." LangString DESC_InSecUtilities ${LANG_RUSSIAN} "Утилиты (конвертор логов для Matlab)." LangString DESC_InSecDrivers ${LANG_RUSSIAN} "Файлы драйверов (опциональный драйвер CDC порта)." - LangString DESC_InSecInstallDrivers ${LANG_RUSSIAN} "Установка опционального OpenPilot CDC драйвера." + LangString DESC_InSecInstallDrivers ${LANG_RUSSIAN} "Опциональный OpenPilot CDC драйвер (виртуальный USB COM порт)." + LangString DESC_InSecAeroSimRC ${LANG_RUSSIAN} "Файлы плагина для симулятора AeroSimRC с примером конфигурации." LangString DESC_InSecShortcuts ${LANG_RUSSIAN} "Установка ярлыков для приложения." ;-------------------------------- diff --git a/package/winx86/translations/strings_zh_CN.nsh b/package/winx86/translations/strings_zh_CN.nsh index 5eff43762..50d867223 100644 --- a/package/winx86/translations/strings_zh_CN.nsh +++ b/package/winx86/translations/strings_zh_CN.nsh @@ -33,7 +33,8 @@ LangString DESC_InSecFirmware ${LANG_TRADCHINESE} "OpenPilot firmware binaries." LangString DESC_InSecUtilities ${LANG_TRADCHINESE} "OpenPilot utilities (Matlab log parser)." LangString DESC_InSecDrivers ${LANG_TRADCHINESE} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_TRADCHINESE} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecInstallDrivers ${LANG_TRADCHINESE} "Optional OpenPilot CDC driver (virtual USB COM port)." + LangString DESC_InSecAeroSimRC ${LANG_TRADCHINESE} "AeroSimRC plugin files with sample configuration." LangString DESC_InSecShortcuts ${LANG_TRADCHINESE} "安装开始菜单的快捷方式." ;-------------------------------- From c80e5a2bc9b708a504addc3becace724dbb9bbeb Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 20 Jul 2012 23:13:41 +0300 Subject: [PATCH 012/165] AeroSimRC: (bugfix) replace non-standard _copysign() by copysign() --- .../src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp index 9135d5a29..9ab45e45a 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp @@ -414,9 +414,9 @@ void Widget::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q) y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0; z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0; - x = _copysign(x, (m(1, 2) - m(2, 1))); - y = _copysign(y, (m(2, 0) - m(0, 2))); - z = _copysign(z, (m(0, 1) - m(1, 0))); + x = copysign(x, (m(1, 2) - m(2, 1))); + y = copysign(y, (m(2, 0) - m(0, 2))); + z = copysign(z, (m(0, 1) - m(1, 0))); q.setScalar(w); q.setX(x); @@ -443,7 +443,7 @@ void Widget::asQuat2RPY(const QQuaternion &q, QVector3D &rpy) qreal R11 = qss - qxx + qyy - qzz; roll = 0.0; - pitch = _copysign(M_PI_2, test); + pitch = copysign(M_PI_2, test); yaw = qAtan2(-R10, R11); } else { qreal R12 = d2 * (q.y() * q.z() + q.scalar() * q.x()); @@ -469,7 +469,7 @@ void Widget::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy) if (qFabs(m(0, 2)) > 0.998) { // ~86.3, gimbal lock roll = 0.0; - pitch = _copysign(M_PI_2, -m(0, 2)); + pitch = copysign(M_PI_2, -m(0, 2)); yaw = qAtan2(-m(1, 0), m(1, 1)); } else { roll = qAtan2(m(1, 2), m(2, 2)); From c3791532b8fd2a3f0f3646329da8e66dd66a4ee7 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 21 Jul 2012 21:32:59 +0300 Subject: [PATCH 013/165] AeroSimRC: fix spelling in imported sources (thanks Jose) --- .../plugins/hitlv2/aerosimrc/src/plugin.cpp | 4 +-- .../hitlv2/aerosimrc/src/udpconnect.cpp | 30 +++++++++---------- .../plugins/hitlv2/aerosimrc/src/udpconnect.h | 6 ++-- 3 files changed, 20 insertions(+), 20 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp index e2100f608..18ba2c15d 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp @@ -40,7 +40,7 @@ QList videoModes; QTime ledTimer; UdpSender *sndr; -UdpReciever *rcvr; +UdpReceiver *rcvr; const float RAD2DEG = (float)(180.0 / M_PI); const float DEG2RAD = (float)(M_PI / 180.0); @@ -104,7 +104,7 @@ SIM_DLL_EXPORT void AeroSIMRC_Plugin_Init(pluginInit *p) sndr = new UdpSender(ini->getOutputMap(), ini->isFromTX()); sndr->init(ini->remoteHost(), ini->remotePort()); - rcvr = new UdpReciever(ini->getInputMap(), ini->isToRX()); + rcvr = new UdpReceiver(ini->getInputMap(), ini->isToRX()); rcvr->init(ini->localHost(), ini->localPort()); // run thread diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp index 06e77b163..0448a705a 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp @@ -112,12 +112,12 @@ void UdpSender::sendDatagram(const simToPlugin *stp) //----------------------------------------------------------------------------- -UdpReciever::UdpReciever(const QList map, +UdpReceiver::UdpReceiver(const QList map, bool isRX, QObject *parent) : QThread(parent) { - qDebug() << this << "UdpReciever::UdpReciever thread:" << thread(); + qDebug() << this << "UdpReceiver::UdpReceiver thread:" << thread(); stopped = false; inSocket = NULL; @@ -130,17 +130,17 @@ UdpReciever::UdpReciever(const QList map, packetsRecived = 1; } -UdpReciever::~UdpReciever() +UdpReceiver::~UdpReceiver() { - qDebug() << this << "UdpReciever::~UdpReciever"; + qDebug() << this << "UdpReceiver::~UdpReceiver"; if (inSocket) delete inSocket; } // public -void UdpReciever::init(const QString &localHost, quint16 localPort) +void UdpReceiver::init(const QString &localHost, quint16 localPort) { - qDebug() << this << "UdpReciever::init"; + qDebug() << this << "UdpReceiver::init"; inSocket = new QUdpSocket(); qDebug() << this << "inSocket constructed" << inSocket->thread(); @@ -148,21 +148,21 @@ void UdpReciever::init(const QString &localHost, quint16 localPort) inSocket->bind(QHostAddress(localHost), localPort); } -void UdpReciever::run() +void UdpReceiver::run() { - qDebug() << this << "UdpReciever::run start"; + qDebug() << this << "UdpReceiver::run start"; while (!stopped) onReadyRead(); - qDebug() << this << "UdpReciever::run ended"; + qDebug() << this << "UdpReceiver::run ended"; } -void UdpReciever::stop() +void UdpReceiver::stop() { - qDebug() << this << "UdpReciever::stop"; + qDebug() << this << "UdpReceiver::stop"; stopped = true; } -void UdpReciever::setChannels(pluginToSim *pts) +void UdpReceiver::setChannels(pluginToSim *pts) { QMutexLocker locker(&mutex); @@ -183,7 +183,7 @@ void UdpReciever::setChannels(pluginToSim *pts) } } -void UdpReciever::getFlighStatus(quint8 &arm, quint8 &mod) +void UdpReceiver::getFlighStatus(quint8 &arm, quint8 &mod) { QMutexLocker locker(&mutex); @@ -192,7 +192,7 @@ void UdpReciever::getFlighStatus(quint8 &arm, quint8 &mod) } // private -void UdpReciever::onReadyRead() +void UdpReceiver::onReadyRead() { if (!inSocket->waitForReadyRead(8)) // 1/60fps ~= 16.7ms, 1/120fps ~= 8.3ms return; @@ -209,7 +209,7 @@ void UdpReciever::onReadyRead() } } -void UdpReciever::processDatagram(QByteArray &datagram) +void UdpReceiver::processDatagram(QByteArray &datagram) { QDataStream stream(datagram); stream.setFloatingPointPrecision(QDataStream::SinglePrecision); diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h index 82b944e77..ead07f046 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h @@ -57,12 +57,12 @@ private: }; -class UdpReciever : public QThread +class UdpReceiver : public QThread { // Q_OBJECT public: - explicit UdpReciever(const QList map, bool isRX, QObject *parent = 0); - ~UdpReciever(); + explicit UdpReceiver(const QList map, bool isRX, QObject *parent = 0); + ~UdpReceiver(); void init(const QString &localHost, quint16 localPort); void run(); void stop(); From a559286d0b7147a884935ebdb2909250bb2937f5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 01:17:06 -0500 Subject: [PATCH 014/165] A few of the UBX types were missing a struct for the type. --- flight/Modules/GPS/UBX.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/GPS/UBX.c b/flight/Modules/GPS/UBX.c index 536236a6b..92d5e08bf 100644 --- a/flight/Modules/GPS/UBX.c +++ b/flight/Modules/GPS/UBX.c @@ -249,7 +249,7 @@ void parse_ubx_nav_velned (struct UBX_NAV_VELNED *velned, GPSPositionData *GpsPo } #if !defined(PIOS_GPS_MINIMAL) -void parse_ubx_nav_timeutc (UBX_NAV_TIMEUTC *timeutc) +void parse_ubx_nav_timeutc (struct UBX_NAV_TIMEUTC *timeutc) { if (!(timeutc->valid & TIMEUTC_VALIDUTC)) return; @@ -268,7 +268,7 @@ void parse_ubx_nav_timeutc (UBX_NAV_TIMEUTC *timeutc) #endif #if !defined(PIOS_GPS_MINIMAL) -void parse_ubx_nav_svinfo (UBX_NAV_SVINFO *svinfo) +void parse_ubx_nav_svinfo (struct UBX_NAV_SVINFO *svinfo) { uint8_t chan; GPSSatellitesData svdata; From f3f34e8f9f7ca98a7b083c09ceccca0e9e116866 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 22 Jul 2012 14:18:49 +0300 Subject: [PATCH 015/165] AeroSimRC: fix CC3D virtual sensor readings in simulation mode --- flight/Modules/Attitude/attitude.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 02ba45744..baa0c5453 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -375,6 +375,10 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) if(xQueueReceive(queue, (void *) &mpu6000_data, SENSOR_PERIOD) == errQUEUE_EMPTY) return -1; // Error, no data + // Do not read raw sensor data in simulation mode + if (GyrosReadOnly() || AccelsReadOnly()) + return 0; + gyros[0] = -mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); gyros[1] = -mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); gyros[2] = -mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); From 4e42fb564e372a8e60f4b77eaf4dab5ec0deee7a Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 22 Jul 2012 14:18:49 +0300 Subject: [PATCH 016/165] AeroSimRC: fix CC3D virtual sensor readings in simulation mode --- flight/Modules/Attitude/attitude.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 02ba45744..baa0c5453 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -375,6 +375,10 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) if(xQueueReceive(queue, (void *) &mpu6000_data, SENSOR_PERIOD) == errQUEUE_EMPTY) return -1; // Error, no data + // Do not read raw sensor data in simulation mode + if (GyrosReadOnly() || AccelsReadOnly()) + return 0; + gyros[0] = -mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); gyros[1] = -mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); gyros[2] = -mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); From 545018244c5af9b521ecd7e8a83a75a1bb484cff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 23:03:27 -0500 Subject: [PATCH 017/165] Make saving occur within the system thread instead of the event system thread --- flight/Modules/System/systemmod.c | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..7d0118583 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -73,6 +73,7 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; +static xQueueHandle objectPersistenceQueue; static bool stackOverflow; static bool mallocFailed; @@ -124,6 +125,8 @@ int32_t SystemModInitialize(void) SystemModStart(); + objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + return 0; } @@ -133,8 +136,6 @@ MODULE_INITCALL(SystemModInitialize, 0) */ static void systemTask(void *parameters) { - portTickType lastSysTime; - /* create all modules thread */ MODULE_TASKCREATE_ALL; @@ -154,10 +155,9 @@ static void systemTask(void *parameters) // Initialize vars idleCounter = 0; idleCounterClear = 0; - lastSysTime = xTaskGetTickCount(); // Listen for SettingPersistance object updates, connect a callback function - ObjectPersistenceConnectCallback(&objectUpdatedCb); + ObjectPersistenceConnectQueue(objectPersistenceQueue); // Main system loop while (1) { @@ -193,11 +193,14 @@ static void systemTask(void *parameters) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - // Wait until next period - if(flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) ); - } else { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS); + UAVObjEvent ev; + int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ? + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) : + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS; + + if(xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) { + // If object persistence is updated call the callback + objectUpdatedCb(&ev); } } } From e38325c745a1a8e0962e22fdc247c97f75134a31 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 08:47:43 -0500 Subject: [PATCH 018/165] Should check that the queue allocates and initialize shoudl return -1 if not --- flight/Modules/System/systemmod.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 7d0118583..005a0c565 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -126,6 +126,8 @@ int32_t SystemModInitialize(void) SystemModStart(); objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + if (objectPersistenceQueue == NULL) + return -1; return 0; } From 9865466da9ddc556d645cc5a93c17f9463d48f41 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 09:51:03 -0500 Subject: [PATCH 019/165] Make sure to create the system queue BEFORE calling task start. Systemmod initializes differently than other threads and I missed htat. Huge thanks to Hyper for making me realize that despite the fact I didn't see it :D. --- flight/Modules/System/systemmod.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 005a0c565..33bf462fb 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -123,12 +123,12 @@ int32_t SystemModInitialize(void) WatchdogStatusInitialize(); #endif - SystemModStart(); - objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); if (objectPersistenceQueue == NULL) return -1; + SystemModStart(); + return 0; } From 66191c4d0128823c321c8b858cbea97a8c13999d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 23:03:27 -0500 Subject: [PATCH 020/165] Make saving occur within the system thread instead of the event system thread --- flight/Modules/System/systemmod.c | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..7d0118583 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -73,6 +73,7 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; +static xQueueHandle objectPersistenceQueue; static bool stackOverflow; static bool mallocFailed; @@ -124,6 +125,8 @@ int32_t SystemModInitialize(void) SystemModStart(); + objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + return 0; } @@ -133,8 +136,6 @@ MODULE_INITCALL(SystemModInitialize, 0) */ static void systemTask(void *parameters) { - portTickType lastSysTime; - /* create all modules thread */ MODULE_TASKCREATE_ALL; @@ -154,10 +155,9 @@ static void systemTask(void *parameters) // Initialize vars idleCounter = 0; idleCounterClear = 0; - lastSysTime = xTaskGetTickCount(); // Listen for SettingPersistance object updates, connect a callback function - ObjectPersistenceConnectCallback(&objectUpdatedCb); + ObjectPersistenceConnectQueue(objectPersistenceQueue); // Main system loop while (1) { @@ -193,11 +193,14 @@ static void systemTask(void *parameters) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - // Wait until next period - if(flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) ); - } else { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS); + UAVObjEvent ev; + int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ? + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) : + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS; + + if(xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) { + // If object persistence is updated call the callback + objectUpdatedCb(&ev); } } } From c0c5da69aa4262b6f1cdaa09906c32c116d42a1b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 08:47:43 -0500 Subject: [PATCH 021/165] Should check that the queue allocates and initialize shoudl return -1 if not --- flight/Modules/System/systemmod.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 7d0118583..005a0c565 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -126,6 +126,8 @@ int32_t SystemModInitialize(void) SystemModStart(); objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + if (objectPersistenceQueue == NULL) + return -1; return 0; } From f9eb82478bf62e03d72aa75147413266f0501dfd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 09:51:03 -0500 Subject: [PATCH 022/165] Make sure to create the system queue BEFORE calling task start. Systemmod initializes differently than other threads and I missed htat. Huge thanks to Hyper for making me realize that despite the fact I didn't see it :D. --- flight/Modules/System/systemmod.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 005a0c565..33bf462fb 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -123,12 +123,12 @@ int32_t SystemModInitialize(void) WatchdogStatusInitialize(); #endif - SystemModStart(); - objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); if (objectPersistenceQueue == NULL) return -1; + SystemModStart(); + return 0; } From 4003cd70a893c612c517497b2be05e58fb174772 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:55:01 +0100 Subject: [PATCH 023/165] GCS-Made rate Kd roll and pitch link when checkbox is checked. --- .../src/plugins/config/configstabilizationwidget.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 331c39e23..b54bdbc44 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -135,6 +135,14 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) { m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value()); } + else if(widget== m_stabilization->RollRateKd) + { + m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value()); + } + else if(widget== m_stabilization->PitchRateKd) + { + m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value()); + } } if(m_stabilization->checkBox_8->checkState()==Qt::Checked) { From 1955e8b84275f02f48bac6986fc60926995d40de Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:45:58 +0100 Subject: [PATCH 024/165] GCS-Comment out the updated statements on vehicleconfig.cpp TODO check if this brings other problems. REVERT commit if it does --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 94c3111b3..7c9ca86e1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - systemSettings->updated(); + //systemSettings->updated(); //emit ConfigurationChanged(); } @@ -180,7 +180,8 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - mixer->updated(); + // mixer->updated(); + qDebug()<<"updateMixer"; } } } @@ -228,7 +229,7 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - mixer->updated(); + //mixer->updated(); } } } From bf6790f554e8f61b3c0c033950e4ad703f9b44fc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 18:42:20 +0100 Subject: [PATCH 025/165] GCS-Made the changes to vehicleconfig final and reenabled the system settings update call. --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 7c9ca86e1..fe76f1660 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - //systemSettings->updated(); + systemSettings->updated(); //emit ConfigurationChanged(); } @@ -180,8 +180,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - // mixer->updated(); - qDebug()<<"updateMixer"; } } } @@ -229,7 +227,6 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - //mixer->updated(); } } } From 6ba8f3ca9e07c2d417977cdd326c972985377117 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:01:33 -0500 Subject: [PATCH 026/165] Fix from hyper to catch when multiple object requests stack up --- ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index ba65e84e5..d8f98be5c 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -388,6 +388,11 @@ void Telemetry::processObjectQueue() UAVObject::UpdateMode updateMode = UAVObject::GetGcsTelemetryUpdateMode(metadata); if ( ( objInfo.event != EV_UNPACKED ) && ( ( objInfo.event != EV_UPDATED_PERIODIC ) || ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) ) ) { + QMap::iterator itr = transMap.find(objInfo.obj->getObjID()); + if ( itr != transMap.end() ) { + qDebug() << "!!!!!! Making request for an object: " << objInfo.obj->getName() << " for which a request is already in progress!!!!!!"; + return; + } UAVObject::Metadata metadata = objInfo.obj->getMetadata(); ObjectTransactionInfo *transInfo = new ObjectTransactionInfo(this); transInfo->obj = objInfo.obj; From 9d82538a096528463a21874ecb150d7106169529 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:16:13 -0500 Subject: [PATCH 027/165] If we set FirmwareIAPObj to update on change then initial object retrieval will force it to be fetched before emitting the autopilotConnected signal. --- .../src/plugins/uavobjectutil/uavobjectutilmanager.cpp | 8 -------- shared/uavobjectdefinition/firmwareiapobj.xml | 2 +- 2 files changed, 1 insertion(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index a30172fb0..be81befb7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -247,14 +247,6 @@ FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap() if (!firmwareIap) return dummy; - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - firmwareIap->requestUpdate(); - loop.exec(); - return firmwareIap->getData(); } diff --git a/shared/uavobjectdefinition/firmwareiapobj.xml b/shared/uavobjectdefinition/firmwareiapobj.xml index 30b070857..be8431ef5 100644 --- a/shared/uavobjectdefinition/firmwareiapobj.xml +++ b/shared/uavobjectdefinition/firmwareiapobj.xml @@ -10,7 +10,7 @@ - + From f5af60af3ea72e3b599035b30904d528f80d1807 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 17:43:47 -0500 Subject: [PATCH 028/165] Increase the stack size for the system module now the saving occurs within that thread. --- flight/CopterControl/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index e4b70e931..dc3b10026 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -94,7 +94,7 @@ /* Task stack sizes */ #define PIOS_ACTUATOR_STACK_SIZE 1020 #define PIOS_MANUAL_STACK_SIZE 724 -#define PIOS_SYSTEM_STACK_SIZE 460 +#define PIOS_SYSTEM_STACK_SIZE 660 #define PIOS_STABILIZATION_STACK_SIZE 524 #define PIOS_TELEM_STACK_SIZE 500 #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 From fc51680e6c1cc3982263d975c02382d84190a957 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:08:59 +0300 Subject: [PATCH 029/165] Windows packaging: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- ground/openpilotgcs/copydata.pro | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index 7e1d5b1b5..d31730d80 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -9,9 +9,7 @@ equals(copydata, 1) { win32:CONFIG(release, debug|release) { # copy Qt DLLs and phonon4 - QT_DLLS = libgcc_s_dw2-1.dll \ - mingwm10.dll \ - phonon4.dll \ + QT_DLLS = phonon4.dll \ QtCore4.dll \ QtGui4.dll \ QtNetwork4.dll \ @@ -27,6 +25,13 @@ equals(copydata, 1) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() } + # copy MinGW DLLs + MINGW_DLLS = libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + # copy iconengines QT_ICONENGINE_DLLS = qsvgicon4.dll data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() From 08034df50ee0eabcecf645d84c7bda9afe116a85 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:55:51 +0300 Subject: [PATCH 030/165] Windows packaging: update sh.cmd script for QtSDK 1.2.1 --- make/winx86/README.txt | 6 +++--- make/winx86/cmd/sh.cmd | 8 ++------ 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 17477d098..3bc070ee1 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -33,7 +33,7 @@ It is expected that you have the following tools installed into the listed locations (but any other locations are fine as well): - Python in C:\Python27 - - QtSDK in C:\Qt\2010.05 or C:\QtSDK (depending on SDK version) + - QtSDK in C:\QtSDK (depending on SDK version) - CodeSourcery G++ in %ProgramFiles%\CodeSourcery\Sourcery G++ Lite - msysGit in %ProgramFiles%\Git - Unicode NSIS in %ProgramFiles%\NSIS\Unicode @@ -190,8 +190,8 @@ This set of scripts uses the MSYS package included into the msysGit distribution and MinGW make included into the QtSDK package. The sh.cmd, shell_script.reg and this README.txt files were written -by Oleg Semyonov (os-openpilot-org@os-propo.info) for the OpenPilot -project and are licensed under CC-BY-SA terms: +by Oleg Semyonov (os@openpilot.org) for the OpenPilot project and +are licensed under CC-BY-SA terms: http://creativecommons.org/licenses/by-sa/3.0/ diff --git a/make/winx86/cmd/sh.cmd b/make/winx86/cmd/sh.cmd index 480044ab7..d9e74033b 100644 --- a/make/winx86/cmd/sh.cmd +++ b/make/winx86/cmd/sh.cmd @@ -54,12 +54,8 @@ set NOT_FOUND= set PATH_DIRS= call :which MSYSGIT "%ProgramFiles%\Git\bin" git.exe -rem These two lines for qt-sdk-win-opensource-2010.05.exe: -call :which QTMINGW "C:\Qt\2010.05\mingw\bin" mingw32-make.exe -call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe -rem These two lines for Qt_SDK_Win_offline_v1_1_1_en.exe: -rem call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe -rem call :which QTSDK "C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin" qmake.exe +call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe +call :which QTSDK "C:\QtSDK\Desktop\Qt\4.8.1\mingw\bin" qmake.exe call :which CODESOURCERY "%ProgramFiles%\CodeSourcery\Sourcery G++ Lite\bin" cs-make.exe call :which PYTHON "C:\Python27" python.exe call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe From e75a2718f1e90aaaca81f3d490f4a7023469a05a Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:08:59 +0300 Subject: [PATCH 031/165] Windows packaging: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- ground/openpilotgcs/copydata.pro | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index 7e1d5b1b5..d31730d80 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -9,9 +9,7 @@ equals(copydata, 1) { win32:CONFIG(release, debug|release) { # copy Qt DLLs and phonon4 - QT_DLLS = libgcc_s_dw2-1.dll \ - mingwm10.dll \ - phonon4.dll \ + QT_DLLS = phonon4.dll \ QtCore4.dll \ QtGui4.dll \ QtNetwork4.dll \ @@ -27,6 +25,13 @@ equals(copydata, 1) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() } + # copy MinGW DLLs + MINGW_DLLS = libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + # copy iconengines QT_ICONENGINE_DLLS = qsvgicon4.dll data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() From 1273a58d9f1a7f6aa7c08b1d9be8996163add3db Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:55:51 +0300 Subject: [PATCH 032/165] Windows packaging: update sh.cmd script for QtSDK 1.2.1 --- make/winx86/README.txt | 6 +++--- make/winx86/cmd/sh.cmd | 8 ++------ 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 17477d098..3bc070ee1 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -33,7 +33,7 @@ It is expected that you have the following tools installed into the listed locations (but any other locations are fine as well): - Python in C:\Python27 - - QtSDK in C:\Qt\2010.05 or C:\QtSDK (depending on SDK version) + - QtSDK in C:\QtSDK (depending on SDK version) - CodeSourcery G++ in %ProgramFiles%\CodeSourcery\Sourcery G++ Lite - msysGit in %ProgramFiles%\Git - Unicode NSIS in %ProgramFiles%\NSIS\Unicode @@ -190,8 +190,8 @@ This set of scripts uses the MSYS package included into the msysGit distribution and MinGW make included into the QtSDK package. The sh.cmd, shell_script.reg and this README.txt files were written -by Oleg Semyonov (os-openpilot-org@os-propo.info) for the OpenPilot -project and are licensed under CC-BY-SA terms: +by Oleg Semyonov (os@openpilot.org) for the OpenPilot project and +are licensed under CC-BY-SA terms: http://creativecommons.org/licenses/by-sa/3.0/ diff --git a/make/winx86/cmd/sh.cmd b/make/winx86/cmd/sh.cmd index 480044ab7..d9e74033b 100644 --- a/make/winx86/cmd/sh.cmd +++ b/make/winx86/cmd/sh.cmd @@ -54,12 +54,8 @@ set NOT_FOUND= set PATH_DIRS= call :which MSYSGIT "%ProgramFiles%\Git\bin" git.exe -rem These two lines for qt-sdk-win-opensource-2010.05.exe: -call :which QTMINGW "C:\Qt\2010.05\mingw\bin" mingw32-make.exe -call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe -rem These two lines for Qt_SDK_Win_offline_v1_1_1_en.exe: -rem call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe -rem call :which QTSDK "C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin" qmake.exe +call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe +call :which QTSDK "C:\QtSDK\Desktop\Qt\4.8.1\mingw\bin" qmake.exe call :which CODESOURCERY "%ProgramFiles%\CodeSourcery\Sourcery G++ Lite\bin" cs-make.exe call :which PYTHON "C:\Python27" python.exe call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe From dcf68c2359b67eb725c46ae72774d311e114d27b Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 30 Jul 2012 00:03:01 +0300 Subject: [PATCH 033/165] AeroSimRC: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- .../src/plugins/hitlv2/aerosimrc/src/plugin.pro | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro index b31d6881b..071559ef3 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -57,14 +57,20 @@ equals(copydata, 1) { # Qt DLLs QT_DLLS = \ - libgcc_s_dw2-1.dll \ - mingwm10.dll \ QtCore4.dll \ QtNetwork4.dll for(dll, QT_DLLS) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() } + # MinGW DLLs + MINGW_DLLS = \ + libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() + } + data_copy.target = FORCE QMAKE_EXTRA_TARGETS += data_copy } From 51b7e1116049f55182a1fff0721df55a54439a45 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 30 Jul 2012 00:08:43 +0300 Subject: [PATCH 034/165] AeroSimRC: remove unused MSVC options --- .../plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h | 9 --------- .../src/plugins/hitlv2/aerosimrc/src/plugin.pro | 6 ------ .../src/plugins/hitlv2/aerosimrc/src/udptestwidget.h | 3 --- 3 files changed, 18 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h index 4adf7c16e..697695bc2 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h @@ -38,13 +38,7 @@ const quint16 DBG_BUFFER_MAX_SIZE = 4096; #define OBSOLETE_MIT_CHECKBOX (1 << 1) #define OBSOLETE_MIT_SEPARATOR (1 << 7) -#if defined(Q_CC_MSVC) -#define PACK_STRUCT -#define MAX_PATH 260 -#pragma pack (push, r1, 1) -#elif defined(Q_CC_GNU) #define PACK_STRUCT __attribute__((packed)) -#endif struct simToPlugin { @@ -207,9 +201,6 @@ struct pluginInit const char *strOutputFolder; } PACK_STRUCT ; // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90) -#ifdef Q_CC_MSVC -#pragma pack (pop, r1) -#endif #undef PACK_STRUCT #endif // AEROSIMRCDATASTRUCT_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro index 071559ef3..51bb42abd 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -15,12 +15,6 @@ SIM_DIR = $$GCS_BUILD_TREE/../AeroSIM-RC PLUGIN_DIR = $$SIM_DIR/Plugin/CopterControl DLLDESTDIR = $$PLUGIN_DIR -# Don't depend on MSVRT*.dll -win32-msvc* { - QMAKE_CXXFLAGS_RELEASE -= -MD - QMAKE_CXXFLAGS_MT_DLL += -MT -} - HEADERS = \ aerosimrcdatastruct.h \ enums.h \ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h index eeca63555..500f35482 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h @@ -31,9 +31,6 @@ #include #include #include -#if defined(Q_CC_MSVC) -#define _USE_MATH_DEFINES -#endif #include #include #include From b8450d4a073756da5784193776c9fb6ee9475468 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 31 Jul 2012 00:18:10 +0200 Subject: [PATCH 035/165] Fixed World Magnetic Model to accept altitude in meters instead of kilometers --- flight/Libraries/WorldMagModel.c | 2 +- ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Libraries/WorldMagModel.c b/flight/Libraries/WorldMagModel.c index cae0ec106..83f413200 100644 --- a/flight/Libraries/WorldMagModel.c +++ b/flight/Libraries/WorldMagModel.c @@ -242,7 +242,7 @@ int WMM_GetMagVector(float Lat, float Lon, float AltEllipsoid, uint16_t Month, u { CoordGeodetic->lambda = Lon; CoordGeodetic->phi = Lat; - CoordGeodetic->HeightAboveEllipsoid = AltEllipsoid; + CoordGeodetic->HeightAboveEllipsoid = AltEllipsoid/1000.0; // convert to km // Convert from geodeitic to Spherical Equations: 17-18, WMM Technical report if (WMM_GeodeticToSpherical(CoordGeodetic, CoordSpherical) < 0) diff --git a/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp b/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp index ce8201ece..207d4b051 100644 --- a/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp +++ b/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp @@ -158,7 +158,7 @@ namespace Utils { { double Lat = LLA[0]; double Lon = LLA[1]; - double AltEllipsoid = LLA[2]; + double AltEllipsoid = LLA[2]/1000.0; // convert to km // *********** // range check supplied params From e32152386a7dfd242f39cebf603eb36c361ddd2d Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 31 Jul 2012 11:10:23 +0200 Subject: [PATCH 036/165] Increased stack for PIOS_SETS_HOMELOCATION case to avoid running into low stack warnings when settings the home location from GPS was actually used. --- flight/Modules/GPS/GPS.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 5851ac10d..0428cb629 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -66,7 +66,7 @@ static float GravityAccel(float latitude, float longitude, float altitude); #ifdef PIOS_GPS_SETS_HOMELOCATION // Unfortunately need a good size stack for the WMM calculation - #define STACK_SIZE_BYTES 750 + #define STACK_SIZE_BYTES 784 #else #if defined(PIOS_GPS_MINIMAL) #define STACK_SIZE_BYTES 500 From 4d257860c8ccd358b9c773f5780f8007121bdd48 Mon Sep 17 00:00:00 2001 From: Ryan Hunter Date: Wed, 18 Jul 2012 17:08:22 -0400 Subject: [PATCH 037/165] Moved the matlab files to matlab folder for GCS plugin --- .../plugins/gcscontrol/Matlab => matlab/GCSPlugin}/GCSControl.m | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {ground/openpilotgcs/src/plugins/gcscontrol/Matlab => matlab/GCSPlugin}/GCSControl.m (100%) diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/Matlab/GCSControl.m b/matlab/GCSPlugin/GCSControl.m similarity index 100% rename from ground/openpilotgcs/src/plugins/gcscontrol/Matlab/GCSControl.m rename to matlab/GCSPlugin/GCSControl.m From dafc455bfacda41f67f69912b6340ea8f1ae419a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 09:36:59 -0500 Subject: [PATCH 038/165] Increase the manualcontrol stack size based on Stac's comments --- flight/CopterControl/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index dc3b10026..371276211 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -93,7 +93,7 @@ /* Task stack sizes */ #define PIOS_ACTUATOR_STACK_SIZE 1020 -#define PIOS_MANUAL_STACK_SIZE 724 +#define PIOS_MANUAL_STACK_SIZE 800 #define PIOS_SYSTEM_STACK_SIZE 660 #define PIOS_STABILIZATION_STACK_SIZE 524 #define PIOS_TELEM_STACK_SIZE 500 From 9d707cef5bee63e7a3f484551b5fb2b50294622c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 24 Feb 2011 03:35:19 -0600 Subject: [PATCH 039/165] Initial import of my androidgcs framework --- androidgcs/AndroidManifest.xml | 18 + androidgcs/bin/OpieMobi.apk | Bin 0 -> 148198 bytes androidgcs/bin/classes.dex | Bin 0 -> 12640 bytes .../ObjBrowserExpandableListAdapter.class | Bin 0 -> 3092 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 0 -> 951 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 0 -> 358 bytes .../org/openpilot/androidgcs/R$color.class | Bin 0 -> 447 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 0 -> 418 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 0 -> 403 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 0 -> 449 bytes .../org/openpilot/androidgcs/R$string.class | Bin 0 -> 445 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 0 -> 627 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 0 -> 1127 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 0 -> 1440 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 0 -> 1199 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 0 -> 1333 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 0 -> 2255 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 0 -> 5422 bytes androidgcs/bin/resources.ap_ | Bin 0 -> 140460 bytes androidgcs/default.properties | 11 + .../gen/org/openpilot/androidgcs/R.java | 31 ++ androidgcs/proguard.cfg | 36 ++ androidgcs/res/drawable-hdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/layout/main.xml | 12 + androidgcs/res/layout/objectbrowser.xml | 8 + androidgcs/res/values/strings.xml | 7 + .../ObjBrowserExpandableListAdapter.java | 99 ++++++ .../openpilot/androidgcs/ObjectBrowser.java | 21 ++ .../org/openpilot/uavtalk/UAVDataObject.java | 27 ++ .../org/openpilot/uavtalk/UAVMetaObject.java | 50 +++ .../src/org/openpilot/uavtalk/UAVObject.java | 117 ++++++ .../openpilot/uavtalk/UAVObjectManager.java | 332 ++++++++++++++++++ 34 files changed, 769 insertions(+) create mode 100644 androidgcs/AndroidManifest.xml create mode 100644 androidgcs/bin/OpieMobi.apk create mode 100644 androidgcs/bin/classes.dex create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class create mode 100644 androidgcs/bin/resources.ap_ create mode 100644 androidgcs/default.properties create mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java create mode 100644 androidgcs/proguard.cfg create mode 100644 androidgcs/res/drawable-hdpi/icon.png create mode 100644 androidgcs/res/drawable-ldpi/icon.png create mode 100644 androidgcs/res/drawable-mdpi/icon.png create mode 100644 androidgcs/res/layout/main.xml create mode 100644 androidgcs/res/layout/objectbrowser.xml create mode 100644 androidgcs/res/values/strings.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml new file mode 100644 index 000000000..83d19e96c --- /dev/null +++ b/androidgcs/AndroidManifest.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk new file mode 100644 index 0000000000000000000000000000000000000000..87a15c5e83805a3bb48265a78f9bd9154813cd35 GIT binary patch literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h