From 954588cc369ad389028f929a3bed792bdf9b4430 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 28 Feb 2021 23:16:03 +0100 Subject: [PATCH 01/47] Started modifying pigpiodhandler class to switch over to libgpiod. Not finished yet...code will not compile. --- source/daemon/CMakeLists.txt | 1 + source/daemon/include/pigpiodhandler.h | 26 +++- source/daemon/src/pigpiodhandler.cpp | 190 ++++++++++++++++++++----- 3 files changed, 179 insertions(+), 38 deletions(-) diff --git a/source/daemon/CMakeLists.txt b/source/daemon/CMakeLists.txt index c1f9dad0..e46c39a3 100644 --- a/source/daemon/CMakeLists.txt +++ b/source/daemon/CMakeLists.txt @@ -42,6 +42,7 @@ find_library(PAHO_MQTTPP3 paho-mqttpp3 REQUIRED) find_library(CRYPTOPP crypto++ REQUIRED) find_library(CONFIGPP config++ REQUIRED) find_library(PIGPIOD_IF2 pigpiod_if2 REQUIRED) +find_library(LIBGPIOD gpiod REQUIRED) find_library(RT rt REQUIRED) endif() diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index e46c5c72..b8c4c0bd 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -10,6 +10,11 @@ #include #include +extern "C" { +//#include +#include +} + #define XOR_RATE 0 #define AND_RATE 1 #define COMBINED_RATE 2 @@ -20,8 +25,15 @@ class PigpiodHandler : public QObject { Q_OBJECT public: - explicit PigpiodHandler(QVector gpioPins = DEFAULT_VECTOR, unsigned int spi_freq = 61035, - uint32_t spi_flags = 0, QObject *parent = nullptr); + enum class PinBias : std::uint8_t { + OpenDrain = 0x01, + OpenSource = 0x02, + ActiveLow = 0x04, + PullDown = 0x10, + PullUp = 0x20 + }; + + explicit PigpiodHandler(std::vector gpioPins = {}, QObject *parent = nullptr); // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; @@ -47,8 +59,10 @@ class PigpiodHandler : public QObject public slots: void stop(); bool initialised(); - void setInput(unsigned int gpio); - void setOutput(unsigned int gpio); + bool setInput(unsigned int gpio); + bool setOutput(unsigned int gpio, bool initState = false); + void setPinBias(unsigned int gpio, ); + void setPullUp(unsigned int gpio); void setPullDown(unsigned int gpio); void setGpioState(unsigned int gpio, bool state); @@ -81,6 +95,10 @@ public slots: void measureGpioClockTime(); bool inhibit=false; int verbose=0; + std::shared_ptr fChip { nullptr }; + std::shared_ptr fInterruptInputLines { nullptr }; + std::map> fLineMap; + // QVector gpioPins; }; diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index faff50f2..359d0035 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -8,15 +8,21 @@ #include #include #include +#include + +/* extern "C" { -#include +//#include +#include } +*/ static int pi = -1; static int spiHandle = -1; static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed +constexpr char CONSUMER[] = "muonpi-daemon"; template inline static T sqr(T x) { return x*x; } @@ -196,59 +202,175 @@ static void cbFunction(int user_pi, unsigned int user_gpio, } } -PigpiodHandler::PigpiodHandler(QVector gpioPins, unsigned int spi_freq, uint32_t spi_flags, QObject *parent) +PigpiodHandler::PigpiodHandler(std::vector gpioPins,QObject *parent) : QObject(parent) { startOfProgram = QDateTime::currentDateTimeUtc(); lastSamplingTime = startOfProgram; elapsedEventTimer.start(); pigHandlerAddress = this; - spiClkFreq = spi_freq; + + spiClkFreq = spi_freq; spiFlags = spi_flags; - pi = pigpio_start((char*)"127.0.0.1", (char*)"8888"); - if (pi < 0) { - //qDebug() << "could not start pigpio. Is pigpiod running?"; - //qDebug() << "you can start pigpiod with: sudo pigpiod -s 1"; - qFatal("Could not connect to pigpio daemon. Is pigpiod running? Start with sudo pigpiod -s 1"); - return; - } - + + char *chipname = "gpiochip0"; + struct gpiod_line *line; + + //chip = gpiod_chip_open_by_name(chipname); + fChip.reset( gpiod_chip_open_by_name(chipname) ); + if (fChip == nullptr) { + qFatal("Open chip failed"); + throw std::exception(); + } + isInitialised = true; -// gpioPins=gpio_pins; - for (auto& gpioPin : gpioPins) { - //if (GPIO_SIGNAL_MAP[gpioPin].direction!=DIR_IN) continue; - set_mode(pi, gpioPin, PI_INPUT); -// if (gpioPin==ADC_READY) set_pull_up_down(pi, GPIO_PINMAP[gpioPin], PI_PUD_UP); - - //qDebug() << "set callback for pin " << gpio_pin; - int result=callback(pi, gpioPin, RISING_EDGE, cbFunction); - if (result<0) { - qCritical()<<"error registering gpio callback for BCM pin"< line ( gpiod_chip_get_line(fChip, gpioPin) ); + if ( line == nullptr ) { + qCritical()<<"error allocating gpio line"<second, CONSUMER ); + if ( ret < 0 ) { + qCritical()<<"Request gpio line" << gpio << "as input failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); + if ( line == nullptr ) { + qCritical()<<"error allocating gpio line"<second, CONSUMER, static_cast(initState) ); + if ( ret < 0 ) { + qCritical()<<"Request gpio line" << gpio << "as output failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); + if ( line == nullptr ) { + qCritical()<<"error allocating gpio line"<(initState) ); + if ( ret < 0 ) { + qCritical()<<"Request gpio line" << gpio << "as output failed"; + return false; + } + fLineMap.emplace( { gpio, line } ); + return true; } -void PigpiodHandler::setPullUp(unsigned int gpio) { - if (isInitialised) set_pull_up_down(pi, gpio, PI_PUD_UP); +void PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { +// if (isInitialised) set_pull_up_down(pi, gpio, PI_PUD_UP); + if (!isInitialised) return; + int flags = 0; + if ( pin_bias & PinBias::OpenDrain ) { + flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_DRAIN; + } else if ( pin_bias & PinBias::OpenSource ) { + flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_SOURCE; + } else if ( pin_bias & PinBias::ActiveLow ) { + flags |= GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; + } else if ( pin_bias & PinBias::PullDown ) { + flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN; + } else if ( pin_bias & PinBias::PullUp ) { + flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP; + } else if ( !(pin_bias & PinBias::PullDown) && !(pin_bias & PinBias::PullUp) ) { + flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; + } + + auto it = fLineMap.find(gpio); + if (it != fLineMap.end()) { + // line object exists, set config + int ret = gpiod_line_set_config( + it->second, GPIOD_LINE_REQUEST_DIRECTION_AS_IS, + flags, 0 ); + if ( ret < 0 ) { + qCritical()<<"Set bias config for gpio line" << gpio << "failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); + if ( line == nullptr ) { + qCritical()<<"error allocating gpio line"< Date: Tue, 9 Mar 2021 01:04:11 +0100 Subject: [PATCH 02/47] Implemented pure usage of libgpiod in PigpiodHandler class. Signals from the former callback function are not yet forwarded, but the core mechanism of event detection works. Pins may be registered/unregistered during runtime and set/get gpio functions also seem to work. Note, that the executing user must be member of gpio group. --- source/daemon/CMakeLists.txt | 7 +- source/daemon/include/daemon.h | 4 +- source/daemon/include/pigpiodhandler.h | 73 ++-- source/daemon/src/daemon.cpp | 41 ++- source/daemon/src/pigpiodhandler.cpp | 469 +++++++++++++++---------- 5 files changed, 361 insertions(+), 233 deletions(-) diff --git a/source/daemon/CMakeLists.txt b/source/daemon/CMakeLists.txt index e46c39a3..163d8e55 100644 --- a/source/daemon/CMakeLists.txt +++ b/source/daemon/CMakeLists.txt @@ -41,8 +41,8 @@ find_library(PAHO_MQTTPP3 paho-mqttpp3 REQUIRED) find_library(CRYPTOPP crypto++ REQUIRED) find_library(CONFIGPP config++ REQUIRED) -find_library(PIGPIOD_IF2 pigpiod_if2 REQUIRED) find_library(LIBGPIOD gpiod REQUIRED) +#find_library(PIGPIOD_IF2 pigpiod_if2 REQUIRED) find_library(RT rt REQUIRED) endif() @@ -186,11 +186,12 @@ target_link_directories(muondetector-daemon PUBLIC "${CMAKE_CURRENT_BINARY_DIR}/ target_link_libraries(muondetector-daemon Qt5::Network Qt5::SerialPort crypto++ - pigpiod_if2 + gpiod +# pigpiod_if2 rt config++ paho-mqtt3c paho-mqtt3a paho-mqtt3cs paho-mqtt3as paho-mqttpp3 - muondetector + muondetector pthread ) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index fc7eb58b..a33356aa 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -204,11 +204,11 @@ public slots: void UBXSetMinMaxSVs(uint8_t minSVs, uint8_t maxSVs); void UBXSetMinCNO(uint8_t minCNO); void GpioSetInput(unsigned int gpio); - void GpioSetOutput(unsigned int gpio); + void GpioSetOutput(unsigned int gpio, bool initState = false); void GpioSetPullUp(unsigned int gpio); void GpioSetPullDown(unsigned int gpio); void GpioSetState(unsigned int gpio, bool state); - void GpioRegisterForCallback(unsigned int gpio, bool edge); // false=falling, true=rising + void GpioRegisterForCallback(unsigned int gpio, PigpiodHandler::EventEdge edge); // false=falling, true=rising void UBXSetCfgTP5(const UbxTimePulseStruct& tp); void UBXSetAopCfg(bool enable=true, uint16_t maxOrbErr=0); void UBXSaveCfg(uint8_t devMask=QtSerialUblox::DEV_BBR | QtSerialUblox::DEV_FLASH); diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index b8c4c0bd..8aacd6cd 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -7,13 +7,18 @@ #include #include +#include +#include +#include #include #include -extern "C" { +//extern "C" { //#include #include -} +//} + +//#include #define XOR_RATE 0 #define AND_RATE 1 @@ -25,16 +30,22 @@ class PigpiodHandler : public QObject { Q_OBJECT public: - enum class PinBias : std::uint8_t { - OpenDrain = 0x01, - OpenSource = 0x02, + enum PinBias : std::uint8_t { + BiasDisabled = 0x00, + PullDown = 0x01, + PullUp = 0x02, ActiveLow = 0x04, - PullDown = 0x10, - PullUp = 0x20 + OpenDrain = 0x08, + OpenSource = 0x10 + }; + enum class EventEdge { + RisingEdge, FallingEdge, BothEdges }; - explicit PigpiodHandler(std::vector gpioPins = {}, QObject *parent = nullptr); - // can't make it private because of access of PigpiodHandler with global pointer + explicit PigpiodHandler(std::vector gpioPins, QObject *parent = nullptr); + ~PigpiodHandler(); + + // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; GPIO_PIN samplingTriggerSignal=EVT_XOR; @@ -53,25 +64,17 @@ class PigpiodHandler : public QObject void eventInterval(quint64 nsecs); void timePulseDiff(qint32 usecs); - // spi related signals - void spiData(uint8_t reg, std::string data); - public slots: void stop(); bool initialised(); - bool setInput(unsigned int gpio); - bool setOutput(unsigned int gpio, bool initState = false); - void setPinBias(unsigned int gpio, ); - - void setPullUp(unsigned int gpio); - void setPullDown(unsigned int gpio); - void setGpioState(unsigned int gpio, bool state); + bool setPinInput(unsigned int gpio); + bool setPinOutput(unsigned int gpio, bool initState); + + bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); + bool setPinState(unsigned int gpio, bool state); void setSamplingTriggerSignal(GPIO_PIN signalName) { samplingTriggerSignal=signalName; } - void registerForCallback(unsigned int gpio, bool edge); // false=falling, true=rising - - // spi related slots - void writeSpi(uint8_t command, std::string data); - void readSpi(uint8_t command, unsigned int bytesToRead); + bool registerInterrupt(unsigned int gpio, EventEdge edge); + bool unRegisterInterrupt(unsigned int gpio); private: bool isInitialised = false; @@ -93,12 +96,26 @@ public slots: QTimer gpioClockTimeMeasurementTimer; void measureGpioClockTime(); + void reloadInterruptSettings(); + void threadLoop(); + bool inhibit=false; int verbose=0; - std::shared_ptr fChip { nullptr }; - std::shared_ptr fInterruptInputLines { nullptr }; - std::map> fLineMap; - + gpiod_chip* fChip { nullptr }; +// std::shared_ptr fChip { nullptr }; + std::map fInterruptLineMap { }; +// std::map> fInterruptLineMap { }; + gpiod_line_bulk fInterruptLineBulk; + std::map fLineMap { }; +// std::map> fLineMap { }; + bool fThreadRunning { false }; + std::unique_ptr fThread { nullptr }; + std::mutex fMutex; +/* + gpiod::chip fChip; + gpiod::line_bulk fInterruptLineBulk; + std::map fLineMap; +*/ // QVector gpioPins; }; diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index ff7ea5ff..1629db6c 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -679,19 +679,24 @@ Daemon::~Daemon() { } void Daemon::connectToPigpiod(){ - const QVector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], +/* + const QVector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], + GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); +*/ + const std::vector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); pigHandler = new PigpiodHandler(gpio_pins); - tdc7200 = new TDC7200(GPIO_PINMAP[TDC_INTB]); + //tdc7200 = new TDC7200(GPIO_PINMAP[TDC_INTB]); pigThread = new QThread(); pigThread->setObjectName("muondetector-daemon-pigpio"); pigHandler->moveToThread(pigThread); - tdc7200->moveToThread(pigThread); + //tdc7200->moveToThread(pigThread); connect(this, &Daemon::aboutToQuit, pigThread, &QThread::quit); connect(pigThread, &QThread::finished, pigThread, &QThread::deleteLater); //pighandler <-> tdc - connect(pigHandler, &PigpiodHandler::spiData, tdc7200, &TDC7200::onDataReceived); +/* + connect(pigHandler, &PigpiodHandler::spiData, tdc7200, &TDC7200::onDataReceived); connect(pigHandler, &PigpiodHandler::signal, tdc7200, &TDC7200::onDataAvailable); connect(tdc7200, &TDC7200::readData, pigHandler, &PigpiodHandler::readSpi); connect(tdc7200, &TDC7200::writeData, pigHandler, &PigpiodHandler::writeSpi); @@ -709,16 +714,16 @@ void Daemon::connectToPigpiod(){ }); connect(pigThread, &QThread::started, tdc7200, &TDC7200::initialise); connect(pigThread, &QThread::finished, tdc7200, &TDC7200::deleteLater); - +*/ //pigHandler <-> thread & daemon connect(this, &Daemon::aboutToQuit, pigHandler, &PigpiodHandler::stop); connect(pigThread, &QThread::finished, pigHandler, &PigpiodHandler::deleteLater); - connect(this, &Daemon::GpioSetOutput, pigHandler, &PigpiodHandler::setOutput); - connect(this, &Daemon::GpioSetInput, pigHandler, &PigpiodHandler::setInput); - connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); - connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); - connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setGpioState); - connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerForCallback); + connect(this, &Daemon::GpioSetOutput, pigHandler, &PigpiodHandler::setPinOutput); + connect(this, &Daemon::GpioSetInput, pigHandler, &PigpiodHandler::setPinInput); +/// connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); +/// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); + connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); + connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::sendGpioPinEvent); connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) @@ -790,16 +795,16 @@ void Daemon::connectToPigpiod(){ emit GpioSetState(GPIO_PINMAP[STATUS1], 0); emit GpioSetState(GPIO_PINMAP[STATUS2], 0); emit GpioSetPullUp(GPIO_PINMAP[ADC_READY]); - emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], 1); + emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], PigpiodHandler::EventEdge::RisingEdge); if (HW_VERSION>1) { - emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); - emit GpioRegisterForCallback(GPIO_PINMAP[PREAMP_FAULT], 0); + //emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); + emit GpioRegisterForCallback(GPIO_PINMAP[PREAMP_FAULT], PigpiodHandler::EventEdge::FallingEdge); emit GpioSetPullUp(GPIO_PINMAP[PREAMP_FAULT]); - emit GpioSetInput(GPIO_PINMAP[TDC_INTB]); - emit GpioRegisterForCallback(GPIO_PINMAP[TDC_INTB], 0); - emit GpioSetInput(GPIO_PINMAP[TIME_MEAS_OUT]); - emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], 0); + //emit GpioSetInput(GPIO_PINMAP[TDC_INTB]); + emit GpioRegisterForCallback(GPIO_PINMAP[TDC_INTB], PigpiodHandler::EventEdge::FallingEdge); + //emit GpioSetInput(GPIO_PINMAP[TIME_MEAS_OUT]); + emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], PigpiodHandler::EventEdge::FallingEdge); } if (HW_VERSION>=3) { emit GpioSetOutput(GPIO_PINMAP[IN_POL1]); diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 359d0035..5ba427cd 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -23,6 +23,7 @@ static int spiHandle = -1; static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed constexpr char CONSUMER[] = "muonpi-daemon"; +constexpr std::chrono::milliseconds loop_delay { 10 }; template inline static T sqr(T x) { return x*x; } @@ -97,7 +98,7 @@ static void cbFunction(int user_pi, unsigned int user_gpio, unsigned int level, uint32_t tick) { //qDebug() << "callback user_pi: " << user_pi << " user_gpio: " << user_gpio << " level: "<< level << " pigHandlerAddressNull: " << pigHandlerAddress.isNull() ; if (pigHandlerAddress.isNull()) { - pigpio_stop(pi); + //pigpio_stop(pi); return; } if (pi != user_pi) { @@ -196,13 +197,13 @@ static void cbFunction(int user_pi, unsigned int user_gpio, catch (std::exception& e) { pigpioHandler = 0; - pigpio_stop(pi); + //pigpio_stop(pi); qCritical() << "Exception catched in 'static void cbFunction(int user_pi, unsigned int user_gpio, unsigned int level, uint32_t tick)':" << e.what(); qCritical() << "with user_pi="< gpioPins,QObject *parent) +PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *parent) : QObject(parent) { startOfProgram = QDateTime::currentDateTimeUtc(); @@ -210,69 +211,117 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins,QObject *paren elapsedEventTimer.start(); pigHandlerAddress = this; - spiClkFreq = spi_freq; - spiFlags = spi_flags; - - char *chipname = "gpiochip0"; - struct gpiod_line *line; + std::string chipname { "/dev/gpiochip0" }; - //chip = gpiod_chip_open_by_name(chipname); - fChip.reset( gpiod_chip_open_by_name(chipname) ); - if (fChip == nullptr) { - qFatal("Open chip failed"); + fChip = gpiod_chip_open(chipname.c_str()); + if ( fChip == nullptr ) { + qCritical()<<"error opening gpio chip "<(nrInterruptPins); + //std::copy( gpioPins.cbegin(), gpioPins.cend(), _interrupt_pins ); + + for (unsigned int gpioPin : gpioPins) { +// std::shared_ptr line ( gpiod_chip_get_line(fChip, gpioPin) ); + gpiod_line* line = gpiod_chip_get_line(fChip, gpioPin); + int flags = 0; + /* + GPIOD_LINE_REQUEST_FLAG_OPEN_DRAIN | + GPIOD_LINE_REQUEST_FLAG_OPEN_SOURCE | + GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; + */ +// int ret = gpiod_line_request_both_edges_events_flags( line, CONSUMER, flags); + int ret = gpiod_line_request_rising_edge_events_flags( line, CONSUMER, flags); + if ( ret < 0 ) { + qCritical()<<"Request for registering gpio line"< line ( gpiod_chip_get_line(fChip, gpioPin) ); - if ( line == nullptr ) { - qCritical()<<"error allocating gpio line"<join(); + for ( auto [gpio,line] : fInterruptLineMap ) { + gpiod_line_release(line); + } + for ( auto [gpio,line] : fLineMap ) { + gpiod_line_release(line); + } + if ( fChip != nullptr ) gpiod_chip_close( fChip ); +} + + +void PigpiodHandler::threadLoop() { + while (fThreadRunning) { + const struct timespec timeout { 0, 100000000UL }; + gpiod_line_bulk event_bulk { }; + int ret = gpiod_line_event_wait_bulk(&fInterruptLineBulk, &timeout, &event_bulk); + if ( ret>0 ) { + unsigned int line_index = 0; + while ( line_index < event_bulk.num_lines ) { + gpiod_line_event event { }; + int ret = gpiod_line_event_read( event_bulk.lines[line_index], &event); + if ( ret == 0 ) { + unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); + std::uint64_t ns = event.ts.tv_sec*1e9 + event.ts.tv_nsec; + qInfo()<<"line event: gpio"<second, CONSUMER, static_cast(initState) ); @@ -312,7 +362,8 @@ bool PigpiodHandler::setOutput(unsigned int gpio, bool initState) { return true; } // line was not allocated yet, so do it now - std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); +// std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); if ( line == nullptr ) { qCritical()<<"error allocating gpio line"<(initState) ); +// fLineMap.emplace( { gpio, line } ); + fLineMap.emplace( std::make_pair( gpio, line ) ); + return true; + } + gpiod::line line( it->second ); + if ( !line.is_requested() ) { + line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(initState) ); + return true; + } + if ( line.direction() == gpiod::line_request::DIRECTION_OUTPUT ) { + qDebug()<<"gpio line" << gpio << "already configured as output"; + return true; + } +// line.set_direction_output( initState ); + // line is not an input, so release it and re-request it as input + line.release(); + line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(initState) ); return true; +*/ + + // if (isInitialised) set_mode(pi, gpio, PI_OUTPUT); } -void PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { -// if (isInitialised) set_pull_up_down(pi, gpio, PI_PUD_UP); - if (!isInitialised) return; +bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { + if (!isInitialised) return false; int flags = 0; if ( pin_bias & PinBias::OpenDrain ) { flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_DRAIN; @@ -337,172 +420,193 @@ void PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { } else if ( pin_bias & PinBias::ActiveLow ) { flags |= GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; } else if ( pin_bias & PinBias::PullDown ) { - flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN; + //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN; } else if ( pin_bias & PinBias::PullUp ) { - flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP; + //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP; } else if ( !(pin_bias & PinBias::PullDown) && !(pin_bias & PinBias::PullUp) ) { - flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; + //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; } auto it = fLineMap.find(gpio); + int dir = -1; if (it != fLineMap.end()) { // line object exists, set config + /* int ret = gpiod_line_set_config( - it->second, GPIOD_LINE_REQUEST_DIRECTION_AS_IS, + it->second.get(), GPIOD_LINE_REQUEST_DIRECTION_AS_IS, flags, 0 ); - if ( ret < 0 ) { - qCritical()<<"Set bias config for gpio line" << gpio << "failed"; - return false; - } - return true; + */ + dir = gpiod_line_direction(it->second); + gpiod_line_release(it->second); } // line was not allocated yet, so do it now - std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); +// std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); if ( line == nullptr ) { qCritical()<<"error allocating gpio line"<second, static_cast(state) ); + if ( ret < 0 ) { + qCritical()<<"Setting state of gpio line" << gpio << "failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + return setPinOutput( gpio, state ); + +/* if (!isInitialised) return false; + auto it = fLineMap.find(gpio); + if (it == fLineMap.end()) { + // line was not allocated yet, so do it now + gpiod::line line( fChip.get_line(gpio) ); + if (line.is_used()) { + qCritical()<<"gpio line" << gpio << "already allocated by another process"; + return false; + } + line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(state) ); +// fLineMap.emplace( { gpio, line } ); + fLineMap.emplace( std::make_pair( gpio, line ) ); + return true; + } + gpiod::line line( it->second ); + if ( !line.is_requested() ) { + line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(state) ); + return true; + } +// line.set_direction_output( initState ); + // line is not an input, so release it and re-request it as input + line.set_value( static_cast(state) ); + return true; +*/ +} + +void PigpiodHandler::reloadInterruptSettings() +{ + if (fThread != nullptr) { + fThreadRunning = false; + fThread->join(); + } + gpiod_line_bulk_init( &fInterruptLineBulk ); + // rerequest bulk events + for (auto [gpio,line] : fInterruptLineMap) { + gpiod_line_bulk_add( &fInterruptLineBulk, line ); + } + fThreadRunning = true; + fThread.reset(new std::thread( [this](){ this->threadLoop(); } ) ); } -void PigpiodHandler::registerForCallback(unsigned int gpio, bool edge) { - int result=callback(pi, gpio, edge?FALLING_EDGE:RISING_EDGE, cbFunction); +bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { + +/* + int result=callback(pi, gpio, edge?FALLING_EDGE:RISING_EDGE, cbFunction); if (result<0) { GPIO_PIN pin=bcmToGpioSignal(gpio); qCritical()<<"error registering gpio callback for BCM pin"<second); + // request for events + int ret=-1; + switch (edge) { + case EventEdge::RisingEdge: + ret = gpiod_line_request_rising_edge_events( it->second, CONSUMER ); + break; + case EventEdge::FallingEdge: + ret = gpiod_line_request_falling_edge_events( it->second, CONSUMER ); + break; + case EventEdge::BothEdges: + ret = gpiod_line_request_both_edges_events( it->second, CONSUMER ); + default: + break; + } + if ( ret < 0 ) { + qCritical()<<"Request gpio line" << gpio << "for events failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); + if ( line == nullptr ) { + qCritical()<<"error allocating gpio line"<>>>>>> 27beb3a0febeba98e0b037468fa27301bb8faae5 - for (int i = 0; i < data.size(); i++){ - qDebug() << hex << (uint8_t)data[i]; - } - qDebug() << "."; - */ - emit spiData(command, data); +bool PigpiodHandler::unRegisterInterrupt(unsigned int gpio) { + if (!isInitialised) return false; + auto it = fInterruptLineMap.find(gpio); + if (it != fInterruptLineMap.end()) { + gpiod_line_release(it->second); + reloadInterruptSettings(); + return true; + } + return false; } bool PigpiodHandler::initialised(){ return isInitialised; } -bool PigpiodHandler::isSpiInitialised(){ - return spiInitialised; -} - -bool PigpiodHandler::spiInitialise(){ - if (!isInitialised){ - qCritical() << "pigpiohandler not initialised"; - return false; - } - if (spiInitialised){ - return true; - } - spiHandle = spi_open(pi, 0, spiClkFreq, spiFlags); - if (spiHandle<0){ - QString errstr=""; - switch (spiHandle){ - case PI_BAD_CHANNEL: - errstr="DMA channel not 0-15"; - break; - case PI_BAD_SPI_SPEED: - errstr="bad SPI speed"; - break; - case PI_BAD_FLAGS: - errstr="bad spi open flags"; - break; - case PI_NO_AUX_SPI: - errstr="no auxiliary SPI on Pi A or B"; - break; - case PI_SPI_OPEN_FAILED: - errstr="can't open SPI device"; - break; - default: - break; - } - qCritical()<<"Could not initialise SPI bus:"<join(); + } + //pigpio_stop(pi); + //pigHandlerAddress.clear(); } void PigpiodHandler::measureGpioClockTime() { @@ -519,7 +623,8 @@ void PigpiodHandler::measureGpioClockTime() { quint64 t0 = startOfProgram.toMSecsSinceEpoch(); clock_gettime(CLOCK_REALTIME, &tp1); - uint32_t tick = get_current_tick(pi); +/// uint32_t tick = get_current_tick(pi); + uint32_t tick = 0; clock_gettime(CLOCK_REALTIME, &tp2); // clock_gettime(CLOCK_MONOTONIC, &tp); From 98624a7eb76f4a5ee58ecc8d4b4aac63c21e62e8 Mon Sep 17 00:00:00 2001 From: hangeza Date: Mon, 8 Mar 2021 11:19:22 +0000 Subject: [PATCH 03/47] Cleaned up PigpiodHandler class a bit and implemented one signal to forward a detected event to the daemon. With this, all basic functions of the daemon seem to work. Not working yet and to be implemented in the new gpio readout scheme: - pulse rate limitation for high freq. bursts - sampling trigger signals (for triggering the ADC readout) - time and time difference measurements for the population of two histos Note: For the daemon to work with the new libgpiod based readout, several things have to be changed from the pigpiod scheme: - the user who is executing the daemon (usually muonuser) must be added to the system group 'gpio' with 'sudo usermod -a -G gpio muonuser' - the pigpiod daemon must be switched off - the libgpiod-dev package must be installed on the system prior to compilation --- source/daemon/src/pigpiodhandler.cpp | 149 +++------------------------ 1 file changed, 16 insertions(+), 133 deletions(-) diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 5ba427cd..a16b23f7 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -22,8 +22,7 @@ static int pi = -1; static int spiHandle = -1; static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed -constexpr char CONSUMER[] = "muonpi-daemon"; -constexpr std::chrono::milliseconds loop_delay { 10 }; +constexpr char CONSUMER[] = "muonpi"; template inline static T sqr(T x) { return x*x; } @@ -206,29 +205,22 @@ static void cbFunction(int user_pi, unsigned int user_gpio, PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *parent) : QObject(parent) { - startOfProgram = QDateTime::currentDateTimeUtc(); - lastSamplingTime = startOfProgram; - elapsedEventTimer.start(); - pigHandlerAddress = this; - + startOfProgram = QDateTime::currentDateTimeUtc(); + lastSamplingTime = startOfProgram; + elapsedEventTimer.start(); + pigHandlerAddress = this; + std::string chipname { "/dev/gpiochip0" }; - + fChip = gpiod_chip_open(chipname.c_str()); if ( fChip == nullptr ) { qCritical()<<"error opening gpio chip "<(nrInterruptPins); - //std::copy( gpioPins.cbegin(), gpioPins.cend(), _interrupt_pins ); + isInitialised = true; for (unsigned int gpioPin : gpioPins) { -// std::shared_ptr line ( gpiod_chip_get_line(fChip, gpioPin) ); gpiod_line* line = gpiod_chip_get_line(fChip, gpioPin); int flags = 0; /* @@ -236,44 +228,19 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *pare GPIOD_LINE_REQUEST_FLAG_OPEN_SOURCE | GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; */ -// int ret = gpiod_line_request_both_edges_events_flags( line, CONSUMER, flags); int ret = gpiod_line_request_rising_edge_events_flags( line, CONSUMER, flags); if ( ret < 0 ) { qCritical()<<"Request for registering gpio line"< line ( gpiod_chip_get_line(fChip, gpio) ); gpiod_line* line = gpiod_chip_get_line(fChip, gpio); if ( line == nullptr ) { qCritical()<<"error allocating gpio line"<(initState) ); -// fLineMap.emplace( { gpio, line } ); - fLineMap.emplace( std::make_pair( gpio, line ) ); - return true; - } - gpiod::line line( it->second ); - if ( !line.is_requested() ) { - line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(initState) ); - return true; - } - if ( line.direction() == gpiod::line_request::DIRECTION_OUTPUT ) { - qDebug()<<"gpio line" << gpio << "already configured as output"; - return true; - } -// line.set_direction_output( initState ); - // line is not an input, so release it and re-request it as input - line.release(); - line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(initState) ); - return true; -*/ - - // if (isInitialised) set_mode(pi, gpio, PI_OUTPUT); } bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { @@ -426,21 +358,15 @@ bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { } else if ( !(pin_bias & PinBias::PullDown) && !(pin_bias & PinBias::PullUp) ) { //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; } - + auto it = fLineMap.find(gpio); int dir = -1; if (it != fLineMap.end()) { // line object exists, set config - /* - int ret = gpiod_line_set_config( - it->second.get(), GPIOD_LINE_REQUEST_DIRECTION_AS_IS, - flags, 0 ); - */ dir = gpiod_line_direction(it->second); gpiod_line_release(it->second); } // line was not allocated yet, so do it now -// std::shared_ptr line ( gpiod_chip_get_line(fChip, gpio) ); gpiod_line* line = gpiod_chip_get_line(fChip, gpio); if ( line == nullptr ) { qCritical()<<"error allocating gpio line"<(state) ); -// fLineMap.emplace( { gpio, line } ); - fLineMap.emplace( std::make_pair( gpio, line ) ); - return true; - } - gpiod::line line( it->second ); - if ( !line.is_requested() ) { - line.request( { CONSUMER, gpiod::line_request::DIRECTION_OUTPUT, 0 }, static_cast(state) ); - return true; - } -// line.set_direction_output( initState ); - // line is not an input, so release it and re-request it as input - line.set_value( static_cast(state) ); - return true; -*/ } void PigpiodHandler::reloadInterruptSettings() @@ -522,15 +417,6 @@ void PigpiodHandler::reloadInterruptSettings() } bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { - -/* - int result=callback(pi, gpio, edge?FALLING_EDGE:RISING_EDGE, cbFunction); - if (result<0) { - GPIO_PIN pin=bcmToGpioSignal(gpio); - qCritical()<<"error registering gpio callback for BCM pin"<join(); } - //pigpio_stop(pi); - //pigHandlerAddress.clear(); } void PigpiodHandler::measureGpioClockTime() { From bd42fc49a288e5eca5ea2266a05b454d60a09410 Mon Sep 17 00:00:00 2001 From: hangeza Date: Mon, 8 Mar 2021 15:30:48 +0000 Subject: [PATCH 04/47] added start() and stop() slots to PigpiodHandler class to always have a defined run status of the internal thread --- source/daemon/include/pigpiodhandler.h | 12 +++--- source/daemon/src/pigpiodhandler.cpp | 57 +++++++++++++++----------- 2 files changed, 37 insertions(+), 32 deletions(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 8aacd6cd..54443def 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -13,12 +13,8 @@ #include #include -//extern "C" { -//#include #include -//} -//#include #define XOR_RATE 0 #define AND_RATE 1 @@ -42,12 +38,13 @@ class PigpiodHandler : public QObject RisingEdge, FallingEdge, BothEdges }; +// PigpiodHandler( QObject *parent ); explicit PigpiodHandler(std::vector gpioPins, QObject *parent = nullptr); - ~PigpiodHandler(); + ~PigpiodHandler(); // can't make it private because of access of PigpiodHandler with global pointer - QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) - QElapsedTimer elapsedEventTimer; + QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) + QElapsedTimer elapsedEventTimer; GPIO_PIN samplingTriggerSignal=EVT_XOR; double clockMeasurementSlope=0.; @@ -65,6 +62,7 @@ class PigpiodHandler : public QObject void timePulseDiff(qint32 usecs); public slots: + void start(); void stop(); bool initialised(); bool setPinInput(unsigned int gpio); diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index a16b23f7..45810f81 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -9,14 +9,7 @@ #include #include #include - -/* -extern "C" { -//#include -#include -} -*/ static int pi = -1; static int spiHandle = -1; @@ -202,13 +195,22 @@ static void cbFunction(int user_pi, unsigned int user_gpio, } } + +/* +PigpiodHandler::PigpiodHandler(QObject *parent) + : QObject(parent) +{ + +} +*/ + PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *parent) : QObject(parent) { - startOfProgram = QDateTime::currentDateTimeUtc(); - lastSamplingTime = startOfProgram; - elapsedEventTimer.start(); - pigHandlerAddress = this; + startOfProgram = QDateTime::currentDateTimeUtc(); + lastSamplingTime = startOfProgram; + elapsedEventTimer.start(); + pigHandlerAddress = this; std::string chipname { "/dev/gpiochip0" }; @@ -218,7 +220,7 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *pare throw std::exception(); return; } - isInitialised = true; + isInitialised = true; for (unsigned int gpioPin : gpioPins) { gpiod_line* line = gpiod_chip_get_line(fChip, gpioPin); @@ -237,17 +239,16 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *pare fInterruptLineMap.emplace( std::make_pair( gpioPin, line) ); } - gpioClockTimeMeasurementTimer.setInterval(MuonPi::Config::Hardware::GPIO::Clock::Measurement::interval/*GPIO_CLOCK_MEASUREMENT_INTERVAL_MS*/); - gpioClockTimeMeasurementTimer.setSingleShot(false); - connect(&gpioClockTimeMeasurementTimer, &QTimer::timeout, this, &PigpiodHandler::measureGpioClockTime); + gpioClockTimeMeasurementTimer.setInterval(MuonPi::Config::Hardware::GPIO::Clock::Measurement::interval/*GPIO_CLOCK_MEASUREMENT_INTERVAL_MS*/); + gpioClockTimeMeasurementTimer.setSingleShot(false); + connect(&gpioClockTimeMeasurementTimer, &QTimer::timeout, this, &PigpiodHandler::measureGpioClockTime); gpioClockTimeMeasurementTimer.start(); reloadInterruptSettings(); } PigpiodHandler::~PigpiodHandler() { - if (fThreadRunning) fThreadRunning = false; - if (fThread != nullptr) fThread->join(); + this->stop(); for ( auto [gpio,line] : fInterruptLineMap ) { gpiod_line_release(line); } @@ -279,7 +280,11 @@ void PigpiodHandler::threadLoop() { line_index++; } } else if ( ret == 0 ) { - + // a timeout occurred, no event was detected + // simply go over into the wait loop again + } else { + // an error occured + // what should we do here? } //std::this_thread::sleep_for(loop_delay); } @@ -403,17 +408,13 @@ bool PigpiodHandler::setPinState(unsigned int gpio, bool state) { void PigpiodHandler::reloadInterruptSettings() { - if (fThread != nullptr) { - fThreadRunning = false; - fThread->join(); - } + this->stop(); gpiod_line_bulk_init( &fInterruptLineBulk ); // rerequest bulk events for (auto [gpio,line] : fInterruptLineMap) { gpiod_line_bulk_add( &fInterruptLineBulk, line ); } - fThreadRunning = true; - fThread.reset(new std::thread( [this](){ this->threadLoop(); } ) ); + this->start(); } bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { @@ -486,12 +487,18 @@ bool PigpiodHandler::initialised(){ } void PigpiodHandler::stop() { - fThreadRunning = false; + fThreadRunning = false; if ( fThread != nullptr ) { fThread->join(); } } +void PigpiodHandler::start() { + if (fThreadRunning) return; + fThreadRunning = true; + fThread.reset(new std::thread( [this](){ this->threadLoop(); } ) ); +} + void PigpiodHandler::measureGpioClockTime() { if (!isInitialised) return; static uint32_t oldTick = 0; From 921d09c4860f6b4d90aaa64817a99bf20e237c62 Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 23 Mar 2021 22:47:12 +0100 Subject: [PATCH 05/47] small change in debug output of detected edges --- source/daemon/src/pigpiodhandler.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 45810f81..0bbcd2f2 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -273,9 +273,11 @@ void PigpiodHandler::threadLoop() { unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); std::uint64_t ns = event.ts.tv_sec*1e9 + event.ts.tv_nsec; emit signal(gpio); - qDebug()<<"line event: gpio"<("UbxTimeMarkStruct"); qRegisterMetaType("I2cDeviceEntry"); - + qRegisterMetaType("PigpiodHandler::EventEdge"); // signal handling setup_unix_signal_handlers(); if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sighupFd)) { @@ -560,7 +560,8 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n preampStatus[1]=preamp2; gainSwitch=gain; biasON = bias_ON; - eventTrigger = (GPIO_PIN)new_eventTrigger; +// eventTrigger = (GPIO_PIN)new_eventTrigger; + eventTrigger = UNDEFINED_PIN; polarity1=new_polarity1; polarity2=new_polarity2; @@ -724,7 +725,7 @@ void Daemon::connectToPigpiod(){ /// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); - connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::sendGpioPinEvent); + connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { @@ -745,7 +746,11 @@ void Daemon::connectToPigpiod(){ } /*cout<<"TP time diff: "<setSamplingTriggerSignal(eventTrigger); + + auto it=GPIO_PINMAP.find(eventTrigger); + if (it != GPIO_PINMAP.end()) { + pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); + } connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); struct timespec ts_res; @@ -1455,19 +1460,23 @@ void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) { emit sendTcpMessage(tcpMessage); } -void Daemon::sendGpioPinEvent(uint8_t gpio_pin) { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); - //unsigned int gpio_function=0; +void Daemon::onGpioPinEvent(uint8_t gpio) { // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio_pin](const std::pair& item) - { return item.second==gpio_pin; } + auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) + { return item.second==gpio; } ); if (result!=GPIO_PINMAP.end()) { - *(tcpMessage.dStream) << (GPIO_PIN)result->first; - emit sendTcpMessage(tcpMessage); + if ( gpio == pigHandler->samplingTriggerSignal ) emit sampleAdc0Event(); + emit sendGpioPinEvent((GPIO_PIN)result->first); } } +void Daemon::sendGpioPinEvent(GPIO_PIN gpio_pin) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); + *(tcpMessage.dStream) << gpio_pin; + emit sendTcpMessage(tcpMessage); +} + void Daemon::sendBiasVoltage(){ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_VOLTAGE); *(tcpMessage.dStream) << biasVoltage; @@ -1507,8 +1516,8 @@ void Daemon::sendPcaChannel(){ void Daemon::sendEventTriggerSelection(){ if (pigHandler==nullptr) return; - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); - *(tcpMessage.dStream) << (GPIO_PIN)pigHandler->samplingTriggerSignal; + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); + *(tcpMessage.dStream) << bcmToGpioSignal(pigHandler->samplingTriggerSignal); emit sendTcpMessage(tcpMessage); } @@ -1697,13 +1706,17 @@ void Daemon::getTemperature(){ void Daemon::setEventTriggerSelection(GPIO_PIN signal) { if (pigHandler==nullptr) return; auto it=GPIO_PINMAP.find(signal); - if (it==GPIO_PINMAP.end()) return; + if (it==GPIO_PINMAP.end()) { + emit setSamplingTriggerSignal( PigpiodHandler::UNDEFINED_GPIO ); + return; + } if (verbose > 0){ qInfo() << "changed event selection to signal " << (unsigned int)signal; } - emit setSamplingTriggerSignal(signal); - emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)pigHandler->samplingTriggerSignal,16), LogParameter::LOG_EVERY)); + //emit setSamplingTriggerSignal(signal); + emit setSamplingTriggerSignal( it->second ); + emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); //sendEventTriggerSelection(); } @@ -2468,7 +2481,7 @@ void Daemon::onLogParameterPolled(){ } if (pca && pca->devicePresent()) emit logParameter(LogParameter("ubxInputSwitch", "0x"+QString::number(pcaPortMask,16), LogParameter::LOG_ON_CHANGE)); - if (pigHandler!=nullptr) emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)pigHandler->samplingTriggerSignal,16), LogParameter::LOG_ON_CHANGE)); + if (pigHandler!=nullptr) emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)bcmToGpioSignal(pigHandler->samplingTriggerSignal),16), LogParameter::LOG_ON_CHANGE)); //logBiasValues(); if (adc && !(adc->getStatus() & i2cDevice::MODE_UNREACHABLE)) { /* diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 0bbcd2f2..9c4b16f6 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -16,6 +16,7 @@ static int spiHandle = -1; static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed constexpr char CONSUMER[] = "muonpi"; +const std::string chipname { "/dev/gpiochip0" }; template inline static T sqr(T x) { return x*x; } @@ -80,12 +81,10 @@ void calcLinearCoefficients(int n, quint64 *xarray, qint64 *yarray, } - - - /* This is the central interrupt routine for all registered GPIO pins * */ +/* static void cbFunction(int user_pi, unsigned int user_gpio, unsigned int level, uint32_t tick) { //qDebug() << "callback user_pi: " << user_pi << " user_gpio: " << user_gpio << " level: "<< level << " pigHandlerAddressNull: " << pigHandlerAddress.isNull() ; @@ -126,18 +125,17 @@ static void cbFunction(int user_pi, unsigned int user_gpio, }); if (it==GPIO_PINMAP.end()) return; -/* - if (user_gpio == GPIO_PINMAP[ADC_READY]) { -// std::cout<<"ADC conv ready"< gpioPins, QObject *pare int ret = gpiod_line_request_rising_edge_events_flags( line, CONSUMER, flags); if ( ret < 0 ) { qCritical()<<"Request for registering gpio line"<stop(); From 8f301b152bc3d5067fabffb868fc3f71035ca9a4 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 11 Jul 2021 13:29:36 +0200 Subject: [PATCH 07/47] Added RateBuffer class for handling of all GPIO rates. Still to be implemented for the tracking of the XOR and AND rates in the daemon. --- source/daemon/CMakeLists.txt | 2 ++ source/daemon/include/daemon.h | 31 ++++++++++------- source/daemon/include/ratebuffer.h | 51 ++++++++++++++++++++++++++++ source/daemon/src/daemon.cpp | 24 +++++++++++-- source/daemon/src/pigpiodhandler.cpp | 13 +++---- source/daemon/src/ratebuffer.cpp | 29 ++++++++++++++++ 6 files changed, 125 insertions(+), 25 deletions(-) create mode 100644 source/daemon/include/ratebuffer.h create mode 100644 source/daemon/src/ratebuffer.cpp diff --git a/source/daemon/CMakeLists.txt b/source/daemon/CMakeLists.txt index 163d8e55..efc04cc2 100644 --- a/source/daemon/CMakeLists.txt +++ b/source/daemon/CMakeLists.txt @@ -74,6 +74,7 @@ set(DAEMON_SOURCE_FILES "${PROJECT_SRC_DIR}/gpio_mapping.cpp" "${PROJECT_SRC_DIR}/logengine.cpp" "${PROJECT_SRC_DIR}/geohash.cpp" + "${PROJECT_SRC_DIR}/ratebuffer.cpp" "${PROJECT_SRC_DIR}/tdc7200.cpp" "${PROJECT_SRC_DIR}/i2c/i2cbusses.c" "${PROJECT_SRC_DIR}/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp" @@ -107,6 +108,7 @@ set(DAEMON_HEADER_FILES "${PROJECT_HEADER_DIR}/tdc7200.h" "${PROJECT_HEADER_DIR}/logengine.h" "${PROJECT_HEADER_DIR}/geohash.h" + "${PROJECT_HEADER_DIR}/ratebuffer.h" "${PROJECT_HEADER_DIR}/i2c/addresses.h" "${PROJECT_HEADER_DIR}/i2c/custom_i2cdetect.h" "${PROJECT_HEADER_DIR}/i2c/i2cbusses.h" diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index dba331aa..80b26cb3 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -10,18 +10,19 @@ #include #include -#include "tcpconnection.h" -#include "custom_io_operators.h" -#include "qtserialublox.h" -#include "pigpiodhandler.h" -#include "tdc7200.h" -#include "filehandler.h" -#include "mqtthandler.h" -#include "i2c/i2cdevices.h" -#include "calibration.h" -#include "logparameter.h" -#include "histogram.h" -#include "logengine.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // for sig handling: #include @@ -30,6 +31,7 @@ struct CalibStruct; struct UbxTimeMarkStruct; + enum GPIO_PIN; class Property { @@ -306,7 +308,10 @@ private slots: // mqtt QPointer mqttHandler; - // signal handling + // rate buffer + RateBuffer rateBuffer; + + // signal handling static int sighupFd[2]; static int sigtermFd[2]; static int sigintFd[2]; diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h new file mode 100644 index 00000000..ec73c656 --- /dev/null +++ b/source/daemon/include/ratebuffer.h @@ -0,0 +1,51 @@ +#ifndef RATEBUFFER_H +#define RATEBUFFER_H +#include +#include +#include +#include +#include +#include +#include +#include +#include + +constexpr double MAX_AVG_RATE { 1000. }; +constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; +using namespace std::literals; +constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60 * 1s }; + +class RateBuffer : public QObject +{ + Q_OBJECT + +public: + struct BufferItem { + std::queue< std::chrono::time_point, + std::list> > + eventbuffer { }; + unsigned long multiplicity_countdown { MAX_BURST_MULTIPLICITY }; + std::chrono::microseconds current_deadtime { 0 }; + }; + + RateBuffer(QObject *parent = nullptr); + ~RateBuffer() = default; + void setRateLimit( double max_cps ); + [[nodiscard]] auto currentRateLimit() const -> double { return fRateLimit; } + void clear() { buffermap.clear(); } + + [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; +signals: + void throttledSignal(unsigned int gpio); + +public slots: + void onSignal(unsigned int gpio); + +private: + double fRateLimit { MAX_AVG_RATE }; + std::chrono::microseconds fBufferTime { MAX_BUFFER_TIME }; + std::map buffermap { }; + +}; + +#endif // RATEBUFFER_H diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 419abb3b..6df4e57d 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -14,8 +14,9 @@ #include #include #include -#include +//#include #include +//#include #include #include #include @@ -309,7 +310,6 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n } } - mqttHandlerThread = new QThread(); mqttHandlerThread->setObjectName("muondetector-daemon-mqtt"); connect(this, &Daemon::aboutToQuit, mqttHandlerThread, &QThread::quit); @@ -627,7 +627,11 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n // connect to the pigpio daemon interface for gpio control connectToPigpiod(); - // set up histograms + // set up the rate buffer for all GPIO signals + rateBuffer.clear(); + connect(pigHandler, &PigpiodHandler::signal, &rateBuffer, &RateBuffer::onSignal); + + // set up histograms setupHistos(); // establish ublox gnss module connection @@ -2554,6 +2558,20 @@ void Daemon::onLogParameterPolled(){ emit logParameter(LogParameter("systemFreeSwap", QString::number(1e-6*info.freeswap/info.mem_unit)+" Mb", LogParameter::LOG_AVERAGE)); emit logParameter(LogParameter("systemLoadAvg", QString::number(info.loads[0]*f_load)+" ", LogParameter::LOG_AVERAGE)); } + + // rate buffer debug output + if ( verbose > 2 ) { + qDebug() << "GPIO Rate Summary:"; + for (auto signalIt=GPIO_PINMAP.begin(); signalIt!=GPIO_PINMAP.end(); signalIt++) { + const GPIO_PIN signalId=signalIt->first; + if (GPIO_SIGNAL_MAP[signalId].direction == DIR_IN ) { + qDebug()<second + <second )<<"Hz"; + } + } + } + // updateOledDisplay(); } diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 9c4b16f6..4d903f00 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -401,15 +401,10 @@ bool PigpiodHandler::setPinState(unsigned int gpio, bool state) { void PigpiodHandler::setSamplingTriggerSignal(unsigned int gpio) { - // The following code is intentionally commented out - // since we don't want to unregister a gpio interrupt after changing the samplingTrigger to another line. - // The reason is, that several interrupt functions can occupy one gpio line. When unregistering the samplingTrigger, - // the pin would cease to funtion as interrupt source for the alternative function. Example: XOR is an interrupt input - // and can also be selected as sampling Trigger by the user for a time. - - if ( gpio == UNDEFINED_GPIO ) { - unRegisterInterrupt( samplingTriggerSignal ); - } + // The following code registers the given gpio pin for interrupt, if not already done before. The previously setInterval + // samplingTrigger is NOT unregistered, since several interrupt functions can occupy one gpio line. + // When unregistering the samplingTrigger, the pin would cease to funtion as interrupt source for the alternative function. + // Example: XOR is an interrupt input and can also be selected as sampling trigger by the user for a time. samplingTriggerSignal=gpio; // search through the interrupt lines whether the line is already selected as interrupt source diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp new file mode 100644 index 00000000..7372eed6 --- /dev/null +++ b/source/daemon/src/ratebuffer.cpp @@ -0,0 +1,29 @@ +#include + + +RateBuffer::RateBuffer(QObject *parent) : QObject(parent) +{ + +} + +void RateBuffer::onSignal(unsigned int gpio) { + auto now = std::chrono::steady_clock::now(); + buffermap[gpio].eventbuffer.push(now); + while ( buffermap[gpio].eventbuffer.size() > 1 + && ( now - buffermap[gpio].eventbuffer.front() > fBufferTime) ) + { + buffermap[gpio].eventbuffer.pop(); + } +} + +auto RateBuffer::avgRate(unsigned int gpio) const -> double +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() ) return 0.; + if ( it->second.eventbuffer.empty() ) return 0.; + auto end = std::chrono::steady_clock::now(); + auto start = end - fBufferTime; + if ( start > it->second.eventbuffer.front() ) start = it->second.eventbuffer.front(); + double span = 1e-6 * std::chrono::duration_cast(end - start).count(); + return ( it->second.eventbuffer.size() / span ); +} From ecbc0592ea7216bf9b07dff0cb5b8b320ab7f8a5 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 11 Jul 2021 17:22:34 +0200 Subject: [PATCH 08/47] Embedded RateBuffer in daemon. All rate handling should be supervised by an instance of this class now. RateBuffer contains a smart rate throttling which prevents lock-up of daemon and GUI at excessive rates. This branch should now privide equal or better functionality compared to the pigpiod daemon. However, the following features are not yet implemented: - Measurement of the system time deviation from GNSS (timpulse) time - Measurement of the GPIO event interval (as in the histogram under statistics tab of the GUI with the same name). This may be implemented easily with the help of the RateBuffer class. --- source/daemon/include/daemon.h | 2 +- source/daemon/include/ratebuffer.h | 7 ++++-- source/daemon/src/daemon.cpp | 28 +++++++++++++++------- source/daemon/src/ratebuffer.cpp | 38 +++++++++++++++++++++++++++--- 4 files changed, 60 insertions(+), 15 deletions(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index 80b26cb3..5248b896 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -174,7 +174,7 @@ public slots: void receivedTcpMessage(TcpMessage tcpMessage); void pollAllUbxMsgRate(); void onGpioPinEvent(uint8_t gpio); - void sendGpioPinEvent(GPIO_PIN gpio_pin); + void sendGpioPinEvent(uint8_t gpio); void onGpsPropertyUpdatedGeodeticPos(const GeodeticPos& pos); void UBXReceivedVersion(const QString& swString, const QString& hwString, const QString& protString); void sampleAdc0Event(); diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h index ec73c656..0a10e127 100644 --- a/source/daemon/include/ratebuffer.h +++ b/source/daemon/include/ratebuffer.h @@ -10,10 +10,11 @@ #include #include -constexpr double MAX_AVG_RATE { 1000. }; +constexpr double MAX_AVG_RATE { 100. }; constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; using namespace std::literals; -constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60 * 1s }; +constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; +constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6/MAX_AVG_RATE) }; class RateBuffer : public QObject { @@ -35,6 +36,8 @@ class RateBuffer : public QObject void clear() { buffermap.clear(); } [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; + [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; + signals: void throttledSignal(unsigned int gpio); diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 6df4e57d..7648cad8 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -630,6 +630,8 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n // set up the rate buffer for all GPIO signals rateBuffer.clear(); connect(pigHandler, &PigpiodHandler::signal, &rateBuffer, &RateBuffer::onSignal); + connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::sendGpioPinEvent); + connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::onGpioPinEvent); // set up histograms setupHistos(); @@ -729,8 +731,8 @@ void Daemon::connectToPigpiod(){ /// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); - connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); - connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); +// connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); +// connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); @@ -771,6 +773,7 @@ void Daemon::connectToPigpiod(){ timespec_get(&lastRateInterval, TIME_UTC); startOfProgram = lastRateInterval; connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin){ +// connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](uint8_t gpio_pin){ rateCounterIntervalActualisation(); if (gpio_pin==GPIO_PINMAP[EVT_XOR]){ xorCounts.back()++; @@ -1471,14 +1474,20 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { ); if (result!=GPIO_PINMAP.end()) { if ( gpio == pigHandler->samplingTriggerSignal ) emit sampleAdc0Event(); - emit sendGpioPinEvent((GPIO_PIN)result->first); + //emit sendGpioPinEvent((GPIO_PIN)result->first); } } -void Daemon::sendGpioPinEvent(GPIO_PIN gpio_pin) { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); - *(tcpMessage.dStream) << gpio_pin; - emit sendTcpMessage(tcpMessage); +void Daemon::sendGpioPinEvent(uint8_t gpio) { + // reverse lookup of gpio function from given pin (first occurence) + auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) + { return item.second==gpio; } + ); + if (result!=GPIO_PINMAP.end()) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); + *(tcpMessage.dStream) << (GPIO_PIN)result->first; + emit sendTcpMessage(tcpMessage); + } } void Daemon::sendBiasVoltage(){ @@ -2566,8 +2575,9 @@ void Daemon::onLogParameterPolled(){ const GPIO_PIN signalId=signalIt->first; if (GPIO_SIGNAL_MAP[signalId].direction == DIR_IN ) { qDebug()<second - <second )<<"Hz"; + <<"pin:"<second + <<"rate:"<second )<<"Hz" + <<"deadtime"<second ).count()<<"us"; } } } diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp index 7372eed6..4757c273 100644 --- a/source/daemon/src/ratebuffer.cpp +++ b/source/daemon/src/ratebuffer.cpp @@ -1,5 +1,5 @@ #include - +#include RateBuffer::RateBuffer(QObject *parent) : QObject(parent) { @@ -8,12 +8,37 @@ RateBuffer::RateBuffer(QObject *parent) : QObject(parent) void RateBuffer::onSignal(unsigned int gpio) { auto now = std::chrono::steady_clock::now(); - buffermap[gpio].eventbuffer.push(now); - while ( buffermap[gpio].eventbuffer.size() > 1 + if ( buffermap[gpio].eventbuffer.empty() ) { + buffermap[gpio].eventbuffer.push(now); + emit throttledSignal(gpio); + return; + } + + while ( !buffermap[gpio].eventbuffer.empty() && ( now - buffermap[gpio].eventbuffer.front() > fBufferTime) ) { buffermap[gpio].eventbuffer.pop(); } + + if ( !buffermap[gpio].eventbuffer.empty() ) { + auto last_event_time = buffermap[gpio].eventbuffer.back(); + if ( now - last_event_time < MAX_DEADTIME ) { +// std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="<0 ) { + deadtime--; + buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); + } + } + } + buffermap[gpio].eventbuffer.push(now); + emit throttledSignal(gpio); } auto RateBuffer::avgRate(unsigned int gpio) const -> double @@ -27,3 +52,10 @@ auto RateBuffer::avgRate(unsigned int gpio) const -> double double span = 1e-6 * std::chrono::duration_cast(end - start).count(); return ( it->second.eventbuffer.size() / span ); } + +auto RateBuffer::currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() ) return std::chrono::microseconds(0); + return it->second.current_deadtime; +} From 618850295a1ffb0b09c615c27917059d4eeb10b6 Mon Sep 17 00:00:00 2001 From: hangeza Date: Mon, 12 Jul 2021 02:04:26 +0200 Subject: [PATCH 09/47] Added measurement of gpio interval time (in histogram "gpioEventInterval"). Adjusted scaling of several histograms. --- source/daemon/include/daemon.h | 1 + source/daemon/include/pigpiodhandler.h | 2 +- source/daemon/include/ratebuffer.h | 2 + source/daemon/src/daemon.cpp | 64 ++++++++++++++++++++------ source/daemon/src/ratebuffer.cpp | 9 ++++ 5 files changed, 63 insertions(+), 15 deletions(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index 5248b896..83af6dd3 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -219,6 +219,7 @@ public slots: void timeMarkIntervalCountUpdate(uint16_t newCounts, double lastInterval); void requestMqttConnectionStatus(); void eventMessage(const QString& messageString); + void eventInterval(quint64 nsecs); private slots: void onRateBufferReminder(); diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 5316c99d..5f8ac228 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -59,7 +59,7 @@ class PigpiodHandler : public QObject signals: void signal(uint8_t gpio_pin); void samplingTrigger(); - void eventInterval(quint64 nsecs); + //void eventInterval(quint64 nsecs); void timePulseDiff(qint32 usecs); public slots: diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h index 0a10e127..ea9e96f7 100644 --- a/source/daemon/include/ratebuffer.h +++ b/source/daemon/include/ratebuffer.h @@ -27,6 +27,7 @@ class RateBuffer : public QObject eventbuffer { }; unsigned long multiplicity_countdown { MAX_BURST_MULTIPLICITY }; std::chrono::microseconds current_deadtime { 0 }; + std::chrono::nanoseconds last_interval { 0 }; }; RateBuffer(QObject *parent = nullptr); @@ -37,6 +38,7 @@ class RateBuffer : public QObject [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; + [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; signals: void throttledSignal(unsigned int gpio); diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 7648cad8..7aaa7ef1 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -624,7 +624,10 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n } flush(cout); - // connect to the pigpio daemon interface for gpio control + // set up histograms + setupHistos(); + + // connect to the pigpio daemon interface for gpio control connectToPigpiod(); // set up the rate buffer for all GPIO signals @@ -633,8 +636,19 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::sendGpioPinEvent); connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::onGpioPinEvent); - // set up histograms - setupHistos(); + connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) + { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { + //checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); + histoMap["gpioEventInterval"].fill(1e-6*nsecs); + } + } ); + + connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) + { if (histoMap.find("gpioEventIntervalShort")!=histoMap.end()) { + if (nsecs/1000<=histoMap["gpioEventIntervalShort"].getMax()) + histoMap["gpioEventIntervalShort"].fill((double)nsecs/1000.); + } + } ); // establish ublox gnss module connection connectToGps(); @@ -733,18 +747,21 @@ void Daemon::connectToPigpiod(){ connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); // connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); // connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); - connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) +/* + connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); histoMap["gpioEventInterval"].fill(1e-6*nsecs); } } ); + connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) { if (histoMap.find("gpioEventIntervalShort")!=histoMap.end()) { if (nsecs/1000<=histoMap["gpioEventIntervalShort"].getMax()) histoMap["gpioEventIntervalShort"].fill((double)nsecs/1000.); } } ); +*/ connect(pigHandler, &PigpiodHandler::timePulseDiff, this, [this](qint32 usecs) { if (histoMap.find("TPTimeDiff")!=histoMap.end()) { checkRescaleHisto(histoMap["TPTimeDiff"], usecs); @@ -968,13 +985,13 @@ void Daemon::setupHistos() { hist=Histogram("UbxEventLength",100,50.,149.); hist.setUnit("ns"); histoMap["UbxEventLength"]=hist; - hist=Histogram("gpioEventInterval",400,0.,1500.); + hist=Histogram("gpioEventInterval",400,0.,2000.); hist.setUnit("ms"); histoMap["gpioEventInterval"]=hist; hist=Histogram("gpioEventIntervalShort",50,0.,49.); hist.setUnit("us"); histoMap["gpioEventIntervalShort"]=hist; - hist=Histogram("UbxEventInterval",200,0.,1100.); + hist=Histogram("UbxEventInterval",400,0.,2000.); hist.setUnit("ms"); histoMap["UbxEventInterval"]=hist; hist=Histogram("TPTimeDiff",200,-999.,1000.); @@ -1025,24 +1042,23 @@ void Daemon::checkRescaleHisto(Histogram& hist, double newValue) { double ofl=hist.getOverflow(); entries-=ufl+ofl; double range=hist.getMax()-hist.getMin(); - if (ufl>0. && ofl>0. && (ufl+ofl)>0.05*entries) { - // range is too small, underflow and overflow have more than 5% of all entries + if (ufl>0. && ofl>0. && (ufl+ofl)>0.02*entries) { + // range is too small, underflow and overflow have more than 2% of all entries rescaleHisto(hist, hist.getMean(), 1.2*range); - } else if (ufl>0.05*entries) { + } else if (ufl>0.02*entries) { // if (entries<1.) rescaleHisto(hist, hist.getMin()-(hist.getMax()-hist.getMin())/2.); if (entries<1.) rescaleHisto(hist, newValue); else rescaleHisto(hist, hist.getMean(), 1.2*range); - } else if (ofl>0.05*entries) { + } else if (ofl>0.02*entries) { // if (entries<1.) rescaleHisto(hist, hist.getMax()+(hist.getMax()-hist.getMin())/2.); if (entries<1.) rescaleHisto(hist, newValue); - else rescaleHisto(hist, hist.getMean(), 1.1*range); + else rescaleHisto(hist, hist.getMean(), 1.2*range); } else if (ufl<1e-3 && ofl<1e-3) { // check if range is too wide if (entries>100) { int lowest = hist.getLowestOccupiedBin(); int highest = hist.getHighestOccupiedBin(); - if ((float)lowest/hist.getNrBins()>0.45) rescaleHisto(hist, hist.getMean(), 0.6*range); - else if ((float)(hist.getNrBins()-highest)/hist.getNrBins()>0.45) rescaleHisto(hist, hist.getMean(), 0.6*range); + if ((float)lowest/hist.getNrBins()>0.45 && (float)(hist.getNrBins()-highest)/hist.getNrBins()>0.45) rescaleHisto(hist, hist.getMean(), 0.75*range); } } } @@ -1473,7 +1489,27 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { { return item.second==gpio; } ); if (result!=GPIO_PINMAP.end()) { - if ( gpio == pigHandler->samplingTriggerSignal ) emit sampleAdc0Event(); + if ( gpio == pigHandler->samplingTriggerSignal ) { + emit eventInterval( rateBuffer.lastInterval(gpio).count() ); +/* + if (user_gpio == GPIO_PINMAP[pigpioHandler->samplingTriggerSignal]){ + if (pigpioHandler->lastSamplingTime.msecsTo(now) >= MuonPi::Config::Hardware::ADC::deadtime) { + emit pigpioHandler->samplingTrigger(); + pigpioHandler->lastSamplingTime = now; + } + quint64 nsecsElapsed=pigpioHandler->elapsedEventTimer.nsecsElapsed(); + pigpioHandler->elapsedEventTimer.start(); + //emit pigpioHandler->eventInterval(nsecsElapsed); + emit pigpioHandler->eventInterval((tick-lastTriggerTick)*1000); + lastTriggerTick=tick; + } +*/ + + + + + emit sampleAdc0Event(); + } //emit sendGpioPinEvent((GPIO_PIN)result->first); } } diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp index 4757c273..f471bf80 100644 --- a/source/daemon/src/ratebuffer.cpp +++ b/source/daemon/src/ratebuffer.cpp @@ -22,6 +22,7 @@ void RateBuffer::onSignal(unsigned int gpio) { if ( !buffermap[gpio].eventbuffer.empty() ) { auto last_event_time = buffermap[gpio].eventbuffer.back(); + buffermap[gpio].last_interval = std::chrono::duration_cast( now - last_event_time ); if ( now - last_event_time < MAX_DEADTIME ) { // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< std::chrono::micros if ( it == buffermap.end() ) return std::chrono::microseconds(0); return it->second.current_deadtime; } + +auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() || it->second.eventbuffer.size() < 2 ) return std::chrono::nanoseconds(0); + return it->second.last_interval; +} + From 0a4d40a6445c02a721090524917244655c3e519c Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 13 Jul 2021 03:10:23 +0200 Subject: [PATCH 10/47] Renamed enum GPIO_PIN to the more reasonable GPIO_SIGNAL, since this signal is explicitly not bound to a fixed GPIO pin. Corrected some wrong assignments in the GPIO pin list for HW Ver 1. --- source/daemon/include/daemon.h | 10 +++++----- source/daemon/include/gpio_mapping.h | 14 ++++++------- source/daemon/include/pigpiodhandler.h | 4 ++-- source/daemon/src/daemon.cpp | 20 +++++++++---------- source/daemon/src/gpio_mapping.cpp | 2 +- source/daemon/src/main.cpp | 2 +- source/daemon/src/pigpiodhandler.cpp | 4 ++-- source/gui/include/mainwindow.h | 6 +++--- source/gui/include/parametermonitorform.h | 4 ++-- source/gui/include/status.h | 4 ++-- source/gui/src/mainwindow.cpp | 10 +++++----- source/gui/src/parametermonitorform.cpp | 4 ++-- source/gui/src/status.cpp | 4 ++-- source/library/include/gpio_pin_definitions.h | 10 +++++----- 14 files changed, 49 insertions(+), 49 deletions(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index 83af6dd3..88c9a131 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -32,7 +32,7 @@ struct CalibStruct; struct UbxTimeMarkStruct; -enum GPIO_PIN; +enum GPIO_SIGNAL; class Property { public: @@ -97,7 +97,7 @@ class Property { struct RateScanInfo { uint8_t origPcaMask=0; - GPIO_PIN origEventTrigger=GPIO_PIN::UNDEFINED_PIN; + GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_PIN; uint16_t lastEvtCounter=0; uint8_t thrChannel=0; float origThr=3.3; @@ -112,7 +112,7 @@ struct RateScanInfo { struct RateScan { // void addScanPoint(double scanpar, double a_rate) { scanMap[scanpar].append(a_rate); } uint8_t origPcaMask=0; - GPIO_PIN origEventTrigger=GPIO_PIN::UNDEFINED_PIN; + GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_PIN; float origScanPar=3.3; double minScanPar=0.; double maxScanPar=1.; @@ -232,7 +232,7 @@ private slots: void incomingConnection(qintptr socketDescriptor) override; void setPcaChannel(uint8_t channel); // channel 0 to 3 // 0: coincidence ; 1: xor ; 2: discr 1 ; 3: discr 2 - void setEventTriggerSelection(GPIO_PIN signal); + void setEventTriggerSelection(GPIO_SIGNAL signal); void sendPcaChannel(); void sendEventTriggerSelection(); void setDacThresh(uint8_t channel, float threshold); // channel 0 or 1 ; threshold in volts @@ -279,7 +279,7 @@ private slots: Adafruit_SSD1306* oled = nullptr; float biasVoltage = 0.; bool biasON = false; - GPIO_PIN eventTrigger; + GPIO_SIGNAL eventTrigger; bool gainSwitch = false; bool preampStatus[2]; uint8_t pcaPortMask = 0; diff --git a/source/daemon/include/gpio_mapping.h b/source/daemon/include/gpio_mapping.h index 93cdecbf..34503262 100644 --- a/source/daemon/include/gpio_mapping.h +++ b/source/daemon/include/gpio_mapping.h @@ -13,7 +13,7 @@ // TO MAKE IT MORE SIMPLE THERE WILL BE ONLY PIGPIO NAMING STANDARD, // NO WIRING PI FROM NOW -static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] = { +static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] = { { /* Pin mapping, HW Version 0, proxy to be never used nor initializing something */ } , @@ -30,9 +30,9 @@ static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] { STATUS1 , 13 }, { STATUS2 , 19 }, { STATUS3 , 26 }, - { TDC_INTB, 20 }, - { TDC_STATUS, 21 }, - { EXT_TRIGGER, 21 } + { TDC_INTB, 24 }, + { TDC_STATUS, 25 }, + { EXT_TRIGGER, 16 } } , { /* Pin mapping, HW Version 2 */ @@ -75,10 +75,10 @@ static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] }; -extern std::map GPIO_PINMAP; +extern std::map GPIO_PINMAP; -inline GPIO_PIN bcmToGpioSignal(unsigned int bcmGpioNumber) { - std::map::const_iterator i = GPIO_PINMAP.cbegin(); +inline GPIO_SIGNAL bcmToGpioSignal(unsigned int bcmGpioNumber) { + std::map::const_iterator i = GPIO_PINMAP.cbegin(); while (i != GPIO_PINMAP.cend() && i->second!=bcmGpioNumber) ++i; if (i==GPIO_PINMAP.cend()) return UNDEFINED_PIN; return i->first; diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 5f8ac228..eff1ff06 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -46,7 +46,7 @@ class PigpiodHandler : public QObject // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; -// GPIO_PIN samplingTriggerSignal=EVT_XOR; +// GPIO_SIGNAL samplingTriggerSignal=EVT_XOR; unsigned int samplingTriggerSignal { UNDEFINED_GPIO }; double clockMeasurementSlope=0.; @@ -72,7 +72,7 @@ public slots: bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); bool setPinState(unsigned int gpio, bool state); void setSamplingTriggerSignal(unsigned int gpio); -// void setSamplingTriggerSignal(GPIO_PIN signalName) { samplingTriggerSignal=signalName; } +// void setSamplingTriggerSignal(GPIO_SIGNAL signalName) { samplingTriggerSignal=signalName; } bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); void setInhibited(bool inh=true) { inhibit=inh; } diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 7aaa7ef1..d9e8ba86 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -201,7 +201,7 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n qRegisterMetaType("UbxTimePulseStruct"); qRegisterMetaType("UbxDopStruct"); qRegisterMetaType("timespec"); - qRegisterMetaType("GPIO_PIN"); + qRegisterMetaType("GPIO_SIGNAL"); qRegisterMetaType("GnssMonHwStruct"); qRegisterMetaType("GnssMonHw2Struct"); qRegisterMetaType("UbxTimeMarkStruct"); @@ -295,7 +295,7 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n cout<<"GPIO pin mapping:"<first; + const GPIO_SIGNAL signalId=signalIt->first; cout<second; switch (GPIO_SIGNAL_MAP[signalId].direction) { case DIR_IN: cout<<" (in)"; @@ -560,7 +560,7 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n preampStatus[1]=preamp2; gainSwitch=gain; biasON = bias_ON; -// eventTrigger = (GPIO_PIN)new_eventTrigger; +// eventTrigger = (GPIO_SIGNAL)new_eventTrigger; eventTrigger = UNDEFINED_PIN; polarity1=new_polarity1; polarity2=new_polarity2; @@ -1197,7 +1197,7 @@ void Daemon::receivedTcpMessage(TcpMessage tcpMessage) { if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER){ unsigned int signal; *(tcpMessage.dStream) >> signal; - setEventTriggerSelection((GPIO_PIN)signal); + setEventTriggerSelection((GPIO_SIGNAL)signal); usleep(1000); sendEventTriggerSelection(); return; @@ -1485,7 +1485,7 @@ void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) { void Daemon::onGpioPinEvent(uint8_t gpio) { // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) + auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second==gpio; } ); if (result!=GPIO_PINMAP.end()) { @@ -1510,18 +1510,18 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { emit sampleAdc0Event(); } - //emit sendGpioPinEvent((GPIO_PIN)result->first); + //emit sendGpioPinEvent((GPIO_SIGNAL)result->first); } } void Daemon::sendGpioPinEvent(uint8_t gpio) { // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) + auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second==gpio; } ); if (result!=GPIO_PINMAP.end()) { TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); - *(tcpMessage.dStream) << (GPIO_PIN)result->first; + *(tcpMessage.dStream) << (GPIO_SIGNAL)result->first; emit sendTcpMessage(tcpMessage); } } @@ -1752,7 +1752,7 @@ void Daemon::getTemperature(){ emit sendTcpMessage(tcpMessage); } -void Daemon::setEventTriggerSelection(GPIO_PIN signal) { +void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) { if (pigHandler==nullptr) return; auto it=GPIO_PINMAP.find(signal); if (it==GPIO_PINMAP.end()) { @@ -2608,7 +2608,7 @@ void Daemon::onLogParameterPolled(){ if ( verbose > 2 ) { qDebug() << "GPIO Rate Summary:"; for (auto signalIt=GPIO_PINMAP.begin(); signalIt!=GPIO_PINMAP.end(); signalIt++) { - const GPIO_PIN signalId=signalIt->first; + const GPIO_SIGNAL signalId=signalIt->first; if (GPIO_SIGNAL_MAP[signalId].direction == DIR_IN ) { qDebug()<second diff --git a/source/daemon/src/gpio_mapping.cpp b/source/daemon/src/gpio_mapping.cpp index 6b308907..c66cc29f 100644 --- a/source/daemon/src/gpio_mapping.cpp +++ b/source/daemon/src/gpio_mapping.cpp @@ -2,4 +2,4 @@ #include "config.h" #include -std::map GPIO_PINMAP = GPIO_PINMAP_VERSIONS[MuonPi::Version::hardware.major]; +std::map GPIO_PINMAP = GPIO_PINMAP_VERSIONS[MuonPi::Version::hardware.major]; diff --git a/source/daemon/src/main.cpp b/source/daemon/src/main.cpp index 111bc266..785454cb 100644 --- a/source/daemon/src/main.cpp +++ b/source/daemon/src/main.cpp @@ -543,7 +543,7 @@ int main(int argc, char *argv[]) { //if (verbose>2) // qWarning() << "No 'trigger_input' setting in configuration file. Assuming gpio" << (int)eventSignal << endl; - qWarning() << "No 'trigger_input' setting in configuration file. Assuming signal" << GPIO_SIGNAL_MAP[(GPIO_PIN)eventSignal].name; + qWarning() << "No 'trigger_input' setting in configuration file. Assuming signal" << GPIO_SIGNAL_MAP[(GPIO_SIGNAL)eventSignal].name; } diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 4d903f00..32b9423f 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -117,9 +117,9 @@ static void cbFunction(int user_pi, unsigned int user_gpio, try{ // allow only registered signals to be processed here - // if gpio pin fired which is not in GPIO_PIN list, return immediately + // if gpio pin fired which is not in GPIO_SIGNAL list, return immediately auto it=std::find_if(GPIO_PINMAP.cbegin(), GPIO_PINMAP.cend(), - [&user_gpio](const std::pair& val) { + [&user_gpio](const std::pair& val) { if (val.second==user_gpio) return true; return false; }); diff --git a/source/gui/include/mainwindow.h b/source/gui/include/mainwindow.h index 9592a7e7..6c42c6d7 100644 --- a/source/gui/include/mainwindow.h +++ b/source/gui/include/mainwindow.h @@ -75,7 +75,7 @@ class MainWindow : public QMainWindow void ubxUptimeReceived(quint32 val); void gpsTP5Received(const UbxTimePulseStruct& tp); void histogramReceived(const Histogram& h); - void triggerSelectionReceived(GPIO_PIN signal); + void triggerSelectionReceived(GPIO_SIGNAL signal); void timepulseReceived(); void adcModeReceived(quint8 mode); void logInfoReceived(const LogInfoStruct& lis); @@ -87,12 +87,12 @@ class MainWindow : public QMainWindow public slots: void receivedTcpMessage(TcpMessage tcpMessage); - void receivedGpioRisingEdge(GPIO_PIN pin); + void receivedGpioRisingEdge(GPIO_SIGNAL pin); void sendRequestUbxMsgRates(); void sendSetUbxMsgRateChanges(QMap changes); void onSendUbxReset(); void makeConnection(QString ipAddress, quint16 port); - void onTriggerSelectionChanged(GPIO_PIN signal); + void onTriggerSelectionChanged(GPIO_SIGNAL signal); void onHistogramCleared(QString histogramName); void onAdcModeChanged(quint8 mode); void onRateScanStart(uint8_t ch); diff --git a/source/gui/include/parametermonitorform.h b/source/gui/include/parametermonitorform.h index d939f96c..13dc842a 100644 --- a/source/gui/include/parametermonitorform.h +++ b/source/gui/include/parametermonitorform.h @@ -31,7 +31,7 @@ class ParameterMonitorForm : public QWidget void preamp2EnableChanged(bool state); void polarityChanged(bool pol1, bool pol2); void timingSelectionChanged(uint8_t sel); - void triggerSelectionChanged(GPIO_PIN signal); + void triggerSelectionChanged(GPIO_SIGNAL signal); public slots: void onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector &calibList); @@ -40,7 +40,7 @@ public slots: void onInputSwitchReceived(uint8_t index); void onBiasSwitchReceived(bool state); void onPreampSwitchReceived(uint8_t channel, bool state); - void onTriggerSelectionReceived(GPIO_PIN signal); + void onTriggerSelectionReceived(GPIO_SIGNAL signal); void onGainSwitchReceived(bool state); void onTemperatureReceived(float temp); void onTimepulseReceived(); diff --git a/source/gui/include/status.h b/source/gui/include/status.h index 4aed4ee7..986a6820 100644 --- a/source/gui/include/status.h +++ b/source/gui/include/status.h @@ -28,7 +28,7 @@ class Status : public QWidget void preamp1SwitchChanged(bool state); void preamp2SwitchChanged(bool state); void resetRateClicked(); - void triggerSelectionChanged(GPIO_PIN signal); + void triggerSelectionChanged(GPIO_SIGNAL signal); public slots: void onGpioRatesReceived(quint8 whichrate, QVector rates); @@ -44,7 +44,7 @@ public slots: void onTemperatureReceived(float value); void clearPulseHeightHisto(); void clearRatePlot(); - void onTriggerSelectionReceived(GPIO_PIN signal); + void onTriggerSelectionReceived(GPIO_SIGNAL signal); void onTimepulseReceived(); void onMqttStatusChanged(bool connected); diff --git a/source/gui/src/mainwindow.cpp b/source/gui/src/mainwindow.cpp index c2be3e2b..27c974c1 100644 --- a/source/gui/src/mainwindow.cpp +++ b/source/gui/src/mainwindow.cpp @@ -41,7 +41,7 @@ MainWindow::MainWindow(QWidget *parent) : qRegisterMetaType("CalibStruct"); qRegisterMetaType>("std::vector"); qRegisterMetaType("UbxTimePulseStruct"); - qRegisterMetaType("GPIO_PIN"); + qRegisterMetaType("GPIO_SIGNAL"); qRegisterMetaType("GnssMonHwStruct"); qRegisterMetaType("GnssMonHw2Struct"); qRegisterMetaType("UbxTimeMarkStruct"); @@ -301,7 +301,7 @@ void MainWindow::makeConnection(QString ipAddress, quint16 port) { tcpThread->start(); } -void MainWindow::onTriggerSelectionChanged(GPIO_PIN signal) +void MainWindow::onTriggerSelectionChanged(GPIO_SIGNAL signal) { TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); *(tcpMessage.dStream) << signal; @@ -401,7 +401,7 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { // if (msgID == gpioPinSig) { unsigned int gpioPin; *(tcpMessage.dStream) >> gpioPin; - receivedGpioRisingEdge((GPIO_PIN)gpioPin); + receivedGpioRisingEdge((GPIO_SIGNAL)gpioPin); return; } if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE) { @@ -458,7 +458,7 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER){ unsigned int signal; *(tcpMessage.dStream) >> signal; - emit triggerSelectionReceived((GPIO_PIN)signal); + emit triggerSelectionReceived((GPIO_SIGNAL)signal); //updateUiProperties(); return; } @@ -897,7 +897,7 @@ void MainWindow::sendRequestGpioRateBuffer(){ emit sendTcpMessage(andRateRequest); } -void MainWindow::receivedGpioRisingEdge(GPIO_PIN pin) { +void MainWindow::receivedGpioRisingEdge(GPIO_SIGNAL pin) { if (pin == EVT_AND) { ui->ANDHit->setStyleSheet("QLabel {background-color: darkGreen;}"); andTimer.start(); diff --git a/source/gui/src/parametermonitorform.cpp b/source/gui/src/parametermonitorform.cpp index 881472cc..7c37c405 100644 --- a/source/gui/src/parametermonitorform.cpp +++ b/source/gui/src/parametermonitorform.cpp @@ -58,7 +58,7 @@ void ParameterMonitorForm::on_timingSelectionComboBox_currentIndexChanged(int in void ParameterMonitorForm::on_adcTriggerSelectionComboBox_currentIndexChanged(int index) { for (auto signalIt=GPIO_SIGNAL_MAP.begin(); signalIt!=GPIO_SIGNAL_MAP.end(); ++signalIt) { - const GPIO_PIN signalId=signalIt.key(); + const GPIO_SIGNAL signalId=signalIt.key(); if (GPIO_SIGNAL_MAP[signalId].name==ui->adcTriggerSelectionComboBox->itemText(index)) { emit triggerSelectionChanged(signalId); return; @@ -197,7 +197,7 @@ void ParameterMonitorForm::onPreampSwitchReceived(uint8_t channel, bool state) else if (channel==1) ui->preamp2EnCheckBox->setChecked(state); } -void ParameterMonitorForm::onTriggerSelectionReceived(GPIO_PIN signal) +void ParameterMonitorForm::onTriggerSelectionReceived(GPIO_SIGNAL signal) { //if (GPIO_PIN_NAMES.find(signal)==GPIO_PIN_NAMES.end()) return; int i=0; diff --git a/source/gui/src/status.cpp b/source/gui/src/status.cpp index e074dbdd..7630a694 100644 --- a/source/gui/src/status.cpp +++ b/source/gui/src/status.cpp @@ -162,7 +162,7 @@ void Status::clearRatePlot() statusUi->ratePlot->plotAndSamples(andSamples); } -void Status::onTriggerSelectionReceived(GPIO_PIN signal) +void Status::onTriggerSelectionReceived(GPIO_SIGNAL signal) { // if (GPIO_PIN_NAMES.find(signal)==GPIO_PIN_NAMES.end()) return; int i=0; @@ -295,7 +295,7 @@ Status::~Status() void Status::on_triggerSelectionComboBox_currentIndexChanged(const QString &arg1) { for (auto signalIt=GPIO_SIGNAL_MAP.begin(); signalIt!=GPIO_SIGNAL_MAP.end(); ++signalIt) { - const GPIO_PIN signalId=signalIt.key(); + const GPIO_SIGNAL signalId=signalIt.key(); if (GPIO_SIGNAL_MAP[signalId].name==arg1) { emit triggerSelectionChanged(signalId); return; diff --git a/source/library/include/gpio_pin_definitions.h b/source/library/include/gpio_pin_definitions.h index c9b916f2..423800aa 100644 --- a/source/library/include/gpio_pin_definitions.h +++ b/source/library/include/gpio_pin_definitions.h @@ -1,5 +1,5 @@ -#ifndef GPIO_PIN_DEFINITIONS_H -#define GPIO_PIN_DEFINITIONS_H +#ifndef GPIO_SIGNAL_DEFINITIONS_H +#define GPIO_SIGNAL_DEFINITIONS_H #include "muondetector_shared_global.h" @@ -16,7 +16,7 @@ // of the RPi GPIO header. To be independent of the specific hardware implementation, // the pin numbers for these signals are defined in gpio_pin_mapping.h on the daemon side -enum GPIO_PIN { UBIAS_EN, +enum GPIO_SIGNAL { UBIAS_EN, PREAMP_1, PREAMP_2, EVT_AND, EVT_XOR, GAIN_HL, ADC_READY, @@ -39,7 +39,7 @@ struct GpioSignalDescriptor { // SIGNAL_POLARITY polarity; }; -static const QMap GPIO_SIGNAL_MAP = +static const QMap GPIO_SIGNAL_MAP = { { UBIAS_EN, { "UBIAS_EN", DIR_OUT } }, { PREAMP_1, { "PREAMP_1", DIR_OUT } }, { PREAMP_2, { "PREAMP_2", DIR_OUT } }, @@ -77,4 +77,4 @@ enum class TIMING_MUX_SELECTION : uint8_t { UNDEFINED = 255 }; -#endif // GPIO_PIN_DEFINITIONS_H +#endif // GPIO_SIGNAL_DEFINITIONS_H From d00fd6ffd7aa7149ad5c646d954b23c4674ffaf4 Mon Sep 17 00:00:00 2001 From: hangeza Date: Wed, 14 Jul 2021 02:09:13 +0200 Subject: [PATCH 11/47] fixed wrong position of default argument in constructor of i2cdevice class --- source/daemon/include/i2c/i2cdevices/i2cdevice.h | 2 +- source/daemon/src/i2c/i2cdevices/i2cdevice.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/source/daemon/include/i2c/i2cdevices/i2cdevice.h b/source/daemon/include/i2c/i2cdevices/i2cdevice.h index 8d579e8d..01c800cc 100644 --- a/source/daemon/include/i2c/i2cdevices/i2cdevice.h +++ b/source/daemon/include/i2c/i2cdevices/i2cdevice.h @@ -32,7 +32,7 @@ class i2cDevice { //using I2C_DEVICE_MODE; i2cDevice(); - i2cDevice(const char* busAddress); + i2cDevice(const char* busAddress = "/dev/i2c-1"); i2cDevice(uint8_t slaveAddress); i2cDevice(const char* busAddress, uint8_t slaveAddress); virtual ~i2cDevice(); diff --git a/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp b/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp index ebf6d1ac..1dc94ddf 100644 --- a/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp +++ b/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp @@ -26,7 +26,7 @@ i2cDevice::i2cDevice() { else fMode = MODE_FAILED; } -i2cDevice::i2cDevice(const char* busAddress = "/dev/i2c-1") { +i2cDevice::i2cDevice(const char* busAddress) { fNrBytesRead = 0; fNrBytesWritten = 0; fDebugLevel = DEFAULT_DEBUG_LEVEL; From ea0f327d3684a955f1f0835eb3d4eaa87bc88248 Mon Sep 17 00:00:00 2001 From: hangeza Date: Wed, 14 Jul 2021 02:56:10 +0200 Subject: [PATCH 12/47] added missing linkage against pthread in daemon.cmake --- source/cmake/daemon.cmake | 1 + 1 file changed, 1 insertion(+) diff --git a/source/cmake/daemon.cmake b/source/cmake/daemon.cmake index b8c19260..096e6a69 100644 --- a/source/cmake/daemon.cmake +++ b/source/cmake/daemon.cmake @@ -137,6 +137,7 @@ target_link_libraries(muondetector-daemon mosquitto muondetector-shared muondetector-shared-mqtt + pthread ) From 3c5eda7cbd63f3954e858979f398073b584128bf Mon Sep 17 00:00:00 2001 From: hangeza Date: Wed, 14 Jul 2021 09:27:45 +0200 Subject: [PATCH 13/47] Updated preinst script to add muonuser to gpio group. This is required for running the daemon with access to the gpio kernel subsystem. --- source/daemon/config/preinst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/daemon/config/preinst b/source/daemon/config/preinst index 99c26d3c..b0336912 100755 --- a/source/daemon/config/preinst +++ b/source/daemon/config/preinst @@ -1,6 +1,6 @@ #!/bin/bash -e mkdir -p /var/muondetector -useradd muonuser -g users -G dialout,pi,i2c,users -s /usr/sbin/nologin -r -N -M -b /var/muondetector || echo "User already exists" +useradd muonuser -g users -G dialout,pi,i2c,users,gpio -s /usr/sbin/nologin -r -N -M -b /var/muondetector || adduser muonuser gpio chown muonuser:users /var/muondetector chmod g+w /var/muondetector From 0af25640ed880ff9f534aa78601f11be20a42f17 Mon Sep 17 00:00:00 2001 From: hangeza Date: Fri, 16 Jul 2021 01:50:32 +0200 Subject: [PATCH 14/47] - modified all control scripts for prerequisites etc. wrt libgpiod - added measurement of time pulse to system time --- source/cmake/daemon.cmake | 2 - source/daemon/config/conffiles | 1 - .../daemon/config/muondetector-daemon.service | 4 +- source/daemon/config/postinst | 1 - source/daemon/include/daemon.h | 2 +- source/daemon/include/pigpiodhandler.h | 4 +- source/daemon/include/ratebuffer.h | 5 +- source/daemon/src/daemon.cpp | 49 ++++++++----------- source/daemon/src/pigpiodhandler.cpp | 8 +-- source/daemon/src/ratebuffer.cpp | 21 ++++++++ 10 files changed, 54 insertions(+), 43 deletions(-) diff --git a/source/cmake/daemon.cmake b/source/cmake/daemon.cmake index 096e6a69..aad33119 100644 --- a/source/cmake/daemon.cmake +++ b/source/cmake/daemon.cmake @@ -172,7 +172,6 @@ install(PROGRAMS ${MUONDETECTOR_LOGIN_INSTALL_FILES} DESTINATION bin COMPONENT d if (MUONDETECTOR_BUILD_GUI) -set(CPACK_DEBIAN_DAEMON_PACKAGE_DEPENDS "pigpiod") set(CPACK_DEBIAN_DAEMON_PACKAGE_CONTROL_EXTRA "${MUONDETECTOR_DAEMON_CONFIG_DIR}/preinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/postinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/prerm;${MUONDETECTOR_DAEMON_CONFIG_DIR}/conffiles") set(CPACK_DEBIAN_DAEMON_PACKAGE_SECTION "net") set(CPACK_DEBIAN_DAEMON_DESCRIPTION " Daemon that controls the muon detector board. @@ -182,7 +181,6 @@ set(CPACK_DEBIAN_DAEMON_DESCRIPTION " Daemon that controls the muon detector boa set(CPACK_COMPONENT_DAEMON_DESCRIPTION "${CPACK_DEBIAN_DAEMON_DESCRIPTION}") set(CPACK_DEBIAN_DAEMON_PACKAGE_NAME "muondetector-daemon") else () -set(CPACK_DEBIAN_PACKAGE_DEPENDS "pigpiod") set(CPACK_DEBIAN_PACKAGE_CONTROL_EXTRA "${MUONDETECTOR_DAEMON_CONFIG_DIR}/preinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/postinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/prerm;${MUONDETECTOR_DAEMON_CONFIG_DIR}/conffiles") set(CPACK_DEBIAN_PACKAGE_SECTION "net") set(CPACK_DEBIAN_PACKAGE_DESCRIPTION " Daemon that controls the muon detector board. diff --git a/source/daemon/config/conffiles b/source/daemon/config/conffiles index 191005ce..b5512dec 100644 --- a/source/daemon/config/conffiles +++ b/source/daemon/config/conffiles @@ -1,2 +1 @@ /etc/muondetector/muondetector.conf -/etc/systemd/system/pigpiod.service.d/pigpiod.conf diff --git a/source/daemon/config/muondetector-daemon.service b/source/daemon/config/muondetector-daemon.service index 05b25c39..67b79369 100644 --- a/source/daemon/config/muondetector-daemon.service +++ b/source/daemon/config/muondetector-daemon.service @@ -1,8 +1,6 @@ [Unit] Description=muondetector-daemon - Daemon for custom muondetector board -Requires=pigpiod.service -BindsTo=pigpiod.service -After=pigpiod.service sockets.target +After=sockets.target [Service] Type=simple diff --git a/source/daemon/config/postinst b/source/daemon/config/postinst index 61eade5f..af7be275 100755 --- a/source/daemon/config/postinst +++ b/source/daemon/config/postinst @@ -1,3 +1,2 @@ #!/bin/bash -e -deb-systemd-helper enable pigpiod.service deb-systemd-helper enable muondetector-daemon.service diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index 88c9a131..e56d4167 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -279,7 +279,7 @@ private slots: Adafruit_SSD1306* oled = nullptr; float biasVoltage = 0.; bool biasON = false; - GPIO_SIGNAL eventTrigger; + GPIO_SIGNAL eventTrigger { UNDEFINED_PIN }; bool gainSwitch = false; bool preampStatus[2]; uint8_t pcaPortMask = 0; diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index eff1ff06..e1d265d1 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -58,9 +58,9 @@ class PigpiodHandler : public QObject signals: void signal(uint8_t gpio_pin); - void samplingTrigger(); + //void samplingTrigger(); //void eventInterval(quint64 nsecs); - void timePulseDiff(qint32 usecs); + //void timePulseDiff(qint32 usecs); public slots: void start(); diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h index ea9e96f7..651c0fd9 100644 --- a/source/daemon/include/ratebuffer.h +++ b/source/daemon/include/ratebuffer.h @@ -39,9 +39,12 @@ class RateBuffer : public QObject [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; + [[nodiscard]] auto lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds; + [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> std::chrono::time_point; signals: - void throttledSignal(unsigned int gpio); + void throttledSignal( unsigned int gpio ); + void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ); public slots: void onSignal(unsigned int gpio); diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index d9e8ba86..e99d0d32 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -560,8 +560,8 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n preampStatus[1]=preamp2; gainSwitch=gain; biasON = bias_ON; -// eventTrigger = (GPIO_SIGNAL)new_eventTrigger; - eventTrigger = UNDEFINED_PIN; + eventTrigger = (GPIO_SIGNAL)new_eventTrigger; +// eventTrigger = UNDEFINED_PIN; polarity1=new_polarity1; polarity2=new_polarity2; @@ -746,30 +746,22 @@ void Daemon::connectToPigpiod(){ connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); // connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); -// connect(pigHandler, &PigpiodHandler::samplingTrigger, this, &Daemon::sampleAdc0Event); -/* - connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) - { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { - checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); - histoMap["gpioEventInterval"].fill(1e-6*nsecs); - } - } ); - - connect(pigHandler, &PigpiodHandler::eventInterval, this, [this](quint64 nsecs) - { if (histoMap.find("gpioEventIntervalShort")!=histoMap.end()) { - if (nsecs/1000<=histoMap["gpioEventIntervalShort"].getMax()) - histoMap["gpioEventIntervalShort"].fill((double)nsecs/1000.); +// connect(pigHandler, &PigpiodHandler::timePulseDiff, this, [this](qint32 usecs) + + // TODO: handling of TP to sys time difference + connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](unsigned int gpio) + { + if ( gpio != GPIO_PINMAP[TIMEPULSE] ) return; + auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); + usecs = usecs % 1000000LL; + if (histoMap.find("TPTimeDiff") != histoMap.end()) { + checkRescaleHisto(histoMap["TPTimeDiff"], usecs); + histoMap["TPTimeDiff"].fill((double)usecs); } + qDebug()<<"TP time diff:"<setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); @@ -1486,10 +1478,10 @@ void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) { void Daemon::onGpioPinEvent(uint8_t gpio) { // reverse lookup of gpio function from given pin (first occurence) auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) - { return item.second==gpio; } + { return item.second == gpio; } ); - if (result!=GPIO_PINMAP.end()) { - if ( gpio == pigHandler->samplingTriggerSignal ) { + if (result != GPIO_PINMAP.end()) { + if ( result->first == eventTrigger ) { emit eventInterval( rateBuffer.lastInterval(gpio).count() ); /* if (user_gpio == GPIO_PINMAP[pigpioHandler->samplingTriggerSignal]){ @@ -1566,7 +1558,7 @@ void Daemon::sendPcaChannel(){ void Daemon::sendEventTriggerSelection(){ if (pigHandler==nullptr) return; TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); - *(tcpMessage.dStream) << bcmToGpioSignal(pigHandler->samplingTriggerSignal); + *(tcpMessage.dStream) << eventTrigger; emit sendTcpMessage(tcpMessage); } @@ -1765,6 +1757,7 @@ void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) { } //emit setSamplingTriggerSignal(signal); emit setSamplingTriggerSignal( it->second ); + eventTrigger = signal; emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); //sendEventTriggerSelection(); } diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index 32b9423f..ba473447 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -257,12 +257,12 @@ void PigpiodHandler::threadLoop() { const struct timespec timeout { 0, 100000000UL }; gpiod_line_bulk event_bulk { }; int ret = gpiod_line_event_wait_bulk(&fInterruptLineBulk, &timeout, &event_bulk); - if ( ret>0 ) { + if ( ret > 0 ) { unsigned int line_index = 0; while ( line_index < event_bulk.num_lines ) { gpiod_line_event event { }; - int ret = gpiod_line_event_read( event_bulk.lines[line_index], &event); - if ( ret == 0 ) { + int result = gpiod_line_event_read( event_bulk.lines[line_index], &event); + if ( result == 0 ) { unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); std::uint64_t ns = event.ts.tv_sec*1e9 + event.ts.tv_nsec; emit signal(gpio); @@ -401,7 +401,7 @@ bool PigpiodHandler::setPinState(unsigned int gpio, bool state) { void PigpiodHandler::setSamplingTriggerSignal(unsigned int gpio) { - // The following code registers the given gpio pin for interrupt, if not already done before. The previously setInterval + // The following code registers the given gpio pin for interrupt, if not already done before. The previously set // samplingTrigger is NOT unregistered, since several interrupt functions can occupy one gpio line. // When unregistering the samplingTrigger, the pin would cease to funtion as interrupt source for the alternative function. // Example: XOR is an interrupt input and can also be selected as sampling trigger by the user for a time. diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp index f471bf80..2509bb29 100644 --- a/source/daemon/src/ratebuffer.cpp +++ b/source/daemon/src/ratebuffer.cpp @@ -1,6 +1,8 @@ #include #include +constexpr auto invalid_time = std::chrono::steady_clock::time_point::min(); + RateBuffer::RateBuffer(QObject *parent) : QObject(parent) { @@ -40,6 +42,9 @@ void RateBuffer::onSignal(unsigned int gpio) { } buffermap[gpio].eventbuffer.push(now); emit throttledSignal(gpio); + if ( buffermap[gpio].last_interval != std::chrono::nanoseconds(0) ) { + emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); + } } auto RateBuffer::avgRate(unsigned int gpio) const -> double @@ -68,3 +73,19 @@ auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanosecon return it->second.last_interval; } +auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds +{ + auto it1 = buffermap.find(gpio1); + if ( it1 == buffermap.end() || it1->second.eventbuffer.empty() ) return std::chrono::nanoseconds(0); + auto it2 = buffermap.find(gpio2); + if ( it2 == buffermap.end() || it2->second.eventbuffer.empty() ) return std::chrono::nanoseconds(0); + return std::chrono::duration_cast( it2->second.eventbuffer.back() - it1->second.eventbuffer.back() ); +} + +auto RateBuffer::lastEventTime(unsigned int gpio) const -> std::chrono::time_point +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; + return it->second.eventbuffer.back(); +} + From 2b6697b7bda5e87d76dc1b21994f1a7085b14bab Mon Sep 17 00:00:00 2001 From: hangeza Date: Fri, 16 Jul 2021 03:20:58 +0200 Subject: [PATCH 15/47] adjust measured TPDiff values symmetrically around 0, i.e. to fall in the range -0.5s...+0.5s, instead of 0...1s as before --- source/daemon/src/daemon.cpp | 63 +++++++++++++++++------------------- 1 file changed, 30 insertions(+), 33 deletions(-) diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index e99d0d32..ac771246 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -650,7 +650,21 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n } } ); - // establish ublox gnss module connection +/* + // TODO: handling of TP to sys time difference + connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](unsigned int gpio) + { + if ( gpio != GPIO_PINMAP[TIMEPULSE] ) return; + auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); + usecs = usecs % 1000000LL; + if (histoMap.find("TPTimeDiff") != histoMap.end()) { + checkRescaleHisto(histoMap["TPTimeDiff"], usecs); + histoMap["TPTimeDiff"].fill((double)usecs); + } + qDebug()<<"TP time diff:"<(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); - usecs = usecs % 1000000LL; - if (histoMap.find("TPTimeDiff") != histoMap.end()) { - checkRescaleHisto(histoMap["TPTimeDiff"], usecs); - histoMap["TPTimeDiff"].fill((double)usecs); - } - qDebug()<<"TP time diff:"<setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); @@ -1482,25 +1482,22 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { ); if (result != GPIO_PINMAP.end()) { if ( result->first == eventTrigger ) { - emit eventInterval( rateBuffer.lastInterval(gpio).count() ); -/* - if (user_gpio == GPIO_PINMAP[pigpioHandler->samplingTriggerSignal]){ - if (pigpioHandler->lastSamplingTime.msecsTo(now) >= MuonPi::Config::Hardware::ADC::deadtime) { - emit pigpioHandler->samplingTrigger(); - pigpioHandler->lastSamplingTime = now; - } - quint64 nsecsElapsed=pigpioHandler->elapsedEventTimer.nsecsElapsed(); - pigpioHandler->elapsedEventTimer.start(); - //emit pigpioHandler->eventInterval(nsecsElapsed); - emit pigpioHandler->eventInterval((tick-lastTriggerTick)*1000); - lastTriggerTick=tick; - } -*/ - - - - + auto nsecs = rateBuffer.lastInterval(gpio).count(); + if ( nsecs > 0 ) { + emit eventInterval( rateBuffer.lastInterval(gpio).count() ); + } emit sampleAdc0Event(); + } else if ( result->first == TIMEPULSE) { + auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); + usecs = usecs % 1000000LL; + if ( usecs > 500000L ) { + usecs -= 1000000LL; + } + if (histoMap.find("TPTimeDiff") != histoMap.end()) { + checkRescaleHisto(histoMap["TPTimeDiff"], usecs); + histoMap["TPTimeDiff"].fill((double)usecs); + } + qDebug()<<"TP time diff:"<first); } From d4fb9e1a590dc54060f1f637ecc4ce512d030b8f Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:06:36 +0200 Subject: [PATCH 16/47] Update source/daemon/include/daemon.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/daemon.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index e56d4167..12358635 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -110,7 +110,6 @@ struct RateScanInfo { }; struct RateScan { -// void addScanPoint(double scanpar, double a_rate) { scanMap[scanpar].append(a_rate); } uint8_t origPcaMask=0; GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_PIN; float origScanPar=3.3; From 98f4d8c7e6e7fe3143f701371f7c6c4c8ba8dbf5 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:06:50 +0200 Subject: [PATCH 17/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index e1d265d1..85696fea 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -46,7 +46,6 @@ class PigpiodHandler : public QObject // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; -// GPIO_SIGNAL samplingTriggerSignal=EVT_XOR; unsigned int samplingTriggerSignal { UNDEFINED_GPIO }; double clockMeasurementSlope=0.; From 59cdb105dc0efbaa8faf2231619dfcd26fca1484 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:07:05 +0200 Subject: [PATCH 18/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 85696fea..18896782 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -57,9 +57,6 @@ class PigpiodHandler : public QObject signals: void signal(uint8_t gpio_pin); - //void samplingTrigger(); - //void eventInterval(quint64 nsecs); - //void timePulseDiff(qint32 usecs); public slots: void start(); From 8732af154a2278df93dabc243130c47349a4d35f Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:07:16 +0200 Subject: [PATCH 19/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 18896782..5005f26d 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -68,7 +68,6 @@ public slots: bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); bool setPinState(unsigned int gpio, bool state); void setSamplingTriggerSignal(unsigned int gpio); -// void setSamplingTriggerSignal(GPIO_SIGNAL signalName) { samplingTriggerSignal=signalName; } bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); void setInhibited(bool inh=true) { inhibit=inh; } From 4b209bedc9a49c5b12dd7832c5f3dbefb482b943 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:07:29 +0200 Subject: [PATCH 20/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 5005f26d..70e55a83 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -98,7 +98,6 @@ public slots: bool inhibit=false; int verbose=0; gpiod_chip* fChip { nullptr }; -// std::shared_ptr fChip { nullptr }; std::map fInterruptLineMap { }; // std::map> fInterruptLineMap { }; gpiod_line_bulk fInterruptLineBulk; From 1db133c30123757ebfbe4283bb1cd715f9bbc6c7 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:07:46 +0200 Subject: [PATCH 21/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 70e55a83..564f737a 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -99,7 +99,6 @@ public slots: int verbose=0; gpiod_chip* fChip { nullptr }; std::map fInterruptLineMap { }; -// std::map> fInterruptLineMap { }; gpiod_line_bulk fInterruptLineBulk; std::map fLineMap { }; // std::map> fLineMap { }; From 207dd0fa9b090ac50592ff6e5a38a614872a4be8 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:01 +0200 Subject: [PATCH 22/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 1 - 1 file changed, 1 deletion(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 564f737a..c8b76681 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -101,7 +101,6 @@ public slots: std::map fInterruptLineMap { }; gpiod_line_bulk fInterruptLineBulk; std::map fLineMap { }; -// std::map> fLineMap { }; bool fThreadRunning { false }; std::unique_ptr fThread { nullptr }; std::mutex fMutex; From d7c1136add859db30e3b1af6071d66e95c609262 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:20 +0200 Subject: [PATCH 23/47] Update source/daemon/include/pigpiodhandler.h MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/include/pigpiodhandler.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index c8b76681..444095eb 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -104,12 +104,6 @@ public slots: bool fThreadRunning { false }; std::unique_ptr fThread { nullptr }; std::mutex fMutex; -/* - gpiod::chip fChip; - gpiod::line_bulk fInterruptLineBulk; - std::map fLineMap; -*/ -// QVector gpioPins; }; From 750d0f2b74ac4dd015acda38236a9505731da0dc Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:28 +0200 Subject: [PATCH 24/47] Update source/daemon/src/ratebuffer.cpp MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/src/ratebuffer.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp index 2509bb29..1941a16c 100644 --- a/source/daemon/src/ratebuffer.cpp +++ b/source/daemon/src/ratebuffer.cpp @@ -26,7 +26,6 @@ void RateBuffer::onSignal(unsigned int gpio) { auto last_event_time = buffermap[gpio].eventbuffer.back(); buffermap[gpio].last_interval = std::chrono::duration_cast( now - last_event_time ); if ( now - last_event_time < MAX_DEADTIME ) { -// std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< std::chrono::time_poi if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; return it->second.eventbuffer.back(); } - From 98dd05a5b67ee1ab27ad074fe492aded134975de Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:34 +0200 Subject: [PATCH 25/47] Update source/gui/src/mainwindow.cpp MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/gui/src/mainwindow.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/source/gui/src/mainwindow.cpp b/source/gui/src/mainwindow.cpp index 33df100b..247206af 100644 --- a/source/gui/src/mainwindow.cpp +++ b/source/gui/src/mainwindow.cpp @@ -395,7 +395,6 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { // quint16 msgID = tcpMessage.getMsgID(); TCP_MSG_KEY msgID = static_cast(tcpMessage.getMsgID()); if (msgID == TCP_MSG_KEY::MSG_GPIO_EVENT) { -// if (msgID == gpioPinSig) { unsigned int gpioPin; *(tcpMessage.dStream) >> gpioPin; receivedGpioRisingEdge((GPIO_SIGNAL)gpioPin); @@ -1289,4 +1288,3 @@ void MainWindow::onPolarityChanged(bool pol1, bool pol2){ emit sendTcpMessage(tcpMessage); } - From 23340b18304ce588443b5a091393459eb926b563 Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:42 +0200 Subject: [PATCH 26/47] Update source/gui/src/parametermonitorform.cpp MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/gui/src/parametermonitorform.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/source/gui/src/parametermonitorform.cpp b/source/gui/src/parametermonitorform.cpp index 6edc4f52..73d9257f 100644 --- a/source/gui/src/parametermonitorform.cpp +++ b/source/gui/src/parametermonitorform.cpp @@ -191,7 +191,6 @@ void ParameterMonitorForm::onPreampSwitchReceived(uint8_t channel, bool state) void ParameterMonitorForm::onTriggerSelectionReceived(GPIO_SIGNAL signal) { - //if (GPIO_PIN_NAMES.find(signal)==GPIO_PIN_NAMES.end()) return; int i=0; while (iadcTriggerSelectionComboBox->count()) { if (ui->adcTriggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name)==0) break; From 40b75124a585f09ee41a15ee7574c7633525d18e Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:08:54 +0200 Subject: [PATCH 27/47] Update source/gui/src/status.cpp MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/gui/src/status.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/source/gui/src/status.cpp b/source/gui/src/status.cpp index 7630a694..8ddb4d53 100644 --- a/source/gui/src/status.cpp +++ b/source/gui/src/status.cpp @@ -164,7 +164,6 @@ void Status::clearRatePlot() void Status::onTriggerSelectionReceived(GPIO_SIGNAL signal) { -// if (GPIO_PIN_NAMES.find(signal)==GPIO_PIN_NAMES.end()) return; int i=0; while (itriggerSelectionComboBox->count()) { if (statusUi->triggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name)==0) break; From 4016e1bbb0e95601fb4d347bc358de64386ee84d Mon Sep 17 00:00:00 2001 From: Hans-Georg Zaunick <40604124+hangeza@users.noreply.github.com> Date: Fri, 16 Jul 2021 10:14:28 +0200 Subject: [PATCH 28/47] Update source/daemon/config/preinst MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Daniel Treffenstädt <52167116+dtreffenstaedt@users.noreply.github.com> --- source/daemon/config/preinst | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/source/daemon/config/preinst b/source/daemon/config/preinst index b0336912..9a68b77a 100755 --- a/source/daemon/config/preinst +++ b/source/daemon/config/preinst @@ -1,6 +1,12 @@ #!/bin/bash -e mkdir -p /var/muondetector -useradd muonuser -g users -G dialout,pi,i2c,users,gpio -s /usr/sbin/nologin -r -N -M -b /var/muondetector || adduser muonuser gpio +if id muonuser &> /dev/null; then + # transitional code until all older versions of muondetector-daemon are updated. + echo "muonuser exists, adding to group gpio." + adduser muonuser gpio +else + useradd muonuser -g users -G dialout,pi,i2c,users,gpio -s /usr/sbin/nologin -r -N -M -b /var/muondetector + fi chown muonuser:users /var/muondetector chmod g+w /var/muondetector From ad7e129b7f264c35633c1b861a78bb37166b8a3d Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 18 Jul 2021 11:48:14 +0200 Subject: [PATCH 29/47] Some clean-up and minor mods: - removed separate the samplingTrigger handling in PigpiodHandler - merged slots for gpio events in daemon into one onGpioPinEvent() slot - removed unregistering interrupts in PigpiodHandler before registering them again. This would be the cleanest procedure but somehow it doesn't work from gpiod side --- source/daemon/include/daemon.h | 9 +-- source/daemon/include/gpio_mapping.h | 8 +-- source/daemon/include/pigpiodhandler.h | 4 +- source/daemon/src/daemon.cpp | 72 +++++++++---------- source/daemon/src/pigpiodhandler.cpp | 68 +++++++++--------- source/library/include/gpio_pin_definitions.h | 13 ++-- 6 files changed, 81 insertions(+), 93 deletions(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index 12358635..f03b205d 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -32,7 +32,7 @@ struct CalibStruct; struct UbxTimeMarkStruct; -enum GPIO_SIGNAL; +//enum GPIO_SIGNAL; class Property { public: @@ -97,7 +97,7 @@ class Property { struct RateScanInfo { uint8_t origPcaMask=0; - GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_PIN; + GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_SIGNAL; uint16_t lastEvtCounter=0; uint8_t thrChannel=0; float origThr=3.3; @@ -110,8 +110,9 @@ struct RateScanInfo { }; struct RateScan { +// void addScanPoint(double scanpar, double a_rate) { scanMap[scanpar].append(a_rate); } uint8_t origPcaMask=0; - GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_PIN; + GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_SIGNAL; float origScanPar=3.3; double minScanPar=0.; double maxScanPar=1.; @@ -278,7 +279,7 @@ private slots: Adafruit_SSD1306* oled = nullptr; float biasVoltage = 0.; bool biasON = false; - GPIO_SIGNAL eventTrigger { UNDEFINED_PIN }; + GPIO_SIGNAL eventTrigger { UNDEFINED_SIGNAL }; bool gainSwitch = false; bool preampStatus[2]; uint8_t pcaPortMask = 0; diff --git a/source/daemon/include/gpio_mapping.h b/source/daemon/include/gpio_mapping.h index 34503262..432fb49f 100644 --- a/source/daemon/include/gpio_mapping.h +++ b/source/daemon/include/gpio_mapping.h @@ -7,11 +7,9 @@ #define MAX_HW_VER 3 -// define pins on the raspberry pi, UBIAS_EN is the power on/off pin for bias voltage -// PREAMP_1/2 enables the DC voltage to power the preamp through the signal cable +// Mapping between signals of the MuonPi hardware interface and the actual GPIO pins of the RaspberryPi // ATTENTION: -// TO MAKE IT MORE SIMPLE THERE WILL BE ONLY PIGPIO NAMING STANDARD, -// NO WIRING PI FROM NOW +// All pins are numbered according to the BCM designation static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] = { { @@ -80,7 +78,7 @@ extern std::map GPIO_PINMAP; inline GPIO_SIGNAL bcmToGpioSignal(unsigned int bcmGpioNumber) { std::map::const_iterator i = GPIO_PINMAP.cbegin(); while (i != GPIO_PINMAP.cend() && i->second!=bcmGpioNumber) ++i; - if (i==GPIO_PINMAP.cend()) return UNDEFINED_PIN; + if (i==GPIO_PINMAP.cend()) return UNDEFINED_SIGNAL; return i->first; } diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 444095eb..855bf65a 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -46,7 +46,7 @@ class PigpiodHandler : public QObject // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; - unsigned int samplingTriggerSignal { UNDEFINED_GPIO }; +// unsigned int samplingTriggerSignal { UNDEFINED_GPIO }; double clockMeasurementSlope=0.; double clockMeasurementOffset=0.; @@ -67,7 +67,7 @@ public slots: bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); bool setPinState(unsigned int gpio, bool state); - void setSamplingTriggerSignal(unsigned int gpio); +// void setSamplingTriggerSignal(unsigned int gpio); bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); void setInhibited(bool inh=true) { inhibit=inh; } diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index ac771246..7604e9f5 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -561,7 +561,7 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n gainSwitch=gain; biasON = bias_ON; eventTrigger = (GPIO_SIGNAL)new_eventTrigger; -// eventTrigger = UNDEFINED_PIN; +// eventTrigger = UNDEFINED_SIGNAL; polarity1=new_polarity1; polarity2=new_polarity2; @@ -650,20 +650,6 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n } } ); -/* - // TODO: handling of TP to sys time difference - connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](unsigned int gpio) - { - if ( gpio != GPIO_PINMAP[TIMEPULSE] ) return; - auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); - usecs = usecs % 1000000LL; - if (histoMap.find("TPTimeDiff") != histoMap.end()) { - checkRescaleHisto(histoMap["TPTimeDiff"], usecs); - histoMap["TPTimeDiff"].fill((double)usecs); - } - qDebug()<<"TP time diff:"< gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], - GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); + GPIO_PINMAP[TIMEPULSE] }); pigHandler = new PigpiodHandler(gpio_pins); //tdc7200 = new TDC7200(GPIO_PINMAP[TDC_INTB]); pigThread = new QThread(); @@ -762,12 +748,6 @@ void Daemon::connectToPigpiod(){ // connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); // connect(pigHandler, &PigpiodHandler::timePulseDiff, this, [this](qint32 usecs) - auto it=GPIO_PINMAP.find(eventTrigger); - if (it != GPIO_PINMAP.end()) { - pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); - } - connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); - struct timespec ts_res; clock_getres(CLOCK_REALTIME, &ts_res); if (verbose>3) { @@ -781,7 +761,10 @@ void Daemon::connectToPigpiod(){ //connect(this, &Daemon::aboutToQuit, [this](){this->toConsole("aboutToQuit called and signal emitted\n");}); timespec_get(&lastRateInterval, TIME_UTC); startOfProgram = lastRateInterval; - connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin){ + +// TODO: delete following block +/* + connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin){ // connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](uint8_t gpio_pin){ rateCounterIntervalActualisation(); if (gpio_pin==GPIO_PINMAP[EVT_XOR]){ @@ -798,6 +781,7 @@ void Daemon::connectToPigpiod(){ //andCounts.push_back(value); } }); + */ pigThread->start(); rateBufferReminder.setInterval(rateBufferInterval); rateBufferReminder.setSingleShot(false); @@ -817,6 +801,12 @@ void Daemon::connectToPigpiod(){ emit GpioSetState(GPIO_PINMAP[STATUS2], 0); emit GpioSetPullUp(GPIO_PINMAP[ADC_READY]); emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], PigpiodHandler::EventEdge::RisingEdge); + auto it=GPIO_PINMAP.find(eventTrigger); + if (it != GPIO_PINMAP.end()) { +// pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); + emit GpioRegisterForCallback(GPIO_PINMAP[eventTrigger], PigpiodHandler::EventEdge::RisingEdge); + } +// connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); if (HW_VERSION>1) { //emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); @@ -1481,13 +1471,7 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { { return item.second == gpio; } ); if (result != GPIO_PINMAP.end()) { - if ( result->first == eventTrigger ) { - auto nsecs = rateBuffer.lastInterval(gpio).count(); - if ( nsecs > 0 ) { - emit eventInterval( rateBuffer.lastInterval(gpio).count() ); - } - emit sampleAdc0Event(); - } else if ( result->first == TIMEPULSE) { + if ( result->first == TIMEPULSE) { auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); usecs = usecs % 1000000LL; if ( usecs > 500000L ) { @@ -1497,9 +1481,22 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { checkRescaleHisto(histoMap["TPTimeDiff"], usecs); histoMap["TPTimeDiff"].fill((double)usecs); } - qDebug()<<"TP time diff:"<2) qDebug()<<"TP time diff:"<first == EVT_XOR || result->first == EVT_AND ) { + rateCounterIntervalActualisation(); + if ( result->first == EVT_XOR ) { + xorCounts.back()++; + } else if ( result->first == EVT_AND ) { + andCounts.back()++; + } + } + if ( result->first == eventTrigger ) { + auto nsecs = rateBuffer.lastInterval(gpio).count(); + if ( nsecs > 0 ) { + emit eventInterval( rateBuffer.lastInterval(gpio).count() ); + } + emit sampleAdc0Event(); } - //emit sendGpioPinEvent((GPIO_SIGNAL)result->first); } } @@ -1745,18 +1742,15 @@ void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) { if (pigHandler==nullptr) return; auto it=GPIO_PINMAP.find(signal); if (it==GPIO_PINMAP.end()) { - emit setSamplingTriggerSignal( PigpiodHandler::UNDEFINED_GPIO ); return; } - if (verbose > 0){ - qInfo() << "changed event selection to signal " << (unsigned int)signal; + if ( verbose > 0 ){ + qInfo() << "changed event selection to signal" << GPIO_SIGNAL_MAP[signal].name; } - //emit setSamplingTriggerSignal(signal); - emit setSamplingTriggerSignal( it->second ); + emit GpioRegisterForCallback( it->second, PigpiodHandler::EventEdge::RisingEdge ); eventTrigger = signal; emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); - //sendEventTriggerSelection(); } // ALL FUNCTIONS ABOUT SETTINGS FOR THE I2C-DEVICES (DAC, ADC, PCA...) @@ -2520,7 +2514,7 @@ void Daemon::onLogParameterPolled(){ } if (pca && pca->devicePresent()) emit logParameter(LogParameter("ubxInputSwitch", "0x"+QString::number(pcaPortMask,16), LogParameter::LOG_ON_CHANGE)); - if (pigHandler!=nullptr) emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)bcmToGpioSignal(pigHandler->samplingTriggerSignal),16), LogParameter::LOG_ON_CHANGE)); + if (pigHandler!=nullptr) emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)eventTrigger,16), LogParameter::LOG_ON_CHANGE)); //logBiasValues(); if (adc && !(adc->getStatus() & i2cDevice::MODE_UNREACHABLE)) { /* diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index ba473447..de03f72e 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -11,9 +11,9 @@ #include -static int pi = -1; +//static int pi = -1; static int spiHandle = -1; -static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed +//static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed constexpr char CONSUMER[] = "muonpi"; const std::string chipname { "/dev/gpiochip0" }; @@ -198,9 +198,6 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *pare startOfProgram = QDateTime::currentDateTimeUtc(); lastSamplingTime = startOfProgram; elapsedEventTimer.start(); - pigHandlerAddress = this; - -// std::string chipname { "/dev/gpiochip0" }; fChip = gpiod_chip_open(chipname.c_str()); if ( fChip == nullptr ) { @@ -265,6 +262,7 @@ void PigpiodHandler::threadLoop() { if ( result == 0 ) { unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); std::uint64_t ns = event.ts.tv_sec*1e9 + event.ts.tv_nsec; + std::chrono::time_point timestamp(std::chrono::nanoseconds(ns)); emit signal(gpio); if ( verbose > 2 ) { qDebug()<<"line event: gpio"<stop(); @@ -430,24 +412,39 @@ bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { if (!isInitialised) return false; auto it = fInterruptLineMap.find(gpio); if (it != fInterruptLineMap.end()) { - // line object exists, release previous line request + // line object exists + // The following code block shall release the previous line request + // and re-request this line for events. + // It is bypassed, since it does not work as intended. + // The function simply does nothing in this case. + return false; gpiod_line_release(it->second); + if ( gpiod_line_update(it->second) < 0 ) { + qCritical()<<"update of gpio line" << gpio << "after release failed"; + //return false; + } // request for events int ret=-1; - switch (edge) { - case EventEdge::RisingEdge: - ret = gpiod_line_request_rising_edge_events( it->second, CONSUMER ); - break; - case EventEdge::FallingEdge: - ret = gpiod_line_request_falling_edge_events( it->second, CONSUMER ); - break; - case EventEdge::BothEdges: - ret = gpiod_line_request_both_edges_events( it->second, CONSUMER ); - default: - break; - } + int errcnt = 10; + while ( errcnt && ret < 0 ) { + switch (edge) { + case EventEdge::RisingEdge: + ret = gpiod_line_request_rising_edge_events( it->second, CONSUMER ); + break; + case EventEdge::FallingEdge: + ret = gpiod_line_request_falling_edge_events( it->second, CONSUMER ); + break; + case EventEdge::BothEdges: + ret = gpiod_line_request_both_edges_events( it->second, CONSUMER ); + default: + break; + } + errcnt--; + if ( ret < 0 ) std::this_thread::sleep_for( std::chrono::milliseconds( 1 ) ); + + } if ( ret < 0 ) { - qCritical()<<"Request gpio line" << gpio << "for events failed"; + qCritical()<<"Re-request gpio line" << gpio << "for events failed"; return false; } return true; @@ -485,6 +482,7 @@ bool PigpiodHandler::unRegisterInterrupt(unsigned int gpio) { auto it = fInterruptLineMap.find(gpio); if (it != fInterruptLineMap.end()) { gpiod_line_release(it->second); + fInterruptLineMap.erase( it ); reloadInterruptSettings(); return true; } diff --git a/source/library/include/gpio_pin_definitions.h b/source/library/include/gpio_pin_definitions.h index 423800aa..d0081f61 100644 --- a/source/library/include/gpio_pin_definitions.h +++ b/source/library/include/gpio_pin_definitions.h @@ -8,15 +8,12 @@ #include #include -// define the pins which are used to interface the raspberry pi -// UBIAS_EN is the power on/off pin for bias voltage -// PREAMP_1/2 enables the DC voltage to power the preamp through the signal cable -// EVT_AND, EVT_XOR are the event inputs from AND and XOR gates +// Define the signals of the hardware interface to the MuonPi HAT // Note: The pin definitions are enum constants and have nothing to do with the actual pin numbers // of the RPi GPIO header. To be independent of the specific hardware implementation, -// the pin numbers for these signals are defined in gpio_pin_mapping.h on the daemon side +// the pin numbers for these signals are defined in gpio_pin_mapping.h on the daemon side through the static map GPIO_PINMAP -enum GPIO_SIGNAL { UBIAS_EN, +enum GPIO_SIGNAL { UBIAS_EN, PREAMP_1, PREAMP_2, EVT_AND, EVT_XOR, GAIN_HL, ADC_READY, @@ -27,7 +24,7 @@ enum GPIO_SIGNAL { UBIAS_EN, TDC_INTB, TDC_STATUS, IN_POL1, IN_POL2, - UNDEFINED_PIN=255 + UNDEFINED_SIGNAL=255 }; enum SIGNAL_DIRECTION { DIR_UNDEFINED, DIR_IN, DIR_OUT, DIR_IO }; @@ -58,7 +55,7 @@ static const QMap GPIO_SIGNAL_MAP = { TDC_STATUS, { "TDC_STATUS", DIR_OUT} }, { IN_POL1, { "IN_POL1", DIR_OUT} }, { IN_POL2, { "IN_POL2", DIR_OUT} }, - { UNDEFINED_PIN, { "UNDEFINED_PIN", DIR_UNDEFINED} } + { UNDEFINED_SIGNAL, { "UNDEFINED_SIGNAL", DIR_UNDEFINED} } }; From 6f4bcff2b1ffc5c4273829c20ee641bfc833a879 Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 20 Jul 2021 20:27:42 +0200 Subject: [PATCH 30/47] - Renamed signal and throttledSignal signals in PigpioHandler and RateBuffer classes to more descriptive event and filteredEvent. - Added transmission of interrupt timestamp to event and filteredEvent signals. --- source/daemon/include/daemon.h | 4 +-- source/daemon/include/pigpiodhandler.h | 6 ++-- source/daemon/include/ratebuffer.h | 16 +++++----- source/daemon/src/daemon.cpp | 12 ++++---- source/daemon/src/main.cpp | 3 ++ source/daemon/src/pigpiodhandler.cpp | 19 +++++++----- source/daemon/src/ratebuffer.cpp | 30 ++++++++++--------- source/library/include/muondetector_structs.h | 3 +- 8 files changed, 51 insertions(+), 42 deletions(-) diff --git a/source/daemon/include/daemon.h b/source/daemon/include/daemon.h index f03b205d..ca474b44 100644 --- a/source/daemon/include/daemon.h +++ b/source/daemon/include/daemon.h @@ -173,8 +173,8 @@ public slots: void onGpsMonHW2Updated(const GnssMonHw2Struct& hw2); void receivedTcpMessage(TcpMessage tcpMessage); void pollAllUbxMsgRate(); - void onGpioPinEvent(uint8_t gpio); - void sendGpioPinEvent(uint8_t gpio); + void onGpioPinEvent(unsigned int gpio, EventTime event_time); + void sendGpioPinEvent(unsigned int gpio, EventTime event_time); void onGpsPropertyUpdatedGeodeticPos(const GeodeticPos& pos); void UBXReceivedVersion(const QString& swString, const QString& hwString, const QString& protString); void sampleAdc0Event(); diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index 855bf65a..b20bf5fc 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -12,6 +12,7 @@ #include #include #include +#include #include @@ -43,10 +44,8 @@ class PigpiodHandler : public QObject explicit PigpiodHandler(std::vector gpioPins, QObject *parent = nullptr); ~PigpiodHandler(); - // can't make it private because of access of PigpiodHandler with global pointer QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) QElapsedTimer elapsedEventTimer; -// unsigned int samplingTriggerSignal { UNDEFINED_GPIO }; double clockMeasurementSlope=0.; double clockMeasurementOffset=0.; @@ -56,7 +55,7 @@ class PigpiodHandler : public QObject bool isInhibited() const { return inhibit; } signals: - void signal(uint8_t gpio_pin); + void event(unsigned int gpio_pin, EventTime timestamp); public slots: void start(); @@ -67,7 +66,6 @@ public slots: bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); bool setPinState(unsigned int gpio, bool state); -// void setSamplingTriggerSignal(unsigned int gpio); bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); void setInhibited(bool inh=true) { inhibit=inh; } diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h index 651c0fd9..afb64848 100644 --- a/source/daemon/include/ratebuffer.h +++ b/source/daemon/include/ratebuffer.h @@ -9,6 +9,9 @@ #include #include #include +#include + +class PigpiodHandler; constexpr double MAX_AVG_RATE { 100. }; constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; @@ -22,10 +25,7 @@ class RateBuffer : public QObject public: struct BufferItem { - std::queue< std::chrono::time_point, - std::list> > - eventbuffer { }; - unsigned long multiplicity_countdown { MAX_BURST_MULTIPLICITY }; + std::queue< EventTime, std::list > eventbuffer { }; std::chrono::microseconds current_deadtime { 0 }; std::chrono::nanoseconds last_interval { 0 }; }; @@ -40,14 +40,14 @@ class RateBuffer : public QObject [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; [[nodiscard]] auto lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds; - [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> std::chrono::time_point; + [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> EventTime; signals: - void throttledSignal( unsigned int gpio ); - void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ); + void filteredEvent( unsigned int gpio, EventTime event_time ); + void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ns); public slots: - void onSignal(unsigned int gpio); + void onEvent(unsigned int gpio, EventTime event_time ); private: double fRateLimit { MAX_AVG_RATE }; diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 7604e9f5..42f17382 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -632,9 +632,9 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n // set up the rate buffer for all GPIO signals rateBuffer.clear(); - connect(pigHandler, &PigpiodHandler::signal, &rateBuffer, &RateBuffer::onSignal); - connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::sendGpioPinEvent); - connect(&rateBuffer, &RateBuffer::throttledSignal, this, &Daemon::onGpioPinEvent); + connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { @@ -1465,14 +1465,14 @@ void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) { emit sendTcpMessage(tcpMessage); } -void Daemon::onGpioPinEvent(uint8_t gpio) { +void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { // reverse lookup of gpio function from given pin (first occurence) auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second == gpio; } ); if (result != GPIO_PINMAP.end()) { if ( result->first == TIMEPULSE) { - auto usecs = std::chrono::duration_cast(rateBuffer.lastEventTime(gpio).time_since_epoch()).count(); + auto usecs = std::chrono::duration_cast(event_time.time_since_epoch()).count(); usecs = usecs % 1000000LL; if ( usecs > 500000L ) { usecs -= 1000000LL; @@ -1500,7 +1500,7 @@ void Daemon::onGpioPinEvent(uint8_t gpio) { } } -void Daemon::sendGpioPinEvent(uint8_t gpio) { +void Daemon::sendGpioPinEvent(unsigned int gpio, EventTime event_time) { // reverse lookup of gpio function from given pin (first occurence) auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second==gpio; } diff --git a/source/daemon/src/main.cpp b/source/daemon/src/main.cpp index 785454cb..88c558b4 100644 --- a/source/daemon/src/main.cpp +++ b/source/daemon/src/main.cpp @@ -20,6 +20,7 @@ #include "custom_io_operators.h" #include "daemon.h" #include "gpio_pin_definitions.h" +#include #include "config.h" //static const char* CONFIG_FILE = "/etc/muondetector/muondetector.conf"; @@ -115,6 +116,8 @@ void messageOutput(QtMsgType type, const QMessageLogContext &context, const QStr int main(int argc, char *argv[]) { qRegisterMetaType("TcpMessage"); + qRegisterMetaType("EventTime"); + qInstallMessageHandler(messageOutput); QCoreApplication a(argc, argv); QCoreApplication::setApplicationName("muondetector-daemon"); diff --git a/source/daemon/src/pigpiodhandler.cpp b/source/daemon/src/pigpiodhandler.cpp index de03f72e..ba46747e 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/source/daemon/src/pigpiodhandler.cpp @@ -257,17 +257,21 @@ void PigpiodHandler::threadLoop() { if ( ret > 0 ) { unsigned int line_index = 0; while ( line_index < event_bulk.num_lines ) { - gpiod_line_event event { }; - int result = gpiod_line_event_read( event_bulk.lines[line_index], &event); + gpiod_line_event line_event { }; + int result = gpiod_line_event_read( event_bulk.lines[line_index], &line_event); if ( result == 0 ) { unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); - std::uint64_t ns = event.ts.tv_sec*1e9 + event.ts.tv_nsec; - std::chrono::time_point timestamp(std::chrono::nanoseconds(ns)); - emit signal(gpio); + //std::uint64_t ns = line_event.ts.tv_sec*1e9 + line_event.ts.tv_nsec; + //const std::chrono::nanoseconds since_epoch_ns(ns); + std::chrono::nanoseconds since_epoch_ns(line_event.ts.tv_nsec); + since_epoch_ns += std::chrono::seconds(line_event.ts.tv_sec); + //auto since_epoch = std::chrono::duration_cast(since_epoch_ns); + EventTime timestamp(since_epoch_ns); + emit event(gpio, timestamp); if ( verbose > 2 ) { qDebug()<<"line event: gpio"< #include -constexpr auto invalid_time = std::chrono::steady_clock::time_point::min(); +constexpr auto invalid_time = std::chrono::system_clock::time_point::min(); RateBuffer::RateBuffer(QObject *parent) : QObject(parent) { } -void RateBuffer::onSignal(unsigned int gpio) { - auto now = std::chrono::steady_clock::now(); +void RateBuffer::onEvent(unsigned int gpio, EventTime event_time ) { +// auto now = std::chrono::steady_clock::now(); if ( buffermap[gpio].eventbuffer.empty() ) { - buffermap[gpio].eventbuffer.push(now); - emit throttledSignal(gpio); + buffermap[gpio].eventbuffer.push(event_time); + emit filteredEvent(gpio, event_time); return; } while ( !buffermap[gpio].eventbuffer.empty() - && ( now - buffermap[gpio].eventbuffer.front() > fBufferTime) ) + && ( event_time - buffermap[gpio].eventbuffer.front() > fBufferTime) ) { buffermap[gpio].eventbuffer.pop(); } if ( !buffermap[gpio].eventbuffer.empty() ) { auto last_event_time = buffermap[gpio].eventbuffer.back(); - buffermap[gpio].last_interval = std::chrono::duration_cast( now - last_event_time ); - if ( now - last_event_time < MAX_DEADTIME ) { + buffermap[gpio].last_interval = std::chrono::duration_cast( event_time - last_event_time ); + if ( event_time - last_event_time < MAX_DEADTIME ) { +// std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< double auto it = buffermap.find(gpio); if ( it == buffermap.end() ) return 0.; if ( it->second.eventbuffer.empty() ) return 0.; - auto end = std::chrono::steady_clock::now(); + auto end = std::chrono::system_clock::now(); auto start = end - fBufferTime; if ( start > it->second.eventbuffer.front() ) start = it->second.eventbuffer.front(); double span = 1e-6 * std::chrono::duration_cast(end - start).count(); @@ -81,9 +82,10 @@ auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> s return std::chrono::duration_cast( it2->second.eventbuffer.back() - it1->second.eventbuffer.back() ); } -auto RateBuffer::lastEventTime(unsigned int gpio) const -> std::chrono::time_point +auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime { auto it = buffermap.find(gpio); if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; return it->second.eventbuffer.back(); } + diff --git a/source/library/include/muondetector_structs.h b/source/library/include/muondetector_structs.h index daa40da0..cc958166 100644 --- a/source/library/include/muondetector_structs.h +++ b/source/library/include/muondetector_structs.h @@ -12,11 +12,12 @@ #include #include #include - +#include enum ADC_SAMPLING_MODE {ADC_MODE_DISABLED=0, ADC_MODE_PEAK=1, ADC_MODE_TRACE=2 }; enum TIMING_MUX_INPUTS { MUX_AND=0, MUX_XOR=1, MUX_DISC1=2, MUX_DISC2=3 }; +using EventTime = std::chrono::time_point; struct CalibStruct { public: From 1319d93632f9bcd66d23b084efcb90f57993bffd Mon Sep 17 00:00:00 2001 From: hangeza Date: Fri, 14 Jan 2022 21:54:04 +0100 Subject: [PATCH 31/47] Further work on libgpiod functionality for event handling: - moved all event handlers to separately spawned threads for each interrupt line - added map to store the last time intervals between events from different gpios in RateBuffer class - changed filling of gpioTimeIntervalShort histogram to time intervals measured between the currently selected eventTrigger and the rising edge of TIME_MEAS_OUT signal --- source/daemon/include/pigpiodhandler.h | 6 +- source/daemon/include/ratebuffer.h | 5 +- source/daemon/src/daemon.cpp | 51 ++++++++++++++--- source/daemon/src/pigpiodhandler.cpp | 79 ++++++++++++++------------ source/daemon/src/ratebuffer.cpp | 27 ++++++--- 5 files changed, 110 insertions(+), 58 deletions(-) diff --git a/source/daemon/include/pigpiodhandler.h b/source/daemon/include/pigpiodhandler.h index b20bf5fc..bdde740b 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/source/daemon/include/pigpiodhandler.h @@ -91,16 +91,16 @@ public slots: void measureGpioClockTime(); void reloadInterruptSettings(); - void threadLoop(); + [[gnu::hot]] void eventHandler( struct gpiod_line *line ); + [[gnu::hot]] void processEvent( unsigned int gpio, std::shared_ptr line_event ); bool inhibit=false; int verbose=0; gpiod_chip* fChip { nullptr }; std::map fInterruptLineMap { }; - gpiod_line_bulk fInterruptLineBulk; std::map fLineMap { }; bool fThreadRunning { false }; - std::unique_ptr fThread { nullptr }; + std::map> fThreads { }; std::mutex fMutex; }; diff --git a/source/daemon/include/ratebuffer.h b/source/daemon/include/ratebuffer.h index afb64848..8735353c 100644 --- a/source/daemon/include/ratebuffer.h +++ b/source/daemon/include/ratebuffer.h @@ -44,7 +44,7 @@ class RateBuffer : public QObject signals: void filteredEvent( unsigned int gpio, EventTime event_time ); - void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ns); + void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ns ); public slots: void onEvent(unsigned int gpio, EventTime event_time ); @@ -53,6 +53,9 @@ public slots: double fRateLimit { MAX_AVG_RATE }; std::chrono::microseconds fBufferTime { MAX_BUFFER_TIME }; std::map buffermap { }; + std::map, std::chrono::nanoseconds> fIntervalMap { }; + + void updateAllIntervals( unsigned int new_gpio, EventTime new_event_time ); }; diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp index 42f17382..ac0663b2 100644 --- a/source/daemon/src/daemon.cpp +++ b/source/daemon/src/daemon.cpp @@ -636,19 +636,27 @@ Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int n connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); - connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - { if (histoMap.find("gpioEventInterval")!=histoMap.end()) { +// connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) + connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if ( histoMap.find("gpioEventInterval")!=histoMap.end() + && ( GPIO_PINMAP[eventTrigger] == gpio ) ) + { //checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); - histoMap["gpioEventInterval"].fill(1e-6*nsecs); + histoMap["gpioEventInterval"].fill( 1e-6 * ns.count() ); } } ); connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - { if (histoMap.find("gpioEventIntervalShort")!=histoMap.end()) { - if (nsecs/1000<=histoMap["gpioEventIntervalShort"].getMax()) - histoMap["gpioEventIntervalShort"].fill((double)nsecs/1000.); - } - } ); +// connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if ( histoMap.find("gpioEventIntervalShort")!=histoMap.end() ) + { + if ( nsecs/1000 <= histoMap["gpioEventIntervalShort"].getMax() ) { + histoMap["gpioEventIntervalShort"].fill( 1e-3 * nsecs ); + } + } + } ); // establish ublox gnss module connection connectToGps(); @@ -815,7 +823,7 @@ void Daemon::connectToPigpiod(){ //emit GpioSetInput(GPIO_PINMAP[TDC_INTB]); emit GpioRegisterForCallback(GPIO_PINMAP[TDC_INTB], PigpiodHandler::EventEdge::FallingEdge); //emit GpioSetInput(GPIO_PINMAP[TIME_MEAS_OUT]); - emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], PigpiodHandler::EventEdge::FallingEdge); + emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], PigpiodHandler::EventEdge::RisingEdge); } if (HW_VERSION>=3) { emit GpioSetOutput(GPIO_PINMAP[IN_POL1]); @@ -1491,12 +1499,37 @@ void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { } } if ( result->first == eventTrigger ) { + /* auto nsecs = rateBuffer.lastInterval(gpio).count(); if ( nsecs > 0 ) { emit eventInterval( rateBuffer.lastInterval(gpio).count() ); } + */ emit sampleAdc0Event(); } + + if ( result->first == TIME_MEAS_OUT ) { + auto start_gpio = GPIO_PINMAP.find(eventTrigger); + if ( start_gpio != GPIO_PINMAP.end() ) { + long long nsecs { 0 }; + if ( result->first != eventTrigger ) { + nsecs = rateBuffer.lastInterval( gpio, start_gpio->second ).count(); + if ( nsecs < 0 ) nsecs = rateBuffer.lastInterval( start_gpio->second, gpio ).count(); + } else { + nsecs = rateBuffer.lastInterval( gpio ).count(); + } + if ( nsecs > 0 ) { + //emit eventInterval( nsecs ); + if ( nsecs < 100000L ) { + emit eventInterval( nsecs ); + std::cout<<"trigger interval="< line_event ) +{ + + //std::uint64_t ns = line_event.ts.tv_sec*1e9 + line_event.ts.tv_nsec; + //const std::chrono::nanoseconds since_epoch_ns(ns); + std::chrono::nanoseconds since_epoch_ns(line_event->ts.tv_nsec); + since_epoch_ns += std::chrono::seconds(line_event->ts.tv_sec); + //auto since_epoch = std::chrono::duration_cast(since_epoch_ns); + EventTime timestamp(since_epoch_ns); + emit event(gpio, timestamp); + if ( verbose > 3 ) { + qDebug()<<"line event: gpio"<event_type==GPIOD_LINE_EVENT_RISING_EDGE)?"rising":"falling") + <<" ts="< line_event { std::make_shared() }; + int ret = gpiod_line_event_wait( line, &timeout ); if ( ret > 0 ) { - unsigned int line_index = 0; - while ( line_index < event_bulk.num_lines ) { - gpiod_line_event line_event { }; - int result = gpiod_line_event_read( event_bulk.lines[line_index], &line_event); - if ( result == 0 ) { - unsigned int gpio = gpiod_line_offset( event_bulk.lines[line_index] ); - //std::uint64_t ns = line_event.ts.tv_sec*1e9 + line_event.ts.tv_nsec; - //const std::chrono::nanoseconds since_epoch_ns(ns); - std::chrono::nanoseconds since_epoch_ns(line_event.ts.tv_nsec); - since_epoch_ns += std::chrono::seconds(line_event.ts.tv_sec); - //auto since_epoch = std::chrono::duration_cast(since_epoch_ns); - EventTime timestamp(since_epoch_ns); - emit event(gpio, timestamp); - if ( verbose > 2 ) { - qDebug()<<"line event: gpio"<second); gpiod_line_release(it->second); + fLineMap.erase( it ); } // line was not allocated yet, so do it now gpiod_line* line = gpiod_chip_get_line(fChip, gpio); @@ -405,11 +413,6 @@ bool PigpiodHandler::setPinState(unsigned int gpio, bool state) { void PigpiodHandler::reloadInterruptSettings() { this->stop(); - gpiod_line_bulk_init( &fInterruptLineBulk ); - // rerequest bulk events - for (auto [gpio,line] : fInterruptLineMap) { - gpiod_line_bulk_add( &fInterruptLineBulk, line ); - } this->start(); } @@ -423,7 +426,8 @@ bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { // It is bypassed, since it does not work as intended. // The function simply does nothing in this case. return false; - gpiod_line_release(it->second); + //stop(); + //gpiod_line_release(it->second); if ( gpiod_line_update(it->second) < 0 ) { qCritical()<<"update of gpio line" << gpio << "after release failed"; //return false; @@ -500,15 +504,18 @@ bool PigpiodHandler::initialised(){ void PigpiodHandler::stop() { fThreadRunning = false; - if ( fThread != nullptr ) { - fThread->join(); + for ( auto &[ gpio, line_thread ] : fThreads ) { + if ( line_thread ) line_thread->join(); } } void PigpiodHandler::start() { if (fThreadRunning) return; fThreadRunning = true; - fThread.reset(new std::thread( [this](){ this->threadLoop(); } ) ); + + for ( auto &[ gpio, line ] : fInterruptLineMap ) { + fThreads[ gpio ] = std::make_unique( [this, gpio, line](){ this->eventHandler( line ); } ); + } } void PigpiodHandler::measureGpioClockTime() { diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp index ac24274e..a31bcaed 100644 --- a/source/daemon/src/ratebuffer.cpp +++ b/source/daemon/src/ratebuffer.cpp @@ -8,15 +8,26 @@ RateBuffer::RateBuffer(QObject *parent) : QObject(parent) } -void RateBuffer::onEvent(unsigned int gpio, EventTime event_time ) { -// auto now = std::chrono::steady_clock::now(); +void RateBuffer::updateAllIntervals( unsigned int new_gpio, EventTime new_event_time ) +{ + for ( const auto [ other_gpio, buffer_item ] : buffermap ) { + if ( new_gpio == other_gpio ) continue; + if ( buffer_item.eventbuffer.empty() ) continue; + auto last_other_time = buffer_item.eventbuffer.back(); + std::chrono::nanoseconds nsecs = std::chrono::duration_cast( new_event_time - last_other_time ); + fIntervalMap.insert_or_assign( std::make_pair( new_gpio, other_gpio ), nsecs ); + } +} + +void RateBuffer::onEvent( unsigned int gpio, EventTime event_time ) { + updateAllIntervals( gpio, event_time ); if ( buffermap[gpio].eventbuffer.empty() ) { buffermap[gpio].eventbuffer.push(event_time); emit filteredEvent(gpio, event_time); return; } - while ( !buffermap[gpio].eventbuffer.empty() + while ( !buffermap.at(gpio).eventbuffer.empty() && ( event_time - buffermap[gpio].eventbuffer.front() > fBufferTime) ) { buffermap[gpio].eventbuffer.pop(); @@ -34,7 +45,7 @@ void RateBuffer::onEvent(unsigned int gpio, EventTime event_time ) { } } else { unsigned long deadtime = buffermap[gpio].current_deadtime.count(); - if ( deadtime>0 ) { + if ( deadtime > 0 ) { deadtime--; buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); } @@ -75,11 +86,9 @@ auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanosecon auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds { - auto it1 = buffermap.find(gpio1); - if ( it1 == buffermap.end() || it1->second.eventbuffer.empty() ) return std::chrono::nanoseconds(0); - auto it2 = buffermap.find(gpio2); - if ( it2 == buffermap.end() || it2->second.eventbuffer.empty() ) return std::chrono::nanoseconds(0); - return std::chrono::duration_cast( it2->second.eventbuffer.back() - it1->second.eventbuffer.back() ); + auto it = fIntervalMap.find( std::make_pair( gpio1, gpio2 ) ); + if ( it == fIntervalMap.end() ) return std::chrono::nanoseconds(0); + return fIntervalMap.at( std::make_pair( gpio1, gpio2 ) ); } auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime From 3db51a3cf48d991253f24dfb8b6e012197c0763d Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 16 Jan 2022 20:36:58 +0100 Subject: [PATCH 32/47] Fixed merge conflicts and adapted code at some places for proper compile success --- CMakeLists.txt | 184 + Dockerfile | 22 - README.md | 7 + build/.gitignore | 3 - cmake/Macdeployqt.cmake | 41 + {source/cmake => cmake}/Windeployqt.cmake | 12 +- {source/cmake => cmake}/daemon.cmake | 138 +- {source/cmake => cmake}/gui.cmake | 158 +- {source/cmake => cmake}/library.cmake | 45 +- cmake/version.cmake | 4 + {source/config => config}/copyright | 0 {source/config => config}/license | 0 {source/daemon => daemon}/LICENSE | 0 {source/daemon => daemon}/README | 0 {source/daemon => daemon}/apt_cache_search.sh | 0 {source/daemon => daemon}/config/changelog | 0 {source/daemon => daemon}/config/conffiles | 0 .../config/muondetector-daemon.1 | 0 .../config/muondetector-daemon.service | 4 +- .../config/muondetector-login | 0 .../config/muondetector-login.1 | 0 .../config/muondetector.conf | 0 {source/daemon => daemon}/config/pigpiod.conf | 0 {source/daemon => daemon}/config/postinst | 0 {source/daemon => daemon}/config/preinst | 0 {source/daemon => daemon}/config/prerm | 0 .../daemon => daemon}/include/calibration.h | 66 +- {source/daemon => daemon}/include/daemon.h | 234 +- daemon/include/hardware/device_types.h | 140 + daemon/include/hardware/i2c/Adafruit_GFX.h | 109 + .../include/hardware/i2c/adafruit_ssd1306.h | 103 + .../include/hardware}/i2c/addresses.h | 6 +- daemon/include/hardware/i2c/ads1015.h | 19 + daemon/include/hardware/i2c/ads1115.h | 99 + daemon/include/hardware/i2c/bme280.h | 66 + daemon/include/hardware/i2c/bmp180.h | 41 + daemon/include/hardware/i2c/eeprom24aa02.h | 53 + daemon/include/hardware/i2c/glcdfont.h | 265 + daemon/include/hardware/i2c/hmc5883.h | 45 + daemon/include/hardware/i2c/i2cdevice.h | 159 + daemon/include/hardware/i2c/i2cutil.h | 35 + daemon/include/hardware/i2c/lm75.h | 29 + daemon/include/hardware/i2c/mcp4728.h | 84 + daemon/include/hardware/i2c/mic184.h | 34 + daemon/include/hardware/i2c/pca9536.h | 46 + daemon/include/hardware/i2c/sht21.h | 39 + .../include/hardware/i2c}/sht31.h | 6 +- .../include/hardware/i2c}/tca9546a.h | 2 +- daemon/include/hardware/i2c/ubloxi2c.h | 32 + daemon/include/hardware/i2c/x9119.h | 37 + daemon/include/hardware/i2cdevices.h | 27 + .../include/hardware/spi}/tdc7200.h | 8 +- daemon/include/hardware/spidevices.h | 6 + daemon/include/logengine.h | 33 + daemon/include/logparameter.h | 38 + .../include/pigpiodhandler.h | 16 +- .../daemon => daemon}/include/qtserialublox.h | 80 +- .../include/utility}/custom_io_operators.h | 3 +- .../include/utility}/filehandler.h | 23 +- daemon/include/utility/geohash.h | 14 + daemon/include/utility/gpio_mapping.h | 80 + .../include/utility}/ratebuffer.h | 5 +- daemon/include/utility/unixtime_from_gps.h | 20 + .../muondetector.conf.template | 0 daemon/src/calibration.cpp | 278 + daemon/src/daemon.cpp | 2585 +++++++ daemon/src/hardware/i2c/Adafruit_GFX.cpp | 555 ++ daemon/src/hardware/i2c/adafruit_ssd1306.cpp | 454 ++ daemon/src/hardware/i2c/ads1115.cpp | 423 ++ daemon/src/hardware/i2c/bme280.cpp | 537 ++ daemon/src/hardware/i2c/bmp180.cpp | 207 + daemon/src/hardware/i2c/eeprom24aa02.cpp | 104 + daemon/src/hardware/i2c/hmc5883.cpp | 187 + daemon/src/hardware/i2c/i2cdevice.cpp | 463 ++ daemon/src/hardware/i2c/i2cutil.cpp | 36 + daemon/src/hardware/i2c/lm75.cpp | 100 + daemon/src/hardware/i2c/mcp4728.cpp | 304 + daemon/src/hardware/i2c/mic184.cpp | 172 + daemon/src/hardware/i2c/pca9536.cpp | 83 + daemon/src/hardware/i2c/sht21.cpp | 156 + .../src/hardware/i2c}/sht31.cpp | 7 +- .../src/hardware/i2c}/tca9546a.cpp | 2 +- daemon/src/hardware/i2c/ubloxi2c.cpp | 53 + daemon/src/hardware/i2c/x9119.cpp | 162 + daemon/src/hardware/i2cdevices.cpp | 54 + daemon/src/hardware/spi/tdc7200.cpp | 179 + daemon/src/logengine.cpp | 147 + daemon/src/main.cpp | 592 ++ .../src/man/man1/muondetector-daemon.1 | 0 .../daemon => daemon}/src/man/pack_all_man.sh | 0 .../src/man/unpack_all_man.sh | 0 .../src/muondetector-login.cpp | 47 +- .../daemon => daemon}/src/pigpiodhandler.cpp | 217 +- .../daemon => daemon}/src/qtserialublox.cpp | 361 +- .../src/qtserialublox_processmessages.cpp | 1066 ++- daemon/src/utility/custom_io_operators.cpp | 23 + daemon/src/utility/filehandler.cpp | 506 ++ daemon/src/utility/geohash.cpp | 60 + .../src/utility}/gpio_mapping.cpp | 2 +- {source/gui => gui}/LICENSE | 0 {source/gui => gui}/README | 0 {source/gui => gui}/config/changelog | 0 {source/gui => gui}/config/description.txt | 0 gui/config/muon.ico | Bin 0 -> 96062 bytes {source/gui => gui}/config/muondetector-gui.1 | 0 .../config/muondetector-gui.desktop | 0 {source/gui => gui}/include/calibform.h | 23 +- {source/gui => gui}/include/calibscandialog.h | 22 +- .../include/custom_histogram_widget.h | 31 +- .../gui => gui}/include/custom_plot_widget.h | 36 +- {source/gui => gui}/include/gnssposwidget.h | 34 +- {source/gui => gui}/include/gpssatsform.h | 23 +- .../gui => gui}/include/histogramdataform.h | 12 +- {source/gui => gui}/include/i2cform.h | 13 +- {source/gui => gui}/include/logplotswidget.h | 26 +- {source/gui => gui}/include/mainwindow.h | 68 +- {source/gui => gui}/include/map.h | 10 +- .../include/parametermonitorform.h | 36 +- {source/gui => gui}/include/plotcustom.h | 23 +- gui/include/scanform.h | 74 + {source/gui => gui}/include/settings.h | 29 +- {source/gui => gui}/include/spiform.h | 7 +- {source/gui => gui}/include/status.h | 39 +- gui/qml/CustomMap.qml | 81 + {source/gui => gui}/qml/CustomMapForm.ui.qml | 0 {source/gui => gui}/qml/mymap.qml | 0 gui/qml/places/doc/images/places.png | Bin 0 -> 233430 bytes .../qml/places/doc/src/places.qdoc | 0 .../gui => gui}/qml/places/forms/Message.qml | 0 .../qml/places/forms/MessageForm.ui.qml | 0 .../qml/places/forms/PlaceDetails.qml | 0 .../qml/places/forms/PlaceDetailsForm.ui.qml | 0 .../qml/places/forms/SearchBoundingBox.qml | 0 .../places/forms/SearchBoundingBoxForm.ui.qml | 0 .../qml/places/forms/SearchBoundingCircle.qml | 0 .../forms/SearchBoundingCircleForm.ui.qml | 0 .../qml/places/forms/SearchCenter.qml | 0 .../qml/places/forms/SearchCenterForm.ui.qml | 0 .../qml/places/forms/SearchOptions.qml | 0 .../qml/places/forms/SearchOptionsForm.ui.qml | 0 {source/gui => gui}/qml/places/helper.js | 0 .../gui => gui}/qml/places/items/MainMenu.qml | 0 .../qml/places/items/MapComponent.qml | 0 .../qml/places/items/SearchBar.qml | 0 {source/gui => gui}/qml/places/main.cpp | 0 {source/gui => gui}/qml/places/places.pro | 0 {source/gui => gui}/qml/places/places.qml | 0 gui/qml/places/resources/categories.png | Bin 0 -> 130 bytes gui/qml/places/resources/left.png | Bin 0 -> 141 bytes gui/qml/places/resources/marker.png | Bin 0 -> 752 bytes gui/qml/places/resources/right.png | Bin 0 -> 147 bytes gui/qml/places/resources/scale.png | Bin 0 -> 98 bytes gui/qml/places/resources/scale_end.png | Bin 0 -> 93 bytes gui/qml/places/resources/search.png | Bin 0 -> 259 bytes gui/qml/places/resources/star.png | Bin 0 -> 1403 bytes .../qml/places/views/CategoryDelegate.qml | 0 .../qml/places/views/CategoryView.qml | 0 .../qml/places/views/EditorialDelegate.qml | 0 .../qml/places/views/EditorialPage.qml | 0 .../qml/places/views/EditorialView.qml | 0 .../qml/places/views/ImageView.qml | 0 .../qml/places/views/RatingView.qml | 0 .../qml/places/views/ReviewDelegate.qml | 0 .../qml/places/views/ReviewPage.qml | 0 .../qml/places/views/ReviewView.qml | 0 .../qml/places/views/SearchResultDelegate.qml | 0 .../qml/places/views/SearchResultView.qml | 0 .../qml/places/views/SuggestionView.qml | 0 gui/res/Info.plist.in | 40 + gui/res/muon.icns | Bin 0 -> 968792 bytes gui/res/muon.ico | Bin 0 -> 96062 bytes {source/gui => gui}/resources.qrc | 1 + gui/src/calibform.cpp | 214 + {source/gui => gui}/src/calibform.ui | 0 gui/src/calibscandialog.cpp | 217 + {source/gui => gui}/src/calibscandialog.ui | 0 gui/src/custom_histogram_widget.cpp | 249 + gui/src/custom_plot_widget.cpp | 225 + gui/src/gnssposwidget.cpp | 496 ++ {source/gui => gui}/src/gnssposwidget.ui | 0 gui/src/gpssatsform.cpp | 308 + {source/gui => gui}/src/gpssatsform.ui | 0 {source/gui => gui}/src/histogramdataform.cpp | 63 +- {source/gui => gui}/src/histogramdataform.ui | 0 gui/src/i2cform.cpp | 91 + {source/gui => gui}/src/i2cform.ui | 0 {source/gui => gui}/src/logplotswidget.cpp | 100 +- {source/gui => gui}/src/logplotswidget.ui | 0 {source/gui => gui}/src/main.cpp | 4 +- {source/gui => gui}/src/mainwindow.cpp | 783 +-- gui/src/mainwindow.ui | 611 ++ .../gui => gui}/src/man/apt_cache_search.sh | 0 .../src/man/man1/muondetector-gui.1 | 0 {source/gui => gui}/src/man/pack_all_man.sh | 0 {source/gui => gui}/src/man/unpack_all_man.sh | 0 gui/src/map.cpp | 40 + {source/gui => gui}/src/map.ui | 0 .../gui => gui}/src/parametermonitorform.cpp | 210 +- .../gui => gui}/src/parametermonitorform.ui | 277 +- gui/src/plotcustom.cpp | 163 + gui/src/scanform.cpp | 319 + gui/src/scanform.ui | 532 ++ {source/gui => gui}/src/settings.cpp | 327 +- {source/gui => gui}/src/settings.ui | 0 {source/gui => gui}/src/spiform.cpp | 6 +- {source/gui => gui}/src/spiform.ui | 0 {source/gui => gui}/src/status.cpp | 270 +- {source/gui => gui}/src/status.ui | 0 {source/gui => gui}/windows.rc | 0 .../library => library}/apt_cache_search.sh | 0 {source/library => library}/config/version.h | 2 + .../library => library}/include/.gitignore | 0 library/include/config.h | 89 + library/include/gpio_pin_definitions.h | 82 + library/include/histogram.h | 64 + .../library => library}/include/mqtthandler.h | 2 + .../include/muondetector_shared_global.h | 1 - library/include/muondetector_structs.h | 526 ++ .../include/tcpconnection.h | 46 +- .../library => library}/include/tcpmessage.h | 8 +- library/include/tcpmessage_keys.h | 82 + library/include/ublox_messages.h | 118 + library/include/ublox_structs.h | 69 + library/include/ubx_msg_key_name_map.h | 100 + {source/library => library}/muondetector.conf | 0 library/src/config.cpp | 10 + library/src/histogram.cpp | 267 + .../library => library}/src/mqtthandler.cpp | 16 +- .../library => library}/src/tcpconnection.cpp | 147 +- .../library => library}/src/tcpmessage.cpp | 25 +- source/CMakeLists.txt | 98 - source/cmake/version.cmake | 3 - source/daemon/include/geohash.h | 16 - source/daemon/include/gpio_mapping.h | 85 - source/daemon/include/i2c/custom_i2cdetect.h | 39 - source/daemon/include/i2c/i2cbusses.h | 63 - source/daemon/include/i2c/i2cdevices.h | 18 - .../include/i2c/i2cdevices/Adafruit_GFX.h | 110 - .../adafruit_ssd1306/adafruit_ssd1306.h | 102 - .../include/i2c/i2cdevices/ads1015/ads1015.h | 19 - .../include/i2c/i2cdevices/ads1115/ads1115.h | 69 - .../include/i2c/i2cdevices/bme280/bme280.h | 53 - .../include/i2c/i2cdevices/bmp180/bmp180.h | 31 - .../i2cdevices/eeprom24aa02/eeprom24aa02.h | 23 - .../include/i2c/i2cdevices/hmc5883/hmc5883.h | 36 - .../daemon/include/i2c/i2cdevices/i2cdevice.h | 126 - .../daemon/include/i2c/i2cdevices/lm75/lm75.h | 19 - .../include/i2c/i2cdevices/mcp4728/mcp4728.h | 46 - .../include/i2c/i2cdevices/pca9536/pca9536.h | 22 - .../include/i2c/i2cdevices/sht21/sht21.h | 27 - .../include/i2c/i2cdevices/sht31/Makefile | 19 - .../i2c/i2cdevices/ubloxi2c/ubloxi2c.h | 20 - .../include/i2c/i2cdevices/x9119/x9119.h | 25 - .../include/i2c/i2cdevices_old/i2cdevices.h | 526 -- source/daemon/include/i2c/linux/i2c-dev.h | 330 - source/daemon/include/logengine.h | 31 - source/daemon/include/logparameter.h | 30 - source/daemon/include/time_from_rtc.h | 35 - source/daemon/include/unixtime_from_gps.h | 60 - source/daemon/src/calibration.cpp | 281 - source/daemon/src/custom_io_operators.cpp | 25 - source/daemon/src/daemon.cpp | 2793 -------- source/daemon/src/dtoa.c | 6204 ----------------- source/daemon/src/filehandler.cpp | 514 -- source/daemon/src/g_fmt.c | 104 - source/daemon/src/geohash.cpp | 58 - source/daemon/src/i2c/Makefile | 23 - source/daemon/src/i2c/custom_i2cdetect.c | 283 - source/daemon/src/i2c/i2cbusses.c | 377 - .../src/i2c/i2cdevices/Adafruit_GFX.cpp | 616 -- .../adafruit_ssd1306/adafruit_ssd1306.cpp | 518 -- .../src/i2c/i2cdevices/ads1115/ads1115.cpp | 185 - .../src/i2c/i2cdevices/bme280/bme280.cpp | 520 -- .../src/i2c/i2cdevices/bmp180/bmp180.cpp | 205 - .../i2cdevices/eeprom24aa02/eeprom24aa02.cpp | 78 - source/daemon/src/i2c/i2cdevices/glcdfont.c | 264 - .../src/i2c/i2cdevices/hmc5883/hmc5883.cpp | 223 - .../daemon/src/i2c/i2cdevices/i2cdevice.cpp | 391 -- .../daemon/src/i2c/i2cdevices/lm75/lm75.cpp | 53 - .../src/i2c/i2cdevices/mcp4728/mcp4728.cpp | 130 - .../src/i2c/i2cdevices/pca9536/pca9536.cpp | 39 - .../daemon/src/i2c/i2cdevices/sht21/sht21.cpp | 175 - .../daemon/src/i2c/i2cdevices/sht31/Makefile | 19 - .../src/i2c/i2cdevices/sht31/sht31_test.cpp | 23 - .../src/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp | 48 - .../daemon/src/i2c/i2cdevices/x9119/x9119.cpp | 208 - .../src/i2c/i2cdevices_old/i2cdevices.cpp | 2697 ------- source/daemon/src/logengine.cpp | 174 - source/daemon/src/main.cpp | 693 -- source/daemon/src/ratebuffer.cpp | 100 - source/daemon/src/tdc7200.cpp | 190 - source/gui/include/scanform.h | 74 - source/gui/qml/CustomMap.qml | 165 - source/gui/src/calibform.cpp | 365 - source/gui/src/calibscandialog.cpp | 260 - source/gui/src/custom_histogram_widget.cpp | 243 - source/gui/src/custom_plot_widget.cpp | 229 - source/gui/src/gnssposwidget.cpp | 510 -- source/gui/src/gpssatsform.cpp | 352 - source/gui/src/i2cform.cpp | 79 - source/gui/src/mainwindow.ui | 511 -- source/gui/src/map.cpp | 69 - source/gui/src/plotcustom.cpp | 158 - source/gui/src/scanform.cpp | 255 - source/gui/src/scanform.ui | 356 - source/library/include/config.h | 73 - source/library/include/gpio_pin_definitions.h | 77 - source/library/include/histogram.h | 136 - source/library/include/muondetector_structs.h | 403 -- source/library/include/tcpmessage_keys.h | 188 - source/library/include/ublox_messages.h | 118 - source/library/include/ublox_structs.h | 70 - source/library/include/ubx_msg_key_name_map.h | 102 - source/library/src/config.cpp | 9 - {source/tools => tools}/CMakeLists.txt | 0 .../src/cosmic_gpio_ratecounter.cpp | 0 .../tools => tools}/src/cosmic_i2c_test.cpp | 0 .../tools => tools}/src/getmacaddresses.cpp | 0 318 files changed, 17749 insertions(+), 27974 deletions(-) create mode 100644 CMakeLists.txt delete mode 100644 Dockerfile delete mode 100644 build/.gitignore create mode 100644 cmake/Macdeployqt.cmake rename {source/cmake => cmake}/Windeployqt.cmake (91%) rename {source/cmake => cmake}/daemon.cmake (60%) rename {source/cmake => cmake}/gui.cmake (77%) rename {source/cmake => cmake}/library.cmake (64%) create mode 100644 cmake/version.cmake rename {source/config => config}/copyright (100%) rename {source/config => config}/license (100%) rename {source/daemon => daemon}/LICENSE (100%) rename {source/daemon => daemon}/README (100%) rename {source/daemon => daemon}/apt_cache_search.sh (100%) rename {source/daemon => daemon}/config/changelog (100%) rename {source/daemon => daemon}/config/conffiles (100%) rename {source/daemon => daemon}/config/muondetector-daemon.1 (100%) rename {source/daemon => daemon}/config/muondetector-daemon.service (80%) rename {source/daemon => daemon}/config/muondetector-login (100%) rename {source/daemon => daemon}/config/muondetector-login.1 (100%) rename {source/daemon => daemon}/config/muondetector.conf (100%) rename {source/daemon => daemon}/config/pigpiod.conf (100%) rename {source/daemon => daemon}/config/postinst (100%) rename {source/daemon => daemon}/config/preinst (100%) rename {source/daemon => daemon}/config/prerm (100%) rename {source/daemon => daemon}/include/calibration.h (56%) rename {source/daemon => daemon}/include/daemon.h (61%) create mode 100644 daemon/include/hardware/device_types.h create mode 100644 daemon/include/hardware/i2c/Adafruit_GFX.h create mode 100644 daemon/include/hardware/i2c/adafruit_ssd1306.h rename {source/daemon/include => daemon/include/hardware}/i2c/addresses.h (77%) create mode 100644 daemon/include/hardware/i2c/ads1015.h create mode 100644 daemon/include/hardware/i2c/ads1115.h create mode 100644 daemon/include/hardware/i2c/bme280.h create mode 100644 daemon/include/hardware/i2c/bmp180.h create mode 100644 daemon/include/hardware/i2c/eeprom24aa02.h create mode 100644 daemon/include/hardware/i2c/glcdfont.h create mode 100644 daemon/include/hardware/i2c/hmc5883.h create mode 100644 daemon/include/hardware/i2c/i2cdevice.h create mode 100644 daemon/include/hardware/i2c/i2cutil.h create mode 100644 daemon/include/hardware/i2c/lm75.h create mode 100644 daemon/include/hardware/i2c/mcp4728.h create mode 100644 daemon/include/hardware/i2c/mic184.h create mode 100644 daemon/include/hardware/i2c/pca9536.h create mode 100644 daemon/include/hardware/i2c/sht21.h rename {source/daemon/include/i2c/i2cdevices/sht31 => daemon/include/hardware/i2c}/sht31.h (91%) rename {source/daemon/include/i2c/i2cdevices/tca9546a => daemon/include/hardware/i2c}/tca9546a.h (93%) create mode 100644 daemon/include/hardware/i2c/ubloxi2c.h create mode 100644 daemon/include/hardware/i2c/x9119.h create mode 100644 daemon/include/hardware/i2cdevices.h rename {source/daemon/include => daemon/include/hardware/spi}/tdc7200.h (86%) create mode 100644 daemon/include/hardware/spidevices.h create mode 100644 daemon/include/logengine.h create mode 100644 daemon/include/logparameter.h rename {source/daemon => daemon}/include/pigpiodhandler.h (93%) rename {source/daemon => daemon}/include/qtserialublox.h (77%) rename {source/daemon/include => daemon/include/utility}/custom_io_operators.h (99%) rename {source/daemon/include => daemon/include/utility}/filehandler.h (79%) create mode 100644 daemon/include/utility/geohash.h create mode 100644 daemon/include/utility/gpio_mapping.h rename {source/daemon/include => daemon/include/utility}/ratebuffer.h (98%) create mode 100644 daemon/include/utility/unixtime_from_gps.h rename {source/daemon => daemon}/muondetector.conf.template (100%) create mode 100644 daemon/src/calibration.cpp create mode 100644 daemon/src/daemon.cpp create mode 100644 daemon/src/hardware/i2c/Adafruit_GFX.cpp create mode 100644 daemon/src/hardware/i2c/adafruit_ssd1306.cpp create mode 100644 daemon/src/hardware/i2c/ads1115.cpp create mode 100644 daemon/src/hardware/i2c/bme280.cpp create mode 100644 daemon/src/hardware/i2c/bmp180.cpp create mode 100644 daemon/src/hardware/i2c/eeprom24aa02.cpp create mode 100644 daemon/src/hardware/i2c/hmc5883.cpp create mode 100644 daemon/src/hardware/i2c/i2cdevice.cpp create mode 100644 daemon/src/hardware/i2c/i2cutil.cpp create mode 100644 daemon/src/hardware/i2c/lm75.cpp create mode 100644 daemon/src/hardware/i2c/mcp4728.cpp create mode 100644 daemon/src/hardware/i2c/mic184.cpp create mode 100644 daemon/src/hardware/i2c/pca9536.cpp create mode 100644 daemon/src/hardware/i2c/sht21.cpp rename {source/daemon/src/i2c/i2cdevices/sht31 => daemon/src/hardware/i2c}/sht31.cpp (93%) rename {source/daemon/src/i2c/i2cdevices/tca9546a => daemon/src/hardware/i2c}/tca9546a.cpp (85%) create mode 100644 daemon/src/hardware/i2c/ubloxi2c.cpp create mode 100644 daemon/src/hardware/i2c/x9119.cpp create mode 100644 daemon/src/hardware/i2cdevices.cpp create mode 100644 daemon/src/hardware/spi/tdc7200.cpp create mode 100644 daemon/src/logengine.cpp create mode 100644 daemon/src/main.cpp rename {source/daemon => daemon}/src/man/man1/muondetector-daemon.1 (100%) rename {source/daemon => daemon}/src/man/pack_all_man.sh (100%) rename {source/daemon => daemon}/src/man/unpack_all_man.sh (100%) rename {source/daemon => daemon}/src/muondetector-login.cpp (78%) rename {source/daemon => daemon}/src/pigpiodhandler.cpp (75%) rename {source/daemon => daemon}/src/qtserialublox.cpp (65%) rename {source/daemon => daemon}/src/qtserialublox_processmessages.cpp (65%) create mode 100644 daemon/src/utility/custom_io_operators.cpp create mode 100644 daemon/src/utility/filehandler.cpp create mode 100644 daemon/src/utility/geohash.cpp rename {source/daemon/src => daemon/src/utility}/gpio_mapping.cpp (80%) rename {source/gui => gui}/LICENSE (100%) rename {source/gui => gui}/README (100%) rename {source/gui => gui}/config/changelog (100%) rename {source/gui => gui}/config/description.txt (100%) create mode 100644 gui/config/muon.ico rename {source/gui => gui}/config/muondetector-gui.1 (100%) rename {source/gui => gui}/config/muondetector-gui.desktop (100%) rename {source/gui => gui}/include/calibform.h (74%) rename {source/gui => gui}/include/calibscandialog.h (64%) rename {source/gui => gui}/include/custom_histogram_widget.h (62%) rename {source/gui => gui}/include/custom_plot_widget.h (55%) rename {source/gui => gui}/include/gnssposwidget.h (66%) rename {source/gui => gui}/include/gpssatsform.h (62%) rename {source/gui => gui}/include/histogramdataform.h (78%) rename {source/gui => gui}/include/i2cform.h (67%) rename {source/gui => gui}/include/logplotswidget.h (80%) rename {source/gui => gui}/include/mainwindow.h (80%) rename {source/gui => gui}/include/map.h (57%) rename {source/gui => gui}/include/parametermonitorform.h (69%) rename {source/gui => gui}/include/plotcustom.h (69%) create mode 100644 gui/include/scanform.h rename {source/gui => gui}/include/settings.h (81%) rename {source/gui => gui}/include/spiform.h (61%) rename {source/gui => gui}/include/status.h (62%) create mode 100644 gui/qml/CustomMap.qml rename {source/gui => gui}/qml/CustomMapForm.ui.qml (100%) rename {source/gui => gui}/qml/mymap.qml (100%) create mode 100644 gui/qml/places/doc/images/places.png rename {source/gui => gui}/qml/places/doc/src/places.qdoc (100%) rename {source/gui => gui}/qml/places/forms/Message.qml (100%) rename {source/gui => gui}/qml/places/forms/MessageForm.ui.qml (100%) rename {source/gui => gui}/qml/places/forms/PlaceDetails.qml (100%) rename {source/gui => gui}/qml/places/forms/PlaceDetailsForm.ui.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchBoundingBox.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchBoundingBoxForm.ui.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchBoundingCircle.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchBoundingCircleForm.ui.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchCenter.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchCenterForm.ui.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchOptions.qml (100%) rename {source/gui => gui}/qml/places/forms/SearchOptionsForm.ui.qml (100%) rename {source/gui => gui}/qml/places/helper.js (100%) rename {source/gui => gui}/qml/places/items/MainMenu.qml (100%) rename {source/gui => gui}/qml/places/items/MapComponent.qml (100%) rename {source/gui => gui}/qml/places/items/SearchBar.qml (100%) rename {source/gui => gui}/qml/places/main.cpp (100%) rename {source/gui => gui}/qml/places/places.pro (100%) rename {source/gui => gui}/qml/places/places.qml (100%) create mode 100644 gui/qml/places/resources/categories.png create mode 100644 gui/qml/places/resources/left.png create mode 100644 gui/qml/places/resources/marker.png create mode 100644 gui/qml/places/resources/right.png create mode 100644 gui/qml/places/resources/scale.png create mode 100644 gui/qml/places/resources/scale_end.png create mode 100644 gui/qml/places/resources/search.png create mode 100644 gui/qml/places/resources/star.png rename {source/gui => gui}/qml/places/views/CategoryDelegate.qml (100%) rename {source/gui => gui}/qml/places/views/CategoryView.qml (100%) rename {source/gui => gui}/qml/places/views/EditorialDelegate.qml (100%) rename {source/gui => gui}/qml/places/views/EditorialPage.qml (100%) rename {source/gui => gui}/qml/places/views/EditorialView.qml (100%) rename {source/gui => gui}/qml/places/views/ImageView.qml (100%) rename {source/gui => gui}/qml/places/views/RatingView.qml (100%) rename {source/gui => gui}/qml/places/views/ReviewDelegate.qml (100%) rename {source/gui => gui}/qml/places/views/ReviewPage.qml (100%) rename {source/gui => gui}/qml/places/views/ReviewView.qml (100%) rename {source/gui => gui}/qml/places/views/SearchResultDelegate.qml (100%) rename {source/gui => gui}/qml/places/views/SearchResultView.qml (100%) rename {source/gui => gui}/qml/places/views/SuggestionView.qml (100%) create mode 100644 gui/res/Info.plist.in create mode 100644 gui/res/muon.icns create mode 100644 gui/res/muon.ico rename {source/gui => gui}/resources.qrc (91%) create mode 100644 gui/src/calibform.cpp rename {source/gui => gui}/src/calibform.ui (100%) create mode 100644 gui/src/calibscandialog.cpp rename {source/gui => gui}/src/calibscandialog.ui (100%) create mode 100644 gui/src/custom_histogram_widget.cpp create mode 100644 gui/src/custom_plot_widget.cpp create mode 100644 gui/src/gnssposwidget.cpp rename {source/gui => gui}/src/gnssposwidget.ui (100%) create mode 100644 gui/src/gpssatsform.cpp rename {source/gui => gui}/src/gpssatsform.ui (100%) rename {source/gui => gui}/src/histogramdataform.cpp (57%) rename {source/gui => gui}/src/histogramdataform.ui (100%) create mode 100644 gui/src/i2cform.cpp rename {source/gui => gui}/src/i2cform.ui (100%) rename {source/gui => gui}/src/logplotswidget.cpp (70%) rename {source/gui => gui}/src/logplotswidget.ui (100%) rename {source/gui => gui}/src/main.cpp (93%) rename {source/gui => gui}/src/mainwindow.cpp (65%) create mode 100644 gui/src/mainwindow.ui rename {source/gui => gui}/src/man/apt_cache_search.sh (100%) rename {source/gui => gui}/src/man/man1/muondetector-gui.1 (100%) rename {source/gui => gui}/src/man/pack_all_man.sh (100%) rename {source/gui => gui}/src/man/unpack_all_man.sh (100%) create mode 100644 gui/src/map.cpp rename {source/gui => gui}/src/map.ui (100%) rename {source/gui => gui}/src/parametermonitorform.cpp (54%) rename {source/gui => gui}/src/parametermonitorform.ui (96%) mode change 100644 => 100755 create mode 100644 gui/src/plotcustom.cpp create mode 100644 gui/src/scanform.cpp create mode 100644 gui/src/scanform.ui rename {source/gui => gui}/src/settings.cpp (58%) rename {source/gui => gui}/src/settings.ui (100%) rename {source/gui => gui}/src/spiform.cpp (57%) rename {source/gui => gui}/src/spiform.ui (100%) rename {source/gui => gui}/src/status.cpp (51%) rename {source/gui => gui}/src/status.ui (100%) rename {source/gui => gui}/windows.rc (100%) rename {source/library => library}/apt_cache_search.sh (100%) rename {source/library => library}/config/version.h (69%) rename {source/library => library}/include/.gitignore (100%) create mode 100644 library/include/config.h create mode 100644 library/include/gpio_pin_definitions.h create mode 100644 library/include/histogram.h rename {source/library => library}/include/mqtthandler.h (99%) rename {source/library => library}/include/muondetector_shared_global.h (99%) create mode 100644 library/include/muondetector_structs.h rename {source/library => library}/include/tcpconnection.h (58%) rename {source/library => library}/include/tcpmessage.h (87%) create mode 100644 library/include/tcpmessage_keys.h create mode 100644 library/include/ublox_messages.h create mode 100644 library/include/ublox_structs.h create mode 100644 library/include/ubx_msg_key_name_map.h rename {source/library => library}/muondetector.conf (100%) create mode 100644 library/src/config.cpp create mode 100644 library/src/histogram.cpp rename {source/library => library}/src/mqtthandler.cpp (95%) rename {source/library => library}/src/tcpconnection.cpp (55%) rename {source/library => library}/src/tcpmessage.cpp (64%) delete mode 100644 source/CMakeLists.txt delete mode 100644 source/cmake/version.cmake delete mode 100644 source/daemon/include/geohash.h delete mode 100644 source/daemon/include/gpio_mapping.h delete mode 100644 source/daemon/include/i2c/custom_i2cdetect.h delete mode 100644 source/daemon/include/i2c/i2cbusses.h delete mode 100644 source/daemon/include/i2c/i2cdevices.h delete mode 100644 source/daemon/include/i2c/i2cdevices/Adafruit_GFX.h delete mode 100644 source/daemon/include/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h delete mode 100644 source/daemon/include/i2c/i2cdevices/ads1015/ads1015.h delete mode 100644 source/daemon/include/i2c/i2cdevices/ads1115/ads1115.h delete mode 100644 source/daemon/include/i2c/i2cdevices/bme280/bme280.h delete mode 100644 source/daemon/include/i2c/i2cdevices/bmp180/bmp180.h delete mode 100644 source/daemon/include/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h delete mode 100644 source/daemon/include/i2c/i2cdevices/hmc5883/hmc5883.h delete mode 100644 source/daemon/include/i2c/i2cdevices/i2cdevice.h delete mode 100644 source/daemon/include/i2c/i2cdevices/lm75/lm75.h delete mode 100644 source/daemon/include/i2c/i2cdevices/mcp4728/mcp4728.h delete mode 100644 source/daemon/include/i2c/i2cdevices/pca9536/pca9536.h delete mode 100644 source/daemon/include/i2c/i2cdevices/sht21/sht21.h delete mode 100644 source/daemon/include/i2c/i2cdevices/sht31/Makefile delete mode 100644 source/daemon/include/i2c/i2cdevices/ubloxi2c/ubloxi2c.h delete mode 100644 source/daemon/include/i2c/i2cdevices/x9119/x9119.h delete mode 100644 source/daemon/include/i2c/i2cdevices_old/i2cdevices.h delete mode 100644 source/daemon/include/i2c/linux/i2c-dev.h delete mode 100644 source/daemon/include/logengine.h delete mode 100644 source/daemon/include/logparameter.h delete mode 100644 source/daemon/include/time_from_rtc.h delete mode 100644 source/daemon/include/unixtime_from_gps.h delete mode 100644 source/daemon/src/calibration.cpp delete mode 100644 source/daemon/src/custom_io_operators.cpp delete mode 100644 source/daemon/src/daemon.cpp delete mode 100644 source/daemon/src/dtoa.c delete mode 100644 source/daemon/src/filehandler.cpp delete mode 100644 source/daemon/src/g_fmt.c delete mode 100644 source/daemon/src/geohash.cpp delete mode 100644 source/daemon/src/i2c/Makefile delete mode 100644 source/daemon/src/i2c/custom_i2cdetect.c delete mode 100644 source/daemon/src/i2c/i2cbusses.c delete mode 100644 source/daemon/src/i2c/i2cdevices/Adafruit_GFX.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/ads1115/ads1115.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/bme280/bme280.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/bmp180/bmp180.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/glcdfont.c delete mode 100644 source/daemon/src/i2c/i2cdevices/hmc5883/hmc5883.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/i2cdevice.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/lm75/lm75.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/mcp4728/mcp4728.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/pca9536/pca9536.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/sht21/sht21.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/sht31/Makefile delete mode 100644 source/daemon/src/i2c/i2cdevices/sht31/sht31_test.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices/x9119/x9119.cpp delete mode 100644 source/daemon/src/i2c/i2cdevices_old/i2cdevices.cpp delete mode 100644 source/daemon/src/logengine.cpp delete mode 100644 source/daemon/src/main.cpp delete mode 100644 source/daemon/src/ratebuffer.cpp delete mode 100644 source/daemon/src/tdc7200.cpp delete mode 100644 source/gui/include/scanform.h delete mode 100644 source/gui/qml/CustomMap.qml delete mode 100644 source/gui/src/calibform.cpp delete mode 100644 source/gui/src/calibscandialog.cpp delete mode 100644 source/gui/src/custom_histogram_widget.cpp delete mode 100644 source/gui/src/custom_plot_widget.cpp delete mode 100644 source/gui/src/gnssposwidget.cpp delete mode 100644 source/gui/src/gpssatsform.cpp delete mode 100644 source/gui/src/i2cform.cpp delete mode 100644 source/gui/src/mainwindow.ui delete mode 100644 source/gui/src/map.cpp delete mode 100644 source/gui/src/plotcustom.cpp delete mode 100644 source/gui/src/scanform.cpp delete mode 100644 source/gui/src/scanform.ui delete mode 100644 source/library/include/config.h delete mode 100644 source/library/include/gpio_pin_definitions.h delete mode 100644 source/library/include/histogram.h delete mode 100644 source/library/include/muondetector_structs.h delete mode 100644 source/library/include/tcpmessage_keys.h delete mode 100644 source/library/include/ublox_messages.h delete mode 100644 source/library/include/ublox_structs.h delete mode 100644 source/library/include/ubx_msg_key_name_map.h delete mode 100644 source/library/src/config.cpp rename {source/tools => tools}/CMakeLists.txt (100%) rename {source/tools => tools}/src/cosmic_gpio_ratecounter.cpp (100%) rename {source/tools => tools}/src/cosmic_i2c_test.cpp (100%) rename {source/tools => tools}/src/getmacaddresses.cpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 00000000..30b70cfe --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,184 @@ +cmake_minimum_required (VERSION 3.10) +project (muondetector LANGUAGES CXX C) + +string(TIMESTAMP PROJECT_DATE_STRING "%b %d, %Y") + +option(MUONDETECTOR_BUILD_GUI "Build the gui for the muondetector" ON) +option(MUONDETECTOR_BUILD_DAEMON "Build the daemon for the muondetector. Defaults to ON on armv7l architecture" OFF) +set(MUONDETECTOR_ON_RASPBERRYPI OFF) + +include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/version.cmake") + +execute_process(COMMAND bash "-c" "git rev-parse --short HEAD | tr -d '\n'" + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + OUTPUT_VARIABLE PROJECT_VERSION_HASH) + + + +if ("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "^(armv7|armv6)") + set(MUONDETECTOR_BUILD_DAEMON ON) + set(MUONDETECTOR_ON_RASPBERRYPI ON) +endif () + +set(MUONDETECTOR_CONFIG_DIR "${CMAKE_CURRENT_SOURCE_DIR}/config") + +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/lib") +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/lib") +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/bin") + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + + + +add_compile_options( + -Wall + -O3 + ) + +if (MSVC) + # Force to always compile with W4 + if(CMAKE_CXX_FLAGS MATCHES "/W[0-4]") + string(REGEX REPLACE "/W[0-4]" "/W4" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + else() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4") + endif() +else() + +add_compile_options( + -Wextra + -Wshadow + -Wpedantic + ) + +endif() + +if (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv7l") +add_compile_options( + -mthumb + -march=armv7-a + -mfpu=vfp + -mfloat-abi=hard + ) +endif (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv7l") + +if (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv6l") +add_compile_options( + -march=armv6z + -mfpu=vfp + -mfloat-abi=hard + -mtune=arm1176jzf-s + ) +endif (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv6l") + + +if (NOT (WIN32 OR APPLE)) +set(CPACK_GENERATOR "DEB") +set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) +set(CPACK_DEBIAN_PACKAGE_HOMEPAGE "https://github.com/MuonPi/muondetector") +set(CPACK_DEBIAN_PACKAGE_MAINTAINER "MuonPi ") +set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT) +endif () +set(CPACK_RESOURCE_FILE_LICENSE "${MUONDETECTOR_CONFIG_DIR}/license") +set(CPACK_PACKAGE_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/packages") +set(CPACK_PACKAGE_VENDOR "MuonPi.org") +set(CPACK_PACKAGE_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}-hotfix1") +set(CPACK_PACKAGE_VERSION_MAJOR "${PROJECT_VERSION_MAJOR}") +set(CPACK_PACKAGE_VERSION_MINOR "${PROJECT_VERSION_MINOR}") +set(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_VERSION_PATCH}") + + +set(CMAKE_AUTOUIC ON) +set(CMAKE_AUTOMOC ON) +set(CMAKE_AUTORCC ON) + + + +if(WIN32) + set(QWT_DIR "C:/Qwt-6.2.0") + set(OPENSSL_DIR "C:/Qt/Tools/OpenSSL/Win_x64") + set(QTROOT "C:/Qt") + set(QTTOOLS "${QTROOT}/Tools") + set(SDKROOT "${QTROOT}/5.15.2/mingw81_64") + list(APPEND CMAKE_PREFIX_PATH "${SDKROOT}") + list(APPEND CMAKE_PREFIX_PATH "${SDKROOT}/lib/cmake/Qt5QuickCompiler") + list(APPEND CMAKE_PREFIX_PATH "${SDKROOT}/lib/cmake/Qt5") + + if (MSVC) + if("${MSVC_RUNTIME}" STREQUAL "") + set(MSVC_RUNTIME "static") + endif() + # Set compiler options. + set(variables + CMAKE_C_FLAGS_DEBUG + CMAKE_C_FLAGS_MINSIZEREL + CMAKE_C_FLAGS_RELEASE + CMAKE_C_FLAGS_RELWITHDEBINFO + CMAKE_CXX_FLAGS_DEBUG + CMAKE_CXX_FLAGS_MINSIZEREL + CMAKE_CXX_FLAGS_RELEASE + CMAKE_CXX_FLAGS_RELWITHDEBINFO + ) + if(${MSVC_RUNTIME} STREQUAL "static") + message(STATUS + "MSVC -> forcing use of statically-linked runtime." + ) + foreach(variable ${variables}) + if(${variable} MATCHES "/MD") + string(REGEX REPLACE "/MD" "/MT" ${variable} "${${variable}}") + endif() + endforeach() + else() + message(STATUS + "MSVC -> forcing use of dynamically-linked runtime." + ) + foreach(variable ${variables}) + if(${variable} MATCHES "/MT") + string(REGEX REPLACE "/MT" "/MD" ${variable} "${${variable}}") + endif() + endforeach() + endif() + endif() + + +else() + +set(Qt5_DIR "/usr/lib/x86_64-linux-gnu/cmake/Qt5/") + +endif () + + + +include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/library.cmake") + +set(MUONDETECTOR_ALL_FILES + "${MUONDETECTOR_LIBRARY_SOURCE_FILES}" + "${MUONDETECTOR_LIBRARY_HEADER_FILES}" + ) +if (MUONDETECTOR_BUILD_GUI) +include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/gui.cmake") + +set(MUONDETECTOR_ALL_FILES + "${MUONDETECTOR_ALL_FILES}" + "${MUONDETECTOR_GUI_SOURCE_FILES}" + "${MUONDETECTOR_GUI_HEADER_FILES}" + ) +endif (MUONDETECTOR_BUILD_GUI) +if (MUONDETECTOR_BUILD_DAEMON) +include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/daemon.cmake") + +set(MUONDETECTOR_ALL_FILES + "${MUONDETECTOR_ALL_FILES}" + "${MUONDETECTOR_DAEMON_SOURCE_FILES}" + "${MUONDETECTOR_DAEMON_HEADER_FILES}" + "${MUONDETECTOR_LOGIN_SOURCE_FILES}" + "${MUONDETECTOR_LOGIN_HEADER_FILES}" + ) +endif (MUONDETECTOR_BUILD_DAEMON) + +add_custom_target(clangformat COMMAND clang-format -style=WebKit -i ${MUONDETECTOR_ALL_FILES}) + + +set(CPACK_DEB_COMPONENT_INSTALL ON) + +include(CPack) \ No newline at end of file diff --git a/Dockerfile b/Dockerfile deleted file mode 100644 index f706acf5..00000000 --- a/Dockerfile +++ /dev/null @@ -1,22 +0,0 @@ -FROM debian:buster - -WORKDIR /builddir/ - -RUN apt update && apt install -y \ - gcc-arm-linux-gnueabihf \ - g++-arm-linux-gnueabihf \ - cmake \ - libconfig++-dev \ - libconfig-dev \ - build-essential \ - git \ - libqt5serialport5-dev \ - libqt5svg5-dev \ - qtdeclarative5-dev \ - libpigpiod-if-dev \ - libcrypto++-dev \ - - -RUN cd /builddir && git clone https://github.com/MuonPi/muondetector.git - -ENTRYPOINT /bin/bash diff --git a/README.md b/README.md index a58255c1..76891c01 100644 --- a/README.md +++ b/README.md @@ -73,6 +73,13 @@ Cheat-Sheet Copy&Paste: It may be when starting for the first time that, if the daemon is not started as a service, the data folder structure cannot be written due to insufficient rights. Starting the daemon with sudo-er rights should be avoided. Here, the folder structure can be created by hand to solve the issue: copy paste the hashed folder name from the error output of the daemon when started without folder structure and create the folder with `sudo mkdir /var/muondetector/[Hashed Name]` with `notUploadedData` and `uploadedData` as sub-folders. Then, change the user rights with `sudo chown -R pi:pi /var/muondetector`. When restarted, the daemon should be able to write the data. +#### Manjaro + +The QT libraries are named differently in Manjaro. +For successful installation, changes to the CMake files have to be made: In `gui.cmake` both occurences of `qwt-qt5` have to be changed to `qwt`. +Compillation can then start as usual with `cmake `, `make` and `make install`. + + ## RUNNING THE SOFTWARE ### Version < 1.1.2 diff --git a/build/.gitignore b/build/.gitignore deleted file mode 100644 index 94548af5..00000000 --- a/build/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -* -*/ -!.gitignore diff --git a/cmake/Macdeployqt.cmake b/cmake/Macdeployqt.cmake new file mode 100644 index 00000000..7152337c --- /dev/null +++ b/cmake/Macdeployqt.cmake @@ -0,0 +1,41 @@ +# The MIT License (MIT) +# +# Copyright (c) 2017 Nathan Osman +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +find_package(Qt5Core REQUIRED) +# Retrieve the absolute path to qmake and then use that path to find +# the macdeployqt binary +get_target_property(_qmake_executable Qt5::qmake IMPORTED_LOCATION) +get_filename_component(_qt_bin_dir "${_qmake_executable}" DIRECTORY) +find_program(MACDEPLOYQT_EXECUTABLE macdeployqt HINTS "${_qt_bin_dir}") +# Add commands that copy the required Qt files to the application bundle +# represented by the target +function(macdeployqt target directory options) + + add_custom_command(TARGET ${target} POST_BUILD + COMMAND "${MACDEPLOYQT_EXECUTABLE}" + \"$/../..\" + -always-overwrite + ${options} + COMMENT "Deploying Qt..." + ) +endfunction() + +mark_as_advanced(MACDEPLOYQT_EXECUTABLE) diff --git a/source/cmake/Windeployqt.cmake b/cmake/Windeployqt.cmake similarity index 91% rename from source/cmake/Windeployqt.cmake rename to cmake/Windeployqt.cmake index 5de19c86..7c057120 100644 --- a/source/cmake/Windeployqt.cmake +++ b/cmake/Windeployqt.cmake @@ -28,6 +28,10 @@ get_target_property(_qmake_executable Qt5::qmake IMPORTED_LOCATION) get_filename_component(_qt_bin_dir "${_qmake_executable}" DIRECTORY) find_program(WINDEPLOYQT_EXECUTABLE windeployqt HINTS "${_qt_bin_dir}") +if(WINDEPLOYQT_EXECUTABLE) + message(STATUS "windeploy_qt found: ${WINDEPLOYQT_EXECUTABLE}") +endif() + # Running this with MSVC 2015 requires CMake 3.6+ if((MSVC_VERSION VERSION_EQUAL 1900 OR MSVC_VERSION VERSION_GREATER 1900) AND CMAKE_VERSION VERSION_LESS "3.6") @@ -42,9 +46,9 @@ function(windeployqt target directory options) add_custom_command(TARGET ${target} POST_BUILD COMMAND "${CMAKE_COMMAND}" -E env PATH="${_qt_bin_dir}" "${WINDEPLOYQT_EXECUTABLE}" - --verbose 0 + #--verbose 0 ${options} - --release + #--release --no-compiler-runtime --no-angle --no-opengl-sw @@ -65,7 +69,6 @@ function(windeployqt target directory options) execute_process( COMMAND \"${CMAKE_COMMAND}\" -E env PATH=\"${_qt_bin_dir}\" \"${WINDEPLOYQT_EXECUTABLE}\" - --release ${options} --dry-run --no-compiler-runtime @@ -93,6 +96,7 @@ function(windeployqt target directory options) # so we fall back to one of CMake's own modules for copying them over set(CMAKE_INSTALL_UCRT_LIBRARIES TRUE) include(InstallRequiredSystemLibraries) + message(STATUS "CMAKE_INSTALL_SYSTEM_RUNTIME_LIBS: ${CMAKE_INSTALL_SYSTEM_RUNTIME_LIBS}") foreach(lib ${CMAKE_INSTALL_SYSTEM_RUNTIME_LIBS}) get_filename_component(filename "${lib}" NAME) add_custom_command(TARGET ${target} POST_BUILD @@ -103,4 +107,4 @@ function(windeployqt target directory options) endfunction() -mark_as_advanced(WINDEPLOYQT_EXECUTABLE) \ No newline at end of file +mark_as_advanced(WINDEPLOYQT_EXECUTABLE) diff --git a/source/cmake/daemon.cmake b/cmake/daemon.cmake similarity index 60% rename from source/cmake/daemon.cmake rename to cmake/daemon.cmake index aad33119..56b974aa 100644 --- a/source/cmake/daemon.cmake +++ b/cmake/daemon.cmake @@ -6,7 +6,9 @@ if(NOT WIN32) # added to make program editable in qt-creator on windows find_library(CRYPTOPP crypto++ REQUIRED) find_library(CONFIGPP config++ REQUIRED) +if (${MUONDETECTOR_ON_RASPBERRY}) find_library(LIBGPIOD gpiod REQUIRED) +endif () find_library(RT rt REQUIRED) find_library(MOSQUITTO mosquitto REQUIRED) @@ -14,73 +16,103 @@ endif() find_package(Qt5 COMPONENTS Network SerialPort REQUIRED) + +set(MUONDETECTOR_SPI_SOURCE_FILES + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/spi/tdc7200.cpp" + ) + +set(MUONDETECTOR_I2C_SOURCE_FILES + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/Adafruit_GFX.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/adafruit_ssd1306.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/ads1115.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/bme280.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/bmp180.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/eeprom24aa02.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/hmc5883.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/lm75.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/mcp4728.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/pca9536.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/sht21.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/sht31.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/tca9546a.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/ubloxi2c.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/x9119.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/mic184.cpp" + + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/i2cdevice.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2c/i2cutil.cpp" + + "${MUONDETECTOR_DAEMON_SRC_DIR}/hardware/i2cdevices.cpp" + ) + set(MUONDETECTOR_DAEMON_SOURCE_FILES "${MUONDETECTOR_DAEMON_SRC_DIR}/main.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/qtserialublox.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/qtserialublox_processmessages.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/pigpiodhandler.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/daemon.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/custom_io_operators.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/filehandler.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/utility/custom_io_operators.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/utility/filehandler.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/calibration.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/gpio_mapping.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/utility/gpio_mapping.cpp" "${MUONDETECTOR_DAEMON_SRC_DIR}/logengine.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/geohash.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/ratebuffer.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/tdc7200.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cbusses.c" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/ads1115/ads1115.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/bme280/bme280.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/bmp180/bmp180.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/hmc5883/hmc5883.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/lm75/lm75.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/mcp4728/mcp4728.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/pca9536/pca9536.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/sht21/sht21.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/x9119/x9119.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/Adafruit_GFX.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/i2cdevice.cpp" - "${MUONDETECTOR_DAEMON_SRC_DIR}/i2c/i2cdevices/glcdfont.c" + "${MUONDETECTOR_DAEMON_SRC_DIR}/utility/geohash.cpp" + "${MUONDETECTOR_DAEMON_SRC_DIR}/utility/ratebuffer.cpp" + + "${MUONDETECTOR_I2C_SOURCE_FILES}" +# "${MUONDETECTOR_SPI_SOURCE_FILES}" + ) + + +set(MUONDETECTOR_I2C_HEADER_FILES + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/Adafruit_GFX.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/adafruit_ssd1306.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/ads1015.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/ads1115.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/bme280.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/bmp180.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/eeprom24aa02.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/glcdfont.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/hmc5883.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/lm75.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/mcp4728.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/pca9536.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/sht21.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/sht31.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/tca9546a.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/ubloxi2c.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/x9119.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/mic184.h" + + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/i2cdevice.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2c/i2cutil.h" + + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/device_types.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/i2cdevices.h" + ) + +set(MUONDETECTOR_SPI_HEADER_FILES + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/spi/tdc7200.h" + + "${MUONDETECTOR_DAEMON_HEADER_DIR}/hardware/spidevices.h" ) set(MUONDETECTOR_DAEMON_HEADER_FILES - "${MUONDETECTOR_DAEMON_HEADER_DIR}/unixtime_from_gps.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/time_from_rtc.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/qtserialublox.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/daemon.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/pigpiodhandler.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/custom_io_operators.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/filehandler.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/custom_io_operators.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/unixtime_from_gps.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/filehandler.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/calibration.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/logparameter.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/gpio_mapping.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/tdc7200.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/gpio_mapping.h" "${MUONDETECTOR_DAEMON_HEADER_DIR}/logengine.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/geohash.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/ratebuffer.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/addresses.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/custom_i2cdetect.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cbusses.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/ads1015/ads1015.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/ads1115/ads1115.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/bme280/bme280.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/bmp180/bmp180.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/hmc5883/hmc5883.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/lm75/lm75.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/mcp4728/mcp4728.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/pca9536/pca9536.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/sht21/sht21.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/ubloxi2c/ubloxi2c.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/x9119/x9119.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/Adafruit_GFX.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/i2cdevices/i2cdevice.h" - "${MUONDETECTOR_DAEMON_HEADER_DIR}/i2c/linux/i2c-dev.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/geohash.h" + "${MUONDETECTOR_DAEMON_HEADER_DIR}/utility/ratebuffer.h" + + "${MUONDETECTOR_I2C_HEADER_FILES}" + #"${MUONDETECTOR_SPI_HEADER_FILES}" ) set(MUONDETECTOR_LOGIN_SOURCE_FILES @@ -118,6 +150,7 @@ target_link_libraries(muondetector-login mosquitto muondetector-shared muondetector-shared-mqtt + pthread ) add_executable(muondetector-daemon ${MUONDETECTOR_DAEMON_SOURCE_FILES} ${MUONDETECTOR_DAEMON_HEADER_FILES}) @@ -167,11 +200,13 @@ install(FILES "${CMAKE_CURRENT_BINARY_DIR}/muondetector-login.1.gz" DESTINATION install(FILES "${MUONDETECTOR_CONFIG_DIR}/copyright" DESTINATION "${CMAKE_INSTALL_DOCDIR}-daemon" COMPONENT daemon) install(FILES ${MUONDETECTOR_DAEMON_INSTALL_FILES} DESTINATION "/etc/muondetector/" COMPONENT daemon) install(FILES "${MUONDETECTOR_DAEMON_CONFIG_DIR}/muondetector-daemon.service" DESTINATION "/lib/systemd/system" COMPONENT daemon) +install(FILES "${MUONDETECTOR_DAEMON_CONFIG_DIR}/pigpiod.conf" DESTINATION "/etc/systemd/system/pigpiod.service.d/" COMPONENT daemon) install(PROGRAMS ${MUONDETECTOR_LOGIN_INSTALL_FILES} DESTINATION bin COMPONENT daemon) if (MUONDETECTOR_BUILD_GUI) +set(CPACK_DEBIAN_DAEMON_PACKAGE_DEPENDS "pigpiod") set(CPACK_DEBIAN_DAEMON_PACKAGE_CONTROL_EXTRA "${MUONDETECTOR_DAEMON_CONFIG_DIR}/preinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/postinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/prerm;${MUONDETECTOR_DAEMON_CONFIG_DIR}/conffiles") set(CPACK_DEBIAN_DAEMON_PACKAGE_SECTION "net") set(CPACK_DEBIAN_DAEMON_DESCRIPTION " Daemon that controls the muon detector board. @@ -181,6 +216,7 @@ set(CPACK_DEBIAN_DAEMON_DESCRIPTION " Daemon that controls the muon detector boa set(CPACK_COMPONENT_DAEMON_DESCRIPTION "${CPACK_DEBIAN_DAEMON_DESCRIPTION}") set(CPACK_DEBIAN_DAEMON_PACKAGE_NAME "muondetector-daemon") else () +set(CPACK_DEBIAN_PACKAGE_DEPENDS "pigpiod") set(CPACK_DEBIAN_PACKAGE_CONTROL_EXTRA "${MUONDETECTOR_DAEMON_CONFIG_DIR}/preinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/postinst;${MUONDETECTOR_DAEMON_CONFIG_DIR}/prerm;${MUONDETECTOR_DAEMON_CONFIG_DIR}/conffiles") set(CPACK_DEBIAN_PACKAGE_SECTION "net") set(CPACK_DEBIAN_PACKAGE_DESCRIPTION " Daemon that controls the muon detector board. @@ -188,4 +224,4 @@ set(CPACK_DEBIAN_PACKAGE_DESCRIPTION " Daemon that controls the muon detector bo It runs in the background and sends the data to the central server. It is licensed under the GNU Lesser General Public License version 3 (LGPL v3).") set(CPACK_DEBIAN_PACKAGE_NAME "muondetector-daemon") -endif () +endif () \ No newline at end of file diff --git a/source/cmake/gui.cmake b/cmake/gui.cmake similarity index 77% rename from source/cmake/gui.cmake rename to cmake/gui.cmake index 7aa6ace8..6c38567b 100644 --- a/source/cmake/gui.cmake +++ b/cmake/gui.cmake @@ -4,54 +4,9 @@ set(MUONDETECTOR_GUI_RES_DIR "${CMAKE_CURRENT_SOURCE_DIR}/gui/") set(MUONDETECTOR_GUI_HEADER_DIR "${CMAKE_CURRENT_SOURCE_DIR}/gui/include") set(MUONDETECTOR_GUI_CONFIG_DIR "${CMAKE_CURRENT_SOURCE_DIR}/gui/config") set(MUONDETECTOR_GUI_QML_DIR "${CMAKE_CURRENT_SOURCE_DIR}/gui/qml") +set(MUONDETECTOR_GUI_APPLE_RES_DIR "${CMAKE_CURRENT_SOURCE_DIR}/gui/res") -if(WIN32) - set(QWT_DIR "C:/Qwt-6.1.4") - set(OPENSSL_DIR "C:/Qt/Tools/OpenSSL/Win_x64") - set(CRYPTOPP_DIR "C:/cryptopp") - list(APPEND CMAKE_PREFIX_PATH "C:/Qt/5.15.1/msvc2019_64/lib/cmake/Qt5QuickCompiler") - list(APPEND CMAKE_PREFIX_PATH "C:/Qt/5.15.1/msvc2019_64/lib/cmake/Qt5") - - if (MSVC) - if("${MSVC_RUNTIME}" STREQUAL "") - set(MSVC_RUNTIME "static") - endif() - # Set compiler options. - set(variables - CMAKE_C_FLAGS_DEBUG - CMAKE_C_FLAGS_MINSIZEREL - CMAKE_C_FLAGS_RELEASE - CMAKE_C_FLAGS_RELWITHDEBINFO - CMAKE_CXX_FLAGS_DEBUG - CMAKE_CXX_FLAGS_MINSIZEREL - CMAKE_CXX_FLAGS_RELEASE - CMAKE_CXX_FLAGS_RELWITHDEBINFO - ) - if(${MSVC_RUNTIME} STREQUAL "static") - message(STATUS - "MSVC -> forcing use of statically-linked runtime." - ) - foreach(variable ${variables}) - if(${variable} MATCHES "/MD") - string(REGEX REPLACE "/MD" "/MT" ${variable} "${${variable}}") - endif() - endforeach() - else() - message(STATUS - "MSVC -> forcing use of dynamically-linked runtime." - ) - foreach(variable ${variables}) - if(${variable} MATCHES "/MT") - string(REGEX REPLACE "/MT" "/MD" ${variable} "${${variable}}") - endif() - endforeach() - endif() - endif() - - -endif() - set(MUONDETECTOR_GUI_SOURCE_FILES "${MUONDETECTOR_GUI_SOURCE_DIR}/calibform.cpp" @@ -122,12 +77,36 @@ configure_file( "${CMAKE_CURRENT_BINARY_DIR}/muon.ico" ) else() + configure_file( "${MUONDETECTOR_GUI_CONFIG_DIR}/muondetector-gui.1" "${CMAKE_CURRENT_BINARY_DIR}/muondetector-gui.1" ) -find_library(QWT_QT5 qwt-qt5 REQUIRED) +endif() + +if(APPLE) + #QWT-Framwork suchen + find_library(QWT + NAMES qwt + HINTS /opt/local/libexec/qt5/lib + REQUIRED) + if(QWT) + include_directories(${QWT}/Headers) + link_libraries(${QWT}) + message(STATUS "QWT found: ${QWT}") + endif() +elseif(WIN32) + find_library(QWT + NAMES qwt + HINTS ${QWT_DIR}/lib + REQUIRED) + if(QWT) + message(STATUS "QWT found: ${QWT}") + endif() +else() + find_library(QWT_QT5 qwt-qt5 REQUIRED) + endif() find_package(Qt5 COMPONENTS Network Svg Widgets Gui Quick QuickWidgets Qml REQUIRED) @@ -143,7 +122,27 @@ qt5_add_resources(qml_QRC "${MUONDETECTOR_GUI_RES_DIR}/resources.qrc") endif() +if(APPLE) + + set(MACOSX_BUNDLE_ICON_FILE muon.icns) + set(myApp_ICON ${MUONDETECTOR_GUI_APPLE_RES_DIR}/muon.icns) + set_source_files_properties(${myApp_ICON} PROPERTIES MACOSX_PACKAGE_LOCATION "Resources") + + add_executable(muondetector-gui MACOSX_BUNDLE ${myApp_ICON} ${MUONDETECTOR_GUI_SOURCE_FILES} ${MUONDETECTOR_GUI_HEADER_FILES} ${MUONDETECTOR_GUI_UI_FILES} ${MUONDETECTOR_GUI_RESOURCE_FILES} ${qml_QRC} ) + + set_target_properties(muondetector-gui PROPERTIES MACOSX_BUNDLE_INFO_PLIST ${MUONDETECTOR_GUI_APPLE_RES_DIR}/Info.plist.in) + +elseif(WIN32) + +add_executable(muondetector-gui WIN32 ${MUONDETECTOR_GUI_SOURCE_FILES} ${MUONDETECTOR_GUI_HEADER_FILES} ${MUONDETECTOR_GUI_UI_FILES} ${MUONDETECTOR_GUI_RESOURCE_FILES} ${qml_QRC}) + +else() + add_executable(muondetector-gui ${MUONDETECTOR_GUI_SOURCE_FILES} ${MUONDETECTOR_GUI_HEADER_FILES} ${MUONDETECTOR_GUI_UI_FILES} ${MUONDETECTOR_GUI_RESOURCE_FILES} ${qml_QRC}) + +endif() + + add_dependencies(muondetector-gui muondetector-shared) set_target_properties(muondetector-gui PROPERTIES POSITION_INDEPENDENT_CODE 1) @@ -155,29 +154,27 @@ target_include_directories(muondetector-gui PUBLIC ) if(WIN32) -target_compile_definitions(muondetector-gui PUBLIC QWT_DLL) +#target_compile_definitions(muondetector-gui PUBLIC QWT_DLL) -target_include_directories(muondetector-gui PUBLIC - $ - $ - $ - $ - ${Qt5Widgets_INCLUDE_DIRS} - ${Qt5Svg_INCLUDE_DIRS} - ${Qt5Network_INCLUDE_DIRS} - ${Qt5Quick_INCLUDE_DIRS} - ${Qt5QuickWidgets_INCLUDE_DIRS} - ${Qt5Qml_INCLUDE_DIRS} - ) -target_link_directories(muondetector-gui PUBLIC - "${QWT_DIR}/lib/" +target_link_libraries(muondetector-gui + Qt5::Network Qt5::Svg Qt5::Widgets Qt5::Gui Qt5::Quick Qt5::QuickWidgets Qt5::Qml + muondetector-shared + pthread + ${QWT} ) +elseif(APPLE) + target_link_libraries(muondetector-gui Qt5::Network Qt5::Svg Qt5::Widgets Qt5::Gui Qt5::Quick Qt5::QuickWidgets Qt5::Qml muondetector-shared - qwt.lib + pthread ) +#strip muss im Bundle erfolgen +if (CMAKE_BUILD_TYPE STREQUAL Release) + add_custom_command(TARGET muondetector-gui POST_BUILD + COMMAND ${CMAKE_STRIP} "${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/muondetector-gui.app/Contents/MacOS/muondetector-gui") +endif () else() @@ -187,13 +184,12 @@ target_link_libraries(muondetector-gui pthread qwt-qt5 ) - - if (CMAKE_BUILD_TYPE STREQUAL Release) add_custom_command(TARGET muondetector-gui POST_BUILD COMMAND ${CMAKE_STRIP} "${CMAKE_RUNTIME_OUTPUT_DIRECTORY}/muondetector-gui") endif () + install(FILES "${MUONDETECTOR_GUI_CONFIG_DIR}/muon.ico" DESTINATION "share/pixmaps/" COMPONENT gui) install(FILES "${MUONDETECTOR_GUI_CONFIG_DIR}/muondetector-gui.desktop" DESTINATION "share/applications/" COMPONENT gui) endif() @@ -201,7 +197,15 @@ endif() install(TARGETS muondetector-gui DESTINATION bin COMPONENT gui) -if(WIN32) +if(APPLE) +include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/Macdeployqt.cmake") +set(macdeploy_options + -qmldir="${MUONDETECTOR_GUI_QML_DIR}" +) # additional options for macdeployqt + +macdeployqt(muondetector-gui "${PROJECT_BINARY_DIR}/bin" "${macdeploy_options}") + +elseif(WIN32) include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/Windeployqt.cmake") set(windeploy_options @@ -210,35 +214,41 @@ set(windeploy_options -printsupport ) # additional options for windeployqt.exe - windeployqt(muondetector-gui "${PROJECT_BINARY_DIR}/bin" "${windeploy_options}") # create a list of files to copy -set( THIRD_PARTY_DLLS +message(STATUS "sdk: ${SDKROOT}") +set( COPY_DLLS "${QWT_DIR}/lib/qwt.dll" + "${SDKROOT}/bin/libwinpthread-1.dll" + "${SDKROOT}/bin/libstdc++-6.dll" + "${SDKROOT}/bin/libgcc_s_seh-1.dll" + "${QTTOOLS}/OpenSSL/Win_x64/bin/libssl-1_1-x64.dll" + "${QTTOOLS}/OpenSSL/Win_x64/bin/libcrypto-1_1-x64.dll" ) # do the copying -foreach( file_i ${THIRD_PARTY_DLLS}) +foreach( file_i ${COPY_DLLS}) add_custom_command( TARGET muondetector-gui POST_BUILD COMMAND ${CMAKE_COMMAND} -E copy "${file_i}" - "${PROJECT_BINARY_DIR}/bin/" + "${PROJECT_BINARY_DIR}/output/bin/" ) install(FILES "${file_i}" DESTINATION "bin" COMPONENT gui) endforeach( file_i ) - set(CPACK_GENERATOR "NSIS") set(CPACK_PACKAGE_DESCRIPTION_FILE "${MUONDETECTOR_GUI_CONFIG_DIR}/description.txt") set(CPACK_NSIS_MODIFY_PATH ON) -include(InstallRequiredSystemLibraries) -#set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") +set(CPACK_PACKAGE_NAME "muondetector-gui") +set(CPACK_SOURCE_PACKAGE_FILE_NAME "${CPACK_PACKAGE_NAME}-${CPACK_PACKAGE_VERSION}") + +include(InstallRequiredSystemLibraries) # There is a bug in NSI that does not handle full UNIX paths properly. # Make sure there is at least one set of four backlashes. -#set(CPACK_NSIS_INSTALLED_ICON_NAME "bin\\\\muondetector-gui.exe") +set(CPACK_NSIS_INSTALLED_ICON_NAME "bin\\\\muondetector-gui.exe") set(CPACK_NSIS_DISPLAY_NAME "Muondetector gui") set(CPACK_NSIS_HELP_LINK "https://muonpi.org") set(CPACK_NSIS_URL_INFO_ABOUT "https://muonpi.org") diff --git a/source/cmake/library.cmake b/cmake/library.cmake similarity index 64% rename from source/cmake/library.cmake rename to cmake/library.cmake index 5877d3ff..4f153a37 100644 --- a/source/cmake/library.cmake +++ b/cmake/library.cmake @@ -3,50 +3,6 @@ set(MUONDETECTOR_LIBRARY_HEADER_DIR "${CMAKE_CURRENT_SOURCE_DIR}/library/include set(MUONDETECTOR_LIBRARY_CONFIG_DIR "${CMAKE_CURRENT_SOURCE_DIR}/library/config") set(LIBRARY_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/library/include/") -if(WIN32) - set(QWT_DIR "C:/Qwt-6.1.4") - set(OPENSSL_DIR "C:/Qt/Tools/OpenSSL/Win_x64") - set(CRYPTOPP_DIR "C:/cryptopp") - list(APPEND CMAKE_PREFIX_PATH "C:/Qt/5.15.1/msvc2019_64/lib/cmake/Qt5QuickCompiler") - list(APPEND CMAKE_PREFIX_PATH "C:/Qt/5.15.1/msvc2019_64/lib/cmake/Qt5") - - if (MSVC) - if("${MSVC_RUNTIME}" STREQUAL "") - set(MSVC_RUNTIME "static") - endif() - # Set compiler options. - set(variables - CMAKE_C_FLAGS_DEBUG - CMAKE_C_FLAGS_MINSIZEREL - CMAKE_C_FLAGS_RELEASE - CMAKE_C_FLAGS_RELWITHDEBINFO - CMAKE_CXX_FLAGS_DEBUG - CMAKE_CXX_FLAGS_MINSIZEREL - CMAKE_CXX_FLAGS_RELEASE - CMAKE_CXX_FLAGS_RELWITHDEBINFO - ) - if(${MSVC_RUNTIME} STREQUAL "static") - message(STATUS - "MSVC -> forcing use of statically-linked runtime." - ) - foreach(variable ${variables}) - if(${variable} MATCHES "/MD") - string(REGEX REPLACE "/MD" "/MT" ${variable} "${${variable}}") - endif() - endforeach() - else() - message(STATUS - "MSVC -> forcing use of dynamically-linked runtime." - ) - foreach(variable ${variables}) - if(${variable} MATCHES "/MT") - string(REGEX REPLACE "/MT" "/MD" ${variable} "${${variable}}") - endif() - endforeach() - endif() - endif() - -endif() find_package(Qt5 COMPONENTS Network REQUIRED) @@ -60,6 +16,7 @@ set(MUONDETECTOR_LIBRARY_SOURCE_FILES "${MUONDETECTOR_LIBRARY_SRC_DIR}/config.cpp" "${MUONDETECTOR_LIBRARY_SRC_DIR}/tcpconnection.cpp" "${MUONDETECTOR_LIBRARY_SRC_DIR}/tcpmessage.cpp" + "${MUONDETECTOR_LIBRARY_SRC_DIR}/histogram.cpp" ) set(MUONDETECTOR_LIBRARY_HEADER_FILES diff --git a/cmake/version.cmake b/cmake/version.cmake new file mode 100644 index 00000000..3b600f1e --- /dev/null +++ b/cmake/version.cmake @@ -0,0 +1,4 @@ +set(PROJECT_VERSION_MAJOR 2) +set(PROJECT_VERSION_MINOR 0) +set(PROJECT_VERSION_PATCH 2) +set(PROJECT_VERSION_ADDITIONAL "") diff --git a/source/config/copyright b/config/copyright similarity index 100% rename from source/config/copyright rename to config/copyright diff --git a/source/config/license b/config/license similarity index 100% rename from source/config/license rename to config/license diff --git a/source/daemon/LICENSE b/daemon/LICENSE similarity index 100% rename from source/daemon/LICENSE rename to daemon/LICENSE diff --git a/source/daemon/README b/daemon/README similarity index 100% rename from source/daemon/README rename to daemon/README diff --git a/source/daemon/apt_cache_search.sh b/daemon/apt_cache_search.sh similarity index 100% rename from source/daemon/apt_cache_search.sh rename to daemon/apt_cache_search.sh diff --git a/source/daemon/config/changelog b/daemon/config/changelog similarity index 100% rename from source/daemon/config/changelog rename to daemon/config/changelog diff --git a/source/daemon/config/conffiles b/daemon/config/conffiles similarity index 100% rename from source/daemon/config/conffiles rename to daemon/config/conffiles diff --git a/source/daemon/config/muondetector-daemon.1 b/daemon/config/muondetector-daemon.1 similarity index 100% rename from source/daemon/config/muondetector-daemon.1 rename to daemon/config/muondetector-daemon.1 diff --git a/source/daemon/config/muondetector-daemon.service b/daemon/config/muondetector-daemon.service similarity index 80% rename from source/daemon/config/muondetector-daemon.service rename to daemon/config/muondetector-daemon.service index 67b79369..be7291c1 100644 --- a/source/daemon/config/muondetector-daemon.service +++ b/daemon/config/muondetector-daemon.service @@ -1,13 +1,13 @@ [Unit] Description=muondetector-daemon - Daemon for custom muondetector board -After=sockets.target +After=sockets.target network-online.target [Service] Type=simple User=muonuser ExecStart=/usr/bin/muondetector-daemon -c ExecStop=/bin/kill $MAINPID -Restart=on-abnormal +Restart=always TimeoutSec=2 [Install] diff --git a/source/daemon/config/muondetector-login b/daemon/config/muondetector-login similarity index 100% rename from source/daemon/config/muondetector-login rename to daemon/config/muondetector-login diff --git a/source/daemon/config/muondetector-login.1 b/daemon/config/muondetector-login.1 similarity index 100% rename from source/daemon/config/muondetector-login.1 rename to daemon/config/muondetector-login.1 diff --git a/source/daemon/config/muondetector.conf b/daemon/config/muondetector.conf similarity index 100% rename from source/daemon/config/muondetector.conf rename to daemon/config/muondetector.conf diff --git a/source/daemon/config/pigpiod.conf b/daemon/config/pigpiod.conf similarity index 100% rename from source/daemon/config/pigpiod.conf rename to daemon/config/pigpiod.conf diff --git a/source/daemon/config/postinst b/daemon/config/postinst similarity index 100% rename from source/daemon/config/postinst rename to daemon/config/postinst diff --git a/source/daemon/config/preinst b/daemon/config/preinst similarity index 100% rename from source/daemon/config/preinst rename to daemon/config/preinst diff --git a/source/daemon/config/prerm b/daemon/config/prerm similarity index 100% rename from source/daemon/config/prerm rename to daemon/config/prerm diff --git a/source/daemon/include/calibration.h b/daemon/include/calibration.h similarity index 56% rename from source/daemon/include/calibration.h rename to daemon/include/calibration.h index 0c39eab9..6bfcca5c 100644 --- a/source/daemon/include/calibration.h +++ b/daemon/include/calibration.h @@ -1,42 +1,41 @@ #ifndef CALIBRATION_H #define CALIBRATION_H +// clang-format off +#include "utility/custom_io_operators.h" +#include +#include "hardware/i2cdevices.h" +// clang-format on + // for sig handling: -#include #include -#include -#include +#include #include #include -#include -#include -#include -#include "i2c/i2cdevices.h" +#include +#include +#include const uint16_t CALIB_HEADER = 0x2019; struct CalibStruct; - -//static const CalibStruct InvalidCalibStruct = CalibStruct( "", "", 0, "" ); - // initialization of calib items // meaning of entries (columns is: // static const std::vector> CALIBITEMS = { - std::make_tuple("VERSION", "UINT8", "3") , - std::make_tuple("FEATURE_FLAGS", "UINT8", "0") , - std::make_tuple("CALIB_FLAGS", "UINT8", "0") , - std::make_tuple("DATE", "UINT32", "0") , - std::make_tuple("RSENSE", "UINT16", "100") , - std::make_tuple("VDIV", "UINT16", "1100") , - std::make_tuple("COEFF0", "FLOAT", "0.0") , - std::make_tuple("COEFF1", "FLOAT", "1.0") , - std::make_tuple("COEFF2", "FLOAT", "0.0") , - std::make_tuple("COEFF3", "FLOAT", "1.0") , - std::make_tuple("WRITE_CYCLES", "UINT32", "1") - }; - + std::make_tuple("VERSION", "UINT8", "3"), + std::make_tuple("FEATURE_FLAGS", "UINT8", "0"), + std::make_tuple("CALIB_FLAGS", "UINT8", "0"), + std::make_tuple("DATE", "UINT32", "0"), + std::make_tuple("RSENSE", "UINT16", "100"), + std::make_tuple("VDIV", "UINT16", "1100"), + std::make_tuple("COEFF0", "FLOAT", "0.0"), + std::make_tuple("COEFF1", "FLOAT", "1.0"), + std::make_tuple("COEFF2", "FLOAT", "0.0"), + std::make_tuple("COEFF3", "FLOAT", "1.0"), + std::make_tuple("WRITE_CYCLES", "UINT32", "1") +}; class ShowerDetectorCalib { @@ -44,7 +43,11 @@ class ShowerDetectorCalib { static const CalibStruct InvalidCalibStruct; ShowerDetectorCalib() { init(); } - ShowerDetectorCalib(EEPROM24AA02 *eep) : fEeprom(eep) { init(); } + ShowerDetectorCalib( std::shared_ptr eep ) + : fEeprom( eep ) + { + init(); + } bool readFromEeprom(); bool writeToEeprom(); @@ -65,8 +68,8 @@ class ShowerDetectorCalib { uint64_t getSerialID(); template - static void getValueFromString(const std::string& valstr, T& value) { - //value = std::stoi(valstr, nullptr); + static void getValueFromString(const std::string& valstr, T& value) + { std::istringstream istr(valstr); istr >> value; } @@ -75,10 +78,9 @@ class ShowerDetectorCalib { void init(); void buildCalibList(); -// void updateBuffer(); - std::vector fCalibList; - EEPROM24AA02 *fEeprom = nullptr; + std::shared_ptr fEeprom { }; + //EEPROM24AA02* fEeprom = nullptr; uint8_t fEepBuffer[256]; bool fEepromValid = false; bool fValid = false; @@ -90,8 +92,6 @@ template void ShowerDetectorCalib::setCalibItem(const std::string& name, T value) { CalibStruct item { getCalibItem(name) }; - //std::cout<<"*** ShowerDetectorCalib::setCalibItem(const std::string&, T) ***"<(const std::string&, unsigned int); template void ShowerDetectorCalib::setCalibItem(const std::string&, int); -//template void ShowerDetectorCalib::setCalibItem(const std::string&, float); - - #endif // CALIBRATION_H diff --git a/source/daemon/include/daemon.h b/daemon/include/daemon.h similarity index 61% rename from source/daemon/include/daemon.h rename to daemon/include/daemon.h index ca474b44..71969a49 100644 --- a/source/daemon/include/daemon.h +++ b/daemon/include/daemon.h @@ -2,140 +2,75 @@ #define DAEMON_H #include +#include #include -#include #include -#include +#include #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +// clang-format off +#include "qtserialublox.h" +#include "utility/filehandler.h" +#include "calibration.h" +// clang-format on + +#include "utility/custom_io_operators.h" +#include "histogram.h" +#include "logengine.h" +#include "utility/ratebuffer.h" +#include "logparameter.h" +#include "mqtthandler.h" +#include "pigpiodhandler.h" +#include "tcpconnection.h" +#include "hardware/spidevices.h" +#include "hardware/device_types.h" // for sig handling: -#include -#include #include +#include +#include struct CalibStruct; struct UbxTimeMarkStruct; +class Property; +enum GPIO_SIGNAL; -//enum GPIO_SIGNAL; - -class Property { -public: - Property()=default; - - template - Property(const T& val) : name(""), unit ("") { - typeId = qMetaTypeId(); - if (typeId==QMetaType::UnknownType) { - typeId = qRegisterMetaType(); - } - value=QVariant(val); - updated=true; - } - - template - Property(const QString& a_name, const T& val, const QString& a_unit = "") - : name(a_name), unit(a_unit) - { - typeId = qMetaTypeId(); - if (typeId==QMetaType::UnknownType) { - typeId = qRegisterMetaType(); - } - value=QVariant(val); - updated=true; - } - - Property(const Property& prop) = default; - Property& operator=(const Property& prop) { - name=prop.name; - unit=prop.unit; - value=prop.value; - typeId=prop.typeId; - updated=prop.updated; - return *this; - } - - Property& operator=(const QVariant& val) { - value = val; - //lastUpdate = std::chrono::system_clock::now(); - updated = true; - return *this; - } - const QVariant& operator()() { - updated = false; - return value; - } - - bool isUpdated() const { return updated; } -// QMetaType::Type type() const { return static_cast(value.type()); } - int type() const { return typeId; } - - QString name=""; - QString unit=""; - -private: - QVariant value; - bool updated=false; - int typeId=0; -}; - -struct RateScanInfo { - uint8_t origPcaMask=0; - GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_SIGNAL; - uint16_t lastEvtCounter=0; - uint8_t thrChannel=0; - float origThr=3.3; - float thrIncrement=0.1; - float minThr=0.05; - float maxThr=3.3; - float currentThr=0.; - uint16_t nrLoops=0; - uint16_t currentLoop=0; -}; - -struct RateScan { -// void addScanPoint(double scanpar, double a_rate) { scanMap[scanpar].append(a_rate); } - uint8_t origPcaMask=0; - GPIO_SIGNAL origEventTrigger=GPIO_SIGNAL::UNDEFINED_SIGNAL; - float origScanPar=3.3; - double minScanPar=0.; - double maxScanPar=1.; - double currentScanPar=0.; - double scanParIncrement=0.; - uint32_t currentCounts=0; - double currentTimeInterval=0.; - double maxTimeInterval=1.; - uint16_t nrLoops=0; - uint16_t currentLoop=0; - QMap scanMap; -}; - -class Daemon : public QTcpServer -{ +class Daemon : public QTcpServer { Q_OBJECT public: - Daemon(QString username, QString password, QString new_gpsdevname, int new_verbose, quint8 new_pcaPortMask, - float *new_dacThresh, float new_biasVoltage, bool bias_ON, bool new_dumpRaw, int new_baudrate, - bool new_configGnss, unsigned int new_eventTrigger, QString new_PeerAddress, quint16 new_PpeerPort, - QString new_serverAddress, quint16 new_serverPort, bool new_showout, bool new_showin, bool preamp1, bool preamp2, bool gain, QString station_ID, - bool new_polarity1, bool new_polarity2, QObject *parent = 0); + struct configuration { + QString username; + QString password; + QString gpsdevname { "" }; + int verbose { 0 }; + quint8 pcaPortMask { 0 }; + std::array dacThresh { -1.0F, -1.0F }; + float biasVoltage { -1.0F }; + bool bias_ON { false }; + bool dumpRaw; + int baudrate { 9600 }; + bool configGnss { false }; + GPIO_SIGNAL eventTrigger { EVT_XOR }; + QString peerAddress { "" }; + quint16 peerPort { 0 }; + QString serverAddress { "" }; + quint16 serverPort { 0 }; + bool showout { false }; + bool showin { false }; + std::array preamp { false, false }; + bool gain { false }; + QString station_ID { "0" }; + std::array polarity { true, true }; + int maxGeohashLength { MuonPi::Settings::log.max_geohash_length }; + bool storeLocal { false }; + }; + + Daemon(configuration cfg, QObject* parent = nullptr); + ~Daemon() override; void configGps(); void configGpsForVersion(); @@ -182,7 +117,6 @@ public slots: void sampleAdcEvent(uint8_t channel); void getTemperature(); void scanI2cBus(); - //void onUBXReceivedTimeTM2(timespec rising, timespec falling, uint32_t accEst, bool valid, uint8_t timeBase, bool utcAvailable); void onUBXReceivedTimeTM2(const UbxTimeMarkStruct& tm); void onLogParameterPolled(); void sendMqttStatus(bool connected); @@ -213,25 +147,25 @@ public slots: void GpioSetState(unsigned int gpio, bool state); void GpioRegisterForCallback(unsigned int gpio, PigpiodHandler::EventEdge edge); // false=falling, true=rising void UBXSetCfgTP5(const UbxTimePulseStruct& tp); - void UBXSetAopCfg(bool enable=true, uint16_t maxOrbErr=0); - void UBXSaveCfg(uint8_t devMask=QtSerialUblox::DEV_BBR | QtSerialUblox::DEV_FLASH); - void setSamplingTriggerSignal(unsigned int gpio); + void UBXSetAopCfg(bool enable = true, uint16_t maxOrbErr = 0); + void UBXSaveCfg(uint8_t devMask = QtSerialUblox::DEV_BBR | QtSerialUblox::DEV_FLASH); + void setSamplingTriggerSignal(GPIO_SIGNAL signalName); void timeMarkIntervalCountUpdate(uint16_t newCounts, double lastInterval); void requestMqttConnectionStatus(); - void eventMessage(const QString& messageString); - void eventInterval(quint64 nsecs); + void eventMessage(const QString& messageString); + void eventInterval(quint64 nsecs); private slots: void onRateBufferReminder(); void updateOledDisplay(); void aquireMonitoringParameters(); - void doRateScanIteration(RateScanInfo* info); - + void onStatusLed1Event( int onTimeMs ); + void onStatusLed2Event( int onTimeMs ); private: void incomingConnection(qintptr socketDescriptor) override; void setPcaChannel(uint8_t channel); // channel 0 to 3 - // 0: coincidence ; 1: xor ; 2: discr 1 ; 3: discr 2 + // 0: coincidence ; 1: xor ; 2: discr 1 ; 3: discr 2 void setEventTriggerSelection(GPIO_SIGNAL signal); void sendPcaChannel(); void sendEventTriggerSelection(); @@ -246,7 +180,7 @@ private slots: void setBiasStatus(bool status); void sendPreampStatus(uint8_t channel); void sendPolarityStatus(); - void setUbxMsgRates(QMap& ubxMsgRates); + void setUbxMsgRates(QMap& ubxMsgRates); void sendUbxMsgRates(); void sendGpioRates(int number = 0, quint8 whichRate = 0); void sendI2cStats(); @@ -259,36 +193,36 @@ private slots: void setupHistos(); void rescaleHisto(Histogram& hist, double center, double width); void rescaleHisto(Histogram& hist, double center); - void checkRescaleHisto(Histogram& hist, double newValue); void clearHisto(const QString& histoName); - void setAdcSamplingMode(quint8 mode); - void startRateScan(uint8_t channel); + void setAdcSamplingMode(ADC_SAMPLING_MODE mode); void printTimestamp(); void delay(int millisecondsWait); + void onAdcSampleReady(ADS1115::Sample sample); void rateCounterIntervalActualisation(); qreal getRateFromCounts(quint8 which_rate); void clearRates(); - MCP4728* dac = nullptr; - ADS1115* adc = nullptr; - PCA9536* pca = nullptr; - LM75* lm75 = nullptr; - EEPROM24AA02* eep = nullptr; - UbloxI2c* ubloxI2c = nullptr; - Adafruit_SSD1306* oled = nullptr; - float biasVoltage = 0.; + std::shared_ptr> temp_sensor_p; + std::shared_ptr> adc_p; + std::shared_ptr> dac_p; + std::shared_ptr> eep_p; + std::shared_ptr> io_extender_p; + std::shared_ptr oled_p { }; + std::shared_ptr ublox_i2c_p { }; + + float biasVoltage = 0.; bool biasON = false; GPIO_SIGNAL eventTrigger { UNDEFINED_SIGNAL }; bool gainSwitch = false; bool preampStatus[2]; uint8_t pcaPortMask = 0; - QVector dacThresh; // do not give values here because of push_back in constructor of deamon + QVector dacThresh; // do not give values here because of push_back in constructor of deamon QPointer pigHandler; QPointer tdc7200; bool spiDevicePresent = false; QPointer tcpConnection; - QMap msgRateCfgs; + QMap msgRateCfgs; int waitingForAppliedMsgRate = 0; QPointer qtGps; QPointer tcpServer; @@ -299,8 +233,8 @@ private slots: int verbose, baudrate; int gpsTimeout = 5000; bool dumpRaw, configGnss, showout, showin; - bool mqttConnectionStatus=false; - bool polarity1 = true; // input polarity switch: true=pos, false=neg + bool mqttConnectionStatus = false; + bool polarity1 = true; // input polarity switch: true=pos, false=neg bool polarity2 = true; // file handling @@ -325,13 +259,6 @@ private slots: ShowerDetectorCalib* calib = nullptr; // histograms -/* - Histogram geoHeightHisto, geoLonHisto, geoLatHisto, - weightedGeoHeightHisto, - pulseHeightHisto, adcSampleTimeHisto, tdc7200Histo, - ubxTimeLengthHisto, eventIntervalHisto, eventIntervalShortHisto, - ubxTimeIntervalHisto, tpTimeDiffHisto; -*/ QMap histoMap; // others @@ -339,16 +266,15 @@ private slots: timespec startOfProgram, lastRateInterval; quint32 rateBufferTime = 60; // in s: 60 seconds quint32 rateBufferInterval = 2000; // in ms: 2 seconds - quint32 rateMaxShowInterval = 60*60*1000; // in ms: 1 hour + quint32 rateMaxShowInterval = 60 * 60 * 1000; // in ms: 1 hour QTimer rateBufferReminder; QTimer oledUpdateTimer; - QList andCounts,xorCounts; + QList andCounts, xorCounts; UbxDopStruct currentDOP; - //timespec lastTimestamp = { 0, 0 }; Property nrSats, nrVisibleSats, fixStatus; QVector peerList; QList adcSamplesBuffer; - uint8_t adcSamplingMode = ADC_MODE_PEAK; + ADC_SAMPLING_MODE adcSamplingMode = ADC_SAMPLING_MODE::PEAK; qint16 currentAdcSampleIndex = -1; QTimer samplingTimer; QTimer parameterMonitorTimer; @@ -362,6 +288,8 @@ private slots: QPointer pigThread; QPointer gpsThread; QPointer tcpThread; + + configuration config; }; #endif // DAEMON_H diff --git a/daemon/include/hardware/device_types.h b/daemon/include/hardware/device_types.h new file mode 100644 index 00000000..b62b06b5 --- /dev/null +++ b/daemon/include/hardware/device_types.h @@ -0,0 +1,140 @@ +#ifndef _DEVICE_TYPES_H_ +#define _DEVICE_TYPES_H_ + +#include +#include +#include +#include + +enum class DeviceType { + ADC, DAC, IO_EXTENDER, TEMP, PRESSURE, HUMIDITY, EEPROM, BUS_SWITCH, RTC, TDC, DISPLAY, MAGNETIC_FIELD, GYRO, ACCELERATION, OTHER +}; + +const std::map DeviceTypes = { + { DeviceType::ADC, "ADC"}, + { DeviceType::DAC, "DAC" }, + { DeviceType::IO_EXTENDER, "IO_EXTENDER" }, + { DeviceType::TEMP, "TEMP" }, + { DeviceType::PRESSURE, "PRESSURE" }, + { DeviceType::HUMIDITY, "HUMIDITY" }, + { DeviceType::EEPROM, "EEPROM" }, + { DeviceType::BUS_SWITCH, "BUS_SWITCH" }, + { DeviceType::RTC, "RTC" }, + { DeviceType::TDC, "TDC" }, + { DeviceType::DISPLAY, "DISPLAY" }, + { DeviceType::MAGNETIC_FIELD, "MAGNETIC_FIELD" }, + { DeviceType::GYRO, "GYRO" }, + { DeviceType::ACCELERATION, "ACCELERATION" }, + { DeviceType::OTHER, "OTHER" } +}; + + +template +class DeviceFunctionBase { +public: + DeviceType type { T }; + const std::string& getName() { return fName; } + void setName( const std::string& name ) { fName = name; } + static const std::string typeString() { + auto it = DeviceTypes.find( T ); + if ( it != DeviceTypes.end() ) return it->second; + return "UNKNOWN"; + } + /** @brief probe the presence of the device + * This method provides a functionality to find out wether the given device is responsive. + * @return Device was responding (true = success) + * @note The probing should be non-invasive, i.e. most devices will not change settings when a read access is performed. + * This method must be implemented in the derived classes. + * */ + virtual bool probeDevicePresence() = 0; +protected: + std::string fName { DeviceTypes.at(T)+"_DEVICE" }; +}; + +/// abstract empty general template class for device functions +/// all methods which are specific for a device function shall be declared in the template specializations of this class +template +class DeviceFunction : public DeviceFunctionBase { +}; + + +// +// here follow the specializations for specific device functions +// + +/** specialization for temperature sensor devices + the specialization has a getTemperature() method, which must be implemented in the derived class +*/ +template <> +class DeviceFunction : public DeviceFunctionBase { +public: + virtual float getTemperature() = 0; + float lastTemperatureValue() const { return fLastTemp; } +protected: + float fLastTemp; +}; + +/** specialization for ADCs + the specialization has getVoltage(), getSample() and triggerConversion() methods, which must be implemented in the derived class +*/ +template <> +class DeviceFunction : public DeviceFunctionBase { +public: + struct Sample { + std::chrono::time_point timestamp; + int value; + float voltage; + float lsb_voltage; + unsigned int channel; + bool operator==(const Sample& other); + bool operator!=(const Sample& other); + }; + static constexpr Sample InvalidSample { std::chrono::steady_clock::time_point::min(), 0, 0., 0., 0 }; + + virtual double getVoltage( unsigned int channel = 0 ) = 0; + virtual Sample getSample( unsigned int channel = 0 ) = 0; + virtual bool triggerConversion( unsigned int channel ) = 0; + void registerConversionReadyCallback(std::function fn) { fConvReadyFn = fn; } + double getLastConvTime() const { return fLastConvTime; } +protected: + std::function fConvReadyFn { }; + double fLastConvTime { 0. }; +}; + +/** specialization for DACs + the specialization has a setVoltage() method, which must be implemented in the derived class +*/ +template <> +class DeviceFunction : public DeviceFunctionBase { +public: + virtual bool setVoltage( unsigned int channel, float voltage ) = 0; + virtual bool storeSettings() = 0; + double getLastConvTime() const { return fLastConvTime; } +protected: + double fLastConvTime { 0. }; +}; + +/** specialization for EEPROMs + the specialization has readBytes() and writeBytes methods, which must be implemented in the derived class +*/ +template <> +class DeviceFunction : public DeviceFunctionBase { +public: + virtual int16_t readBytes(uint8_t regAddr, uint16_t length, uint8_t* data) = 0; + virtual bool writeBytes(uint8_t addr, uint16_t length, uint8_t* data) = 0; +protected: +}; + +/** specialization for I/O extenders + the specialization has setOutputPorts(), setOutputState and getInputState methods, which must be implemented in the derived class +*/ +template <> +class DeviceFunction : public DeviceFunctionBase { +public: + virtual bool setOutputPorts(uint8_t portMask) = 0; + virtual bool setOutputState(uint8_t portMask) = 0; + virtual uint8_t getInputState() = 0; +protected: +}; + +#endif // !_DEVICE_TYPES_H_ \ No newline at end of file diff --git a/daemon/include/hardware/i2c/Adafruit_GFX.h b/daemon/include/hardware/i2c/Adafruit_GFX.h new file mode 100644 index 00000000..51c44e8a --- /dev/null +++ b/daemon/include/hardware/i2c/Adafruit_GFX.h @@ -0,0 +1,109 @@ +/****************************************************************** + This is the core graphics library for all our displays, providing + basic graphics primitives (points, lines, circles, etc.). It needs + to be paired with a hardware-specific library for each display + device we carry (handling the lower-level functions). + + Adafruit invests time and resources providing this open + source code, please support Adafruit and open-source hardware + by purchasing products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, check license.txt for more information. + All text above must be included in any redistribution. + +02/18/2013 Charles-Henri Hallard (http://hallard.me) + Modified for compiling and use on Raspberry ArduiPi Board + LCD size and connection are now passed as arguments on + the command line (no more #define on compilation needed) + ArduiPi project documentation http://hallard.me/arduipi + + ******************************************************************/ + +#ifndef _ADAFRUIT_GFX_H +#define _ADAFRUIT_GFX_H + +#include +#include +#include + +#define adafruit_swap(a, b) \ + { \ + int16_t t = a; \ + a = b; \ + b = t; \ + } + +class Adafruit_GFX { +public: + Adafruit_GFX() = default; + void constructor(int16_t w, int16_t h); + + // this must be defined by the subclass + virtual void drawPixel(int16_t x, int16_t y, uint16_t color) = 0; + virtual void invertDisplay(bool i); + + void printf(const char* format, ...); + void print(const char* string); + + // these are 'generic' drawing functions, so we can share them! + virtual void drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + uint16_t color); + virtual void drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color); + virtual void drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color); + virtual void drawRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color); + virtual void fillRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color); + + void drawVerticalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent); + void drawHorizontalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent); + + virtual void fillScreen(uint16_t color); + + void drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color); + void drawCircleHelper(int16_t x0, int16_t y0, + int16_t r, uint8_t cornername, uint16_t color); + void fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color); + void fillCircleHelper(int16_t x0, int16_t y0, int16_t r, + uint8_t cornername, int16_t delta, uint16_t color); + + void drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + int16_t x2, int16_t y2, uint16_t color); + void fillTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + int16_t x2, int16_t y2, uint16_t color); + void drawRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h, + int16_t radius, uint16_t color); + void fillRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h, + int16_t radius, uint16_t color); + + void drawBitmap(int16_t x, int16_t y, + const uint8_t* bitmap, int16_t w, int16_t h, + uint16_t color); + void drawChar(int16_t x, int16_t y, unsigned char c, + uint16_t color, uint16_t bg, uint8_t size); + virtual size_t write(uint8_t); + + void setCursor(int16_t x, int16_t y); + void setTextColor(uint16_t c); + void setTextColor(uint16_t c, uint16_t bg); + void setTextSize(uint8_t s); + void setTextWrap(bool w); + + int16_t height(void); + int16_t width(void); + + void setRotation(uint8_t r); + uint8_t getRotation(void); + +protected: + int16_t WIDTH, HEIGHT; // this is the 'raw' display w/h - never changes + int16_t _width, _height; // dependent on rotation + int16_t cursor_x, cursor_y; + uint16_t textcolor, textbgcolor; + uint8_t textsize; + uint8_t rotation; + bool wrap; // If set, 'wrap' text at right edge of display +}; + +#endif diff --git a/daemon/include/hardware/i2c/adafruit_ssd1306.h b/daemon/include/hardware/i2c/adafruit_ssd1306.h new file mode 100644 index 00000000..ac1c832a --- /dev/null +++ b/daemon/include/hardware/i2c/adafruit_ssd1306.h @@ -0,0 +1,103 @@ +#ifndef _ADAFRUIT_SSD1306_H_ +#define _ADAFRUIT_SSD1306_H_ + +#include "hardware/i2c/i2cdevice.h" + +#include "hardware/i2c/Adafruit_GFX.h" +// OLED defines +#define OLED_I2C_RESET RPI_V2_GPIO_P1_22 /* GPIO 25 pin 12 */ +// Oled supported display +#define OLED_ADAFRUIT_SPI_128x32 0 +#define OLED_ADAFRUIT_SPI_128x64 1 +#define OLED_ADAFRUIT_I2C_128x32 2 +#define OLED_ADAFRUIT_I2C_128x64 3 +#define OLED_SEEED_I2C_128x64 4 +#define OLED_SEEED_I2C_96x96 5 +#define OLED_LAST_OLED 6 /* always last type, used in code to end array */ + +/********************************************************************* +This is a library for our Monochrome OLEDs based on SSD1306 drivers + +Pick one up today in the adafruit shop! +------> http://www.adafruit.com/category/63_98 + +These displays use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen must be included in any redistribution + +02/18/2013 Charles-Henri Hallard (http://hallard.me) +Modified for compiling and use on Raspberry ArduiPi Board +LCD size and connection are now passed as arguments on +the command line (no more #define on compilation needed) +ArduiPi project documentation http://hallard.me/arduipi + +*********************************************************************/ +class Adafruit_SSD1306 : public i2cDevice, public Adafruit_GFX { +public: + enum { BLACK = 0, + WHITE = 1 }; + + Adafruit_SSD1306() + : i2cDevice(0x3c) + { + fTitle = "SSD1306 OLED"; + init(OLED_ADAFRUIT_I2C_128x64, -1); + } + Adafruit_SSD1306(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "SSD1306 OLED"; + init(OLED_ADAFRUIT_I2C_128x64, -1); + } + Adafruit_SSD1306(uint8_t slaveAddress, uint8_t OLED_TYPE = OLED_ADAFRUIT_I2C_128x64, int8_t rst_pin = -1) + : i2cDevice(slaveAddress) + { + fTitle = "SSD1306 OLED"; + init(OLED_TYPE, rst_pin); + } + + ~Adafruit_SSD1306() { close(); } + + // I2C Init + bool init(uint8_t OLED_TYPE, int8_t RST); + + void select_oled(uint8_t OLED_TYPE); + + void begin(void); + void close(void); + + void ssd1306_command(uint8_t c); + void ssd1306_command(uint8_t c0, uint8_t c1); + void ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2); + void ssd1306_data(uint8_t c); + + void clearDisplay(void); + void invertDisplay(bool inv); + void display(); + + void startscrollright(uint8_t start, uint8_t stop); + void startscrollleft(uint8_t start, uint8_t stop); + + void startscrolldiagright(uint8_t start, uint8_t stop); + void startscrolldiagleft(uint8_t start, uint8_t stop); + void stopscroll(void); + + void drawPixel(int16_t x, int16_t y, uint16_t color); + +private: + uint8_t* poledbuff = nullptr; // Pointer to OLED data buffer in memory + int8_t rst; + int16_t ssd1306_lcdwidth, ssd1306_lcdheight; + uint8_t vcc_type; + + void fastI2Cwrite(uint8_t c); + void fastI2Cwrite(char* tbuf, uint32_t len); +}; +#endif // !_ADAFRUIT_SSD1306_H_ diff --git a/source/daemon/include/i2c/addresses.h b/daemon/include/hardware/i2c/addresses.h similarity index 77% rename from source/daemon/include/i2c/addresses.h rename to daemon/include/hardware/i2c/addresses.h index 4314591c..a687dd37 100644 --- a/source/daemon/include/i2c/addresses.h +++ b/daemon/include/hardware/i2c/addresses.h @@ -11,11 +11,11 @@ #define POTI4_ADDR 0x2c #define EEP_ADDR 0x50 -#define VMEAS_FACTOR (0.165+22.0)/0.165 -#define IMEAS_FACTOR 1./(4.7e-3) +#define VMEAS_FACTOR (0.165 + 22.0) / 0.165 +#define IMEAS_FACTOR 1. / (4.7e-3) #define VMEAS_OFFSET 0.0 #define IMEAS_OFFSET -22.5 #define VTEMP_OFFSET 0.0 -#define VTEMP_SLOPE 0.0 +#define VTEMP_SLOPE 0.0 #define ITEMP_OFFSET 0.0 #define ITEMP_SLOPE 0.1205 diff --git a/daemon/include/hardware/i2c/ads1015.h b/daemon/include/hardware/i2c/ads1015.h new file mode 100644 index 00000000..c7e13a8f --- /dev/null +++ b/daemon/include/hardware/i2c/ads1015.h @@ -0,0 +1,19 @@ +#ifndef _ADS1015_H_ +#define _ADS1015_H_ +#include "hardware/i2c/ads1115.h" + +/* ADS1015: 4(2) ch, 12 bit ADC */ + +class ADS1015 : public ADS1115 { +public: + using ADS1115::ADS1115; + +protected: + inline void init() + { + ADS1115::init(); + fTitle = "ADS1015"; + } +}; + +#endif // !_ADS1015_H_ diff --git a/daemon/include/hardware/i2c/ads1115.h b/daemon/include/hardware/i2c/ads1115.h new file mode 100644 index 00000000..be553bcf --- /dev/null +++ b/daemon/include/hardware/i2c/ads1115.h @@ -0,0 +1,99 @@ +#ifndef _ADS1115_H_ +#define _ADS1115_H_ + +#include +#include +#include +#include + +#include "hardware/i2c/i2cdevice.h" +#include "hardware/device_types.h" + +// ADC ADS1x13/4/5 sampling readout delay +constexpr unsigned int READ_WAIT_DELAY_US_INIT { 10 }; + +/* ADS1115: 4(2) ch, 16 bit ADC */ + +class ADS1115 : public i2cDevice, public DeviceFunction, public static_device_base { +public: + + typedef std::function SampleCallbackType; + + static constexpr int16_t MIN_ADC_VALUE { -32768 }; + static constexpr int16_t MAX_ADC_VALUE { 32767 }; + static constexpr uint16_t FULL_SCALE_RANGE { 65535 }; + + enum CFG_CHANNEL { CH0 = 0, CH1, CH2, CH3 }; + enum CFG_DIFF_CHANNEL { CH0_1 = 0, CH0_3, CH1_3, CH2_3 }; + enum CFG_PGA { PGA6V = 0, PGA4V = 1, PGA2V = 2, PGA1V = 3, PGA512MV = 4, PGA256MV = 5 }; + enum CFG_RATES { SPS8 = 0x00, SPS16 = 0x01, SPS32 = 0x02, SPS64 = 0x03, SPS128 = 0x04, SPS250 = 0x05, SPS475 = 0x06, SPS860 = 0x07 }; + enum class CONV_MODE { UNKNOWN, SINGLE, CONTINUOUS }; + + static auto adcToVoltage( int16_t adc, const CFG_PGA pga_setting ) -> float; + + ADS1115(); + ADS1115(uint8_t slaveAddress); + ADS1115(const char* busAddress, uint8_t slaveAddress); + ADS1115(const char* busAddress, uint8_t slaveAddress, CFG_PGA pga); + virtual ~ADS1115(); + + bool identify() override; + + void setActiveChannel( uint8_t channel, bool differential_mode = false ); + void setPga(CFG_PGA pga) { fPga[0] = fPga[1] = fPga[2] = fPga[3] = pga; } + void setPga(unsigned int pga) { setPga((CFG_PGA)pga); } + void setPga(uint8_t channel, CFG_PGA pga); + void setPga(uint8_t channel, uint8_t pga) { setPga(channel, (CFG_PGA)pga); } + CFG_PGA getPga(int ch) const { return fPga[ch]; } + void setAGC(bool state); + void setAGC(uint8_t channel, bool state); + bool getAGC(uint8_t channel) const; + void setRate(unsigned int rate) { fRate = rate & 0x07; } + unsigned int getRate() const { return fRate; } + bool setLowThreshold(int16_t thr); + bool setHighThreshold(int16_t thr); + int16_t readADC(unsigned int channel); + double getVoltage(unsigned int channel) override; + void getVoltage(unsigned int channel, double& voltage); + void getVoltage(unsigned int channel, int16_t& adc, double& voltage); + //bool devicePresent() override; + void setDiffMode(bool mode) { fDiffMode = mode; } + bool setDataReadyPinMode(); + unsigned int getReadWaitDelay() const { return fReadWaitDelay; } + bool setContinuousSampling( bool cont_sampling = true ); + bool triggerConversion( unsigned int channel ) override; + Sample getSample( unsigned int channel ) override; + Sample conversionFinished(); + bool probeDevicePresence() override { return devicePresent(); } + +protected: + CFG_PGA fPga[4] { PGA4V, PGA4V, PGA4V, PGA4V }; + uint8_t fRate { 0x00 }; + uint8_t fCurrentChannel { 0 }; + uint8_t fSelectedChannel { 0 }; + unsigned int fReadWaitDelay { READ_WAIT_DELAY_US_INIT }; ///< conversion wait time in us + bool fAGC[4] { false, false, false, false }; ///< software agc which switches over to a better pga setting if voltage too low/high + bool fDiffMode { false }; ///< measure differential input signals (true) or single ended (false=default) + CONV_MODE fConvMode { CONV_MODE::UNKNOWN }; + Sample fLastSample[4] { InvalidSample, InvalidSample, InvalidSample, InvalidSample }; + + std::mutex fMutex; + + enum REG : uint8_t { + CONVERSION = 0x00, + CONFIG = 0x01, + LO_THRESH = 0x02, + HI_THRESH = 0x03 + }; + + virtual void init(); + bool writeConfig( bool startNewConversion = false ); + bool setCompQueue( uint8_t bitpattern ); + bool readConversionResult( int16_t& dataword ); + static constexpr auto lsb_voltage( const CFG_PGA pga_setting ) -> float { return ( PGAGAINS[pga_setting]/MAX_ADC_VALUE ); } + void waitConversionFinished(bool& error); +private: + static constexpr float PGAGAINS[8] { 6.144, 4.096, 2.048, 1.024, 0.512, 0.256, 0.256, 0.256 }; +}; + +#endif // !_ADS1115_H_ diff --git a/daemon/include/hardware/i2c/bme280.h b/daemon/include/hardware/i2c/bme280.h new file mode 100644 index 00000000..d6db4ef7 --- /dev/null +++ b/daemon/include/hardware/i2c/bme280.h @@ -0,0 +1,66 @@ +#ifndef _BME280_H_ +#define _BME280_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* BME280 */ +// struct to store temperature, pressure and humidity data in different ways +struct TPH { + uint32_t adc_T; + uint32_t adc_P; + uint32_t adc_H; + double T, P, H; +}; +class BME280 : public i2cDevice { // t_max = 112.8 ms for all three measurements at max oversampling +public: + BME280() + : i2cDevice(0x76) + { + init(); + } + BME280(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + init(); + } + BME280(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + init(); + } + + bool init(); + bool status(); + bool measure(); + uint8_t readConfig(); + uint8_t read_CtrlMeasReg(); + bool writeConfig(uint8_t config); + bool write_CtrlMeasReg(uint8_t config); + bool setMode(uint8_t mode); // 3 bits: "1=sleep", "2=single shot", "3=interval" + bool setTSamplingMode(uint8_t mode); + bool setPSamplingMode(uint8_t mode); + bool setHSamplingMode(uint8_t mode); + bool setDefaultSettings(); + bool softReset(); + void readCalibParameters(); + inline bool isCalibValid() const { return fCalibrationValid; } + uint16_t getCalibParameter(unsigned int param) const; + int32_t readUT(); + int32_t readUP(); + int32_t readUH(); + TPH readTPCU(); + TPH getTPHValues(); + double getTemperature(int32_t adc_T); + double getPressure(signed int adc_P); + double getPressure(signed int adc_P, signed int t_fine); + double getHumidity(int32_t adc_H); + double getHumidity(int32_t adc_H, int32_t t_fine); + +private: + int32_t fT_fine = 0; + unsigned int fLastConvTime; + bool fCalibrationValid; + uint16_t fCalibParameters[18]; // 18x 16-Bit words in 36 8-Bit registers +}; + +#endif // !_BME280_H_ diff --git a/daemon/include/hardware/i2c/bmp180.h b/daemon/include/hardware/i2c/bmp180.h new file mode 100644 index 00000000..cc6fd8b1 --- /dev/null +++ b/daemon/include/hardware/i2c/bmp180.h @@ -0,0 +1,41 @@ +#ifndef _BMP180_H_ +#define _BMP180_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* BMP180 */ + +class BMP180 : public i2cDevice { +public: + BMP180() + : i2cDevice(0x77) + { + fTitle = "BMP180"; + } + BMP180(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "BMP180"; + } + BMP180(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = "BMP180"; + } + + bool init(); + void readCalibParameters(); + inline bool isCalibValid() const { return fCalibrationValid; } + signed int getCalibParameter(unsigned int param) const; + unsigned int readUT(); + unsigned int readUP(uint8_t oss); + double getTemperature(); + double getPressure(uint8_t oss); + +private: + unsigned int fLastConvTime; + bool fCalibrationValid; + signed int fCalibParameters[11]; +}; + +#endif // _I2CDEVICES_H_ diff --git a/daemon/include/hardware/i2c/eeprom24aa02.h b/daemon/include/hardware/i2c/eeprom24aa02.h new file mode 100644 index 00000000..1ed73962 --- /dev/null +++ b/daemon/include/hardware/i2c/eeprom24aa02.h @@ -0,0 +1,53 @@ +#ifndef _EEPROM24AA02_H_ +#define _EEPROM24AA02_H_ + +#include "hardware/i2c/i2cdevice.h" +#include "hardware/device_types.h" + +/* EEPROM24AA02 */ + +class EEPROM24AA02 : public i2cDevice, public DeviceFunction, public static_device_base { +public: + EEPROM24AA02() + : i2cDevice(0x50) + { + fTitle = fName = "24AA02"; + } + EEPROM24AA02(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = fName = "24AA02"; + } + EEPROM24AA02(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = fName = "24AA02"; + } + + uint8_t readByte(uint8_t addr); + bool readByte(uint8_t addr, uint8_t* value); + void writeByte(uint8_t addr, uint8_t data); + /** Write multiple bytes to starting from given address into EEPROM memory. + * @param addr First register address to write to + * @param length Number of bytes to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + * @note this is an overloaded function to the one from the i2cDevice base class in order to + * prevent sequential write operations crossing page boundaries of the EEPROM. This function conforms to + * the page-wise sequential write (c.f. http://ww1.microchip.com/downloads/en/devicedoc/21709c.pdf p.7). + */ + bool writeBytes(uint8_t addr, uint16_t length, uint8_t* data) override; + int16_t readBytes(uint8_t regAddr, uint16_t length, uint8_t* data) override; + + bool identify() override; + bool probeDevicePresence() override { return devicePresent(); } +private: + // hide all write functions from i2cDevice class since they do not conform to the correct write sequence of the eeprom + using i2cDevice::write; + using i2cDevice::writeByte; + using i2cDevice::writeBytes; + using i2cDevice::writeWord; + using i2cDevice::writeWords; + using i2cDevice::readBytes; +}; +#endif //!_EEPROM24AA02_H diff --git a/daemon/include/hardware/i2c/glcdfont.h b/daemon/include/hardware/i2c/glcdfont.h new file mode 100644 index 00000000..de2f96fa --- /dev/null +++ b/daemon/include/hardware/i2c/glcdfont.h @@ -0,0 +1,265 @@ +#ifndef FONT5X7_H +#define FONT5X7_H + +// standard ascii 5x7 font +// clang-format off +static const unsigned char font[] = { + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x5B, 0x4F, 0x5B, 0x3E, + 0x3E, 0x6B, 0x4F, 0x6B, 0x3E, + 0x1C, 0x3E, 0x7C, 0x3E, 0x1C, + 0x18, 0x3C, 0x7E, 0x3C, 0x18, + 0x1C, 0x57, 0x7D, 0x57, 0x1C, + 0x1C, 0x5E, 0x7F, 0x5E, 0x1C, + 0x00, 0x18, 0x3C, 0x18, 0x00, + 0xFF, 0xE7, 0xC3, 0xE7, 0xFF, + 0x00, 0x18, 0x24, 0x18, 0x00, + 0xFF, 0xE7, 0xDB, 0xE7, 0xFF, + 0x30, 0x48, 0x3A, 0x06, 0x0E, + 0x26, 0x29, 0x79, 0x29, 0x26, + 0x40, 0x7F, 0x05, 0x05, 0x07, + 0x40, 0x7F, 0x05, 0x25, 0x3F, + 0x5A, 0x3C, 0xE7, 0x3C, 0x5A, + 0x7F, 0x3E, 0x1C, 0x1C, 0x08, + 0x08, 0x1C, 0x1C, 0x3E, 0x7F, + 0x14, 0x22, 0x7F, 0x22, 0x14, + 0x5F, 0x5F, 0x00, 0x5F, 0x5F, + 0x06, 0x09, 0x7F, 0x01, 0x7F, + 0x00, 0x66, 0x89, 0x95, 0x6A, + 0x60, 0x60, 0x60, 0x60, 0x60, + 0x94, 0xA2, 0xFF, 0xA2, 0x94, + 0x08, 0x04, 0x7E, 0x04, 0x08, + 0x10, 0x20, 0x7E, 0x20, 0x10, + 0x08, 0x08, 0x2A, 0x1C, 0x08, + 0x08, 0x1C, 0x2A, 0x08, 0x08, + 0x1E, 0x10, 0x10, 0x10, 0x10, + 0x0C, 0x1E, 0x0C, 0x1E, 0x0C, + 0x30, 0x38, 0x3E, 0x38, 0x30, + 0x06, 0x0E, 0x3E, 0x0E, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x5F, 0x00, 0x00, + 0x00, 0x07, 0x00, 0x07, 0x00, + 0x14, 0x7F, 0x14, 0x7F, 0x14, + 0x24, 0x2A, 0x7F, 0x2A, 0x12, + 0x23, 0x13, 0x08, 0x64, 0x62, + 0x36, 0x49, 0x56, 0x20, 0x50, + 0x00, 0x08, 0x07, 0x03, 0x00, + 0x00, 0x1C, 0x22, 0x41, 0x00, + 0x00, 0x41, 0x22, 0x1C, 0x00, + 0x2A, 0x1C, 0x7F, 0x1C, 0x2A, + 0x08, 0x08, 0x3E, 0x08, 0x08, + 0x00, 0x80, 0x70, 0x30, 0x00, + 0x08, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x00, 0x60, 0x60, 0x00, + 0x20, 0x10, 0x08, 0x04, 0x02, + 0x3E, 0x51, 0x49, 0x45, 0x3E, + 0x00, 0x42, 0x7F, 0x40, 0x00, + 0x72, 0x49, 0x49, 0x49, 0x46, + 0x21, 0x41, 0x49, 0x4D, 0x33, + 0x18, 0x14, 0x12, 0x7F, 0x10, + 0x27, 0x45, 0x45, 0x45, 0x39, + 0x3C, 0x4A, 0x49, 0x49, 0x31, + 0x41, 0x21, 0x11, 0x09, 0x07, + 0x36, 0x49, 0x49, 0x49, 0x36, + 0x46, 0x49, 0x49, 0x29, 0x1E, + 0x00, 0x00, 0x14, 0x00, 0x00, + 0x00, 0x40, 0x34, 0x00, 0x00, + 0x00, 0x08, 0x14, 0x22, 0x41, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x00, 0x41, 0x22, 0x14, 0x08, + 0x02, 0x01, 0x59, 0x09, 0x06, + 0x3E, 0x41, 0x5D, 0x59, 0x4E, + 0x7C, 0x12, 0x11, 0x12, 0x7C, + 0x7F, 0x49, 0x49, 0x49, 0x36, + 0x3E, 0x41, 0x41, 0x41, 0x22, + 0x7F, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x49, 0x49, 0x49, 0x41, + 0x7F, 0x09, 0x09, 0x09, 0x01, + 0x3E, 0x41, 0x41, 0x51, 0x73, + 0x7F, 0x08, 0x08, 0x08, 0x7F, + 0x00, 0x41, 0x7F, 0x41, 0x00, + 0x20, 0x40, 0x41, 0x3F, 0x01, + 0x7F, 0x08, 0x14, 0x22, 0x41, + 0x7F, 0x40, 0x40, 0x40, 0x40, + 0x7F, 0x02, 0x1C, 0x02, 0x7F, + 0x7F, 0x04, 0x08, 0x10, 0x7F, + 0x3E, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x09, 0x09, 0x09, 0x06, + 0x3E, 0x41, 0x51, 0x21, 0x5E, + 0x7F, 0x09, 0x19, 0x29, 0x46, + 0x26, 0x49, 0x49, 0x49, 0x32, + 0x03, 0x01, 0x7F, 0x01, 0x03, + 0x3F, 0x40, 0x40, 0x40, 0x3F, + 0x1F, 0x20, 0x40, 0x20, 0x1F, + 0x3F, 0x40, 0x38, 0x40, 0x3F, + 0x63, 0x14, 0x08, 0x14, 0x63, + 0x03, 0x04, 0x78, 0x04, 0x03, + 0x61, 0x59, 0x49, 0x4D, 0x43, + 0x00, 0x7F, 0x41, 0x41, 0x41, + 0x02, 0x04, 0x08, 0x10, 0x20, + 0x00, 0x41, 0x41, 0x41, 0x7F, + 0x04, 0x02, 0x01, 0x02, 0x04, + 0x40, 0x40, 0x40, 0x40, 0x40, + 0x00, 0x03, 0x07, 0x08, 0x00, + 0x20, 0x54, 0x54, 0x78, 0x40, + 0x7F, 0x28, 0x44, 0x44, 0x38, + 0x38, 0x44, 0x44, 0x44, 0x28, + 0x38, 0x44, 0x44, 0x28, 0x7F, + 0x38, 0x54, 0x54, 0x54, 0x18, + 0x00, 0x08, 0x7E, 0x09, 0x02, + 0x18, 0xA4, 0xA4, 0x9C, 0x78, + 0x7F, 0x08, 0x04, 0x04, 0x78, + 0x00, 0x44, 0x7D, 0x40, 0x00, + 0x20, 0x40, 0x40, 0x3D, 0x00, + 0x7F, 0x10, 0x28, 0x44, 0x00, + 0x00, 0x41, 0x7F, 0x40, 0x00, + 0x7C, 0x04, 0x78, 0x04, 0x78, + 0x7C, 0x08, 0x04, 0x04, 0x78, + 0x38, 0x44, 0x44, 0x44, 0x38, + 0xFC, 0x18, 0x24, 0x24, 0x18, + 0x18, 0x24, 0x24, 0x18, 0xFC, + 0x7C, 0x08, 0x04, 0x04, 0x08, + 0x48, 0x54, 0x54, 0x54, 0x24, + 0x04, 0x04, 0x3F, 0x44, 0x24, + 0x3C, 0x40, 0x40, 0x20, 0x7C, + 0x1C, 0x20, 0x40, 0x20, 0x1C, + 0x3C, 0x40, 0x30, 0x40, 0x3C, + 0x44, 0x28, 0x10, 0x28, 0x44, + 0x4C, 0x90, 0x90, 0x90, 0x7C, + 0x44, 0x64, 0x54, 0x4C, 0x44, + 0x00, 0x08, 0x36, 0x41, 0x00, + 0x00, 0x00, 0x77, 0x00, 0x00, + 0x00, 0x41, 0x36, 0x08, 0x00, + 0x02, 0x01, 0x02, 0x04, 0x02, + 0x3C, 0x26, 0x23, 0x26, 0x3C, + 0x1E, 0xA1, 0xA1, 0x61, 0x12, + 0x3A, 0x40, 0x40, 0x20, 0x7A, + 0x38, 0x54, 0x54, 0x55, 0x59, + 0x21, 0x55, 0x55, 0x79, 0x41, + 0x21, 0x54, 0x54, 0x78, 0x41, + 0x21, 0x55, 0x54, 0x78, 0x40, + 0x20, 0x54, 0x55, 0x79, 0x40, + 0x0C, 0x1E, 0x52, 0x72, 0x12, + 0x39, 0x55, 0x55, 0x55, 0x59, + 0x39, 0x54, 0x54, 0x54, 0x59, + 0x39, 0x55, 0x54, 0x54, 0x58, + 0x00, 0x00, 0x45, 0x7C, 0x41, + 0x00, 0x02, 0x45, 0x7D, 0x42, + 0x00, 0x01, 0x45, 0x7C, 0x40, + 0xF0, 0x29, 0x24, 0x29, 0xF0, + 0xF0, 0x28, 0x25, 0x28, 0xF0, + 0x7C, 0x54, 0x55, 0x45, 0x00, + 0x20, 0x54, 0x54, 0x7C, 0x54, + 0x7C, 0x0A, 0x09, 0x7F, 0x49, + 0x32, 0x49, 0x49, 0x49, 0x32, + 0x32, 0x48, 0x48, 0x48, 0x32, + 0x32, 0x4A, 0x48, 0x48, 0x30, + 0x3A, 0x41, 0x41, 0x21, 0x7A, + 0x3A, 0x42, 0x40, 0x20, 0x78, + 0x00, 0x9D, 0xA0, 0xA0, 0x7D, + 0x39, 0x44, 0x44, 0x44, 0x39, + 0x3D, 0x40, 0x40, 0x40, 0x3D, + 0x3C, 0x24, 0xFF, 0x24, 0x24, + 0x48, 0x7E, 0x49, 0x43, 0x66, + 0x2B, 0x2F, 0xFC, 0x2F, 0x2B, + 0xFF, 0x09, 0x29, 0xF6, 0x20, + 0xC0, 0x88, 0x7E, 0x09, 0x03, + 0x20, 0x54, 0x54, 0x79, 0x41, + 0x00, 0x00, 0x44, 0x7D, 0x41, + 0x30, 0x48, 0x48, 0x4A, 0x32, + 0x38, 0x40, 0x40, 0x22, 0x7A, + 0x00, 0x7A, 0x0A, 0x0A, 0x72, + 0x7D, 0x0D, 0x19, 0x31, 0x7D, + 0x26, 0x29, 0x29, 0x2F, 0x28, + 0x26, 0x29, 0x29, 0x29, 0x26, + 0x30, 0x48, 0x4D, 0x40, 0x20, + 0x38, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x08, 0x38, + 0x2F, 0x10, 0xC8, 0xAC, 0xBA, + 0x2F, 0x10, 0x28, 0x34, 0xFA, + 0x00, 0x00, 0x7B, 0x00, 0x00, + 0x08, 0x14, 0x2A, 0x14, 0x22, + 0x22, 0x14, 0x2A, 0x14, 0x08, + 0xAA, 0x00, 0x55, 0x00, 0xAA, + 0xAA, 0x55, 0xAA, 0x55, 0xAA, + 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x10, 0x10, 0x10, 0xFF, 0x00, + 0x14, 0x14, 0x14, 0xFF, 0x00, + 0x10, 0x10, 0xFF, 0x00, 0xFF, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x14, 0x14, 0x14, 0xFC, 0x00, + 0x14, 0x14, 0xF7, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x14, 0x14, 0xF4, 0x04, 0xFC, + 0x14, 0x14, 0x17, 0x10, 0x1F, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0x1F, 0x00, + 0x10, 0x10, 0x10, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0xF0, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x10, + 0x10, 0x10, 0x10, 0x10, 0x10, + 0x10, 0x10, 0x10, 0xFF, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x14, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0x10, 0x17, + 0x00, 0x00, 0xFC, 0x04, 0xF4, + 0x14, 0x14, 0x17, 0x10, 0x17, + 0x14, 0x14, 0xF4, 0x04, 0xF4, + 0x00, 0x00, 0xFF, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x14, 0x14, 0xF7, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x17, 0x14, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0xF4, 0x14, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x00, 0x00, 0x1F, 0x10, 0x1F, + 0x00, 0x00, 0x00, 0x1F, 0x14, + 0x00, 0x00, 0x00, 0xFC, 0x14, + 0x00, 0x00, 0xF0, 0x10, 0xF0, + 0x10, 0x10, 0xFF, 0x10, 0xFF, + 0x14, 0x14, 0x14, 0xFF, 0x14, + 0x10, 0x10, 0x10, 0x1F, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x10, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x38, 0x44, 0x44, 0x38, 0x44, + 0x7C, 0x2A, 0x2A, 0x3E, 0x14, + 0x7E, 0x02, 0x02, 0x06, 0x06, + 0x02, 0x7E, 0x02, 0x7E, 0x02, + 0x63, 0x55, 0x49, 0x41, 0x63, + 0x38, 0x44, 0x44, 0x3C, 0x04, + 0x40, 0x7E, 0x20, 0x1E, 0x20, + 0x06, 0x02, 0x7E, 0x02, 0x02, + 0x99, 0xA5, 0xE7, 0xA5, 0x99, + 0x1C, 0x2A, 0x49, 0x2A, 0x1C, + 0x4C, 0x72, 0x01, 0x72, 0x4C, + 0x30, 0x4A, 0x4D, 0x4D, 0x30, + 0x30, 0x48, 0x78, 0x48, 0x30, + 0xBC, 0x62, 0x5A, 0x46, 0x3D, + 0x3E, 0x49, 0x49, 0x49, 0x00, + 0x7E, 0x01, 0x01, 0x01, 0x7E, + 0x2A, 0x2A, 0x2A, 0x2A, 0x2A, + 0x44, 0x44, 0x5F, 0x44, 0x44, + 0x40, 0x51, 0x4A, 0x44, 0x40, + 0x40, 0x44, 0x4A, 0x51, 0x40, + 0x00, 0x00, 0xFF, 0x01, 0x03, + 0xE0, 0x80, 0xFF, 0x00, 0x00, + 0x08, 0x08, 0x6B, 0x6B, 0x08, + 0x36, 0x12, 0x36, 0x24, 0x36, + 0x06, 0x0F, 0x09, 0x0F, 0x06, + 0x00, 0x00, 0x18, 0x18, 0x00, + 0x00, 0x00, 0x10, 0x10, 0x00, + 0x30, 0x40, 0xFF, 0x01, 0x01, + 0x00, 0x1F, 0x01, 0x01, 0x1E, + 0x00, 0x19, 0x1D, 0x17, 0x12, + 0x00, 0x3C, 0x3C, 0x3C, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00, +}; +// clang-format on + +#endif diff --git a/daemon/include/hardware/i2c/hmc5883.h b/daemon/include/hardware/i2c/hmc5883.h new file mode 100644 index 00000000..9c55b2c4 --- /dev/null +++ b/daemon/include/hardware/i2c/hmc5883.h @@ -0,0 +1,45 @@ +#ifndef _HMC5883_H_ +#define _HMC5883_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* HMC5883 */ + +class HMC5883 : public i2cDevice { +public: + // Resolution for the 8 gain settings in mG/LSB + static const double GAIN[8]; + HMC5883() + : i2cDevice(0x1e) + { + fTitle = "HMC5883"; + } + HMC5883(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "HMC5883"; + } + HMC5883(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = "HMC5883"; + } + + bool init(); + // gain range 0..7 + void setGain(uint8_t gain); + uint8_t readGain(); + bool getXYZRawValues(int& x, int& y, int& z); + bool getXYZMagneticFields(double& x, double& y, double& z); + bool readRDYBit(); + bool readLockBit(); + bool calibrate(int& x, int& y, int& z); + +private: + unsigned int fLastConvTime; + bool fCalibrationValid; + unsigned int fGain; + signed int fCalibParameters[11]; +}; + +#endif // !_HMC5883_H_ diff --git a/daemon/include/hardware/i2c/i2cdevice.h b/daemon/include/hardware/i2c/i2cdevice.h new file mode 100644 index 00000000..48001a90 --- /dev/null +++ b/daemon/include/hardware/i2c/i2cdevice.h @@ -0,0 +1,159 @@ +#include // open +#include // uint8_t, etc +#include +#include +#include +#include // ioctl +#include // for gettimeofday() +#include +#include +#include + +#ifndef _I2CDEVICE_H_ +#define _I2CDEVICE_H_ + +#define DEFAULT_DEBUG_LEVEL 0 + +// base class fragment static_device_base which implemets static functions available to all derived classes +// by the Curiously Recursive Template Pattern (CRTP) mechanism +template +struct static_device_base +{ + friend class i2cDevice; + static bool identifyDevice(uint8_t addr) { + auto it = T::getGlobalDeviceList().begin(); + bool found { false }; + while ( !found && it != T::getGlobalDeviceList().end() ) { + if ( (*it)->getAddress() == addr) { + found = true; + break; + } + it++; + } + if ( found ) { + T dummyDevice( 0x00 ); + if ( (*it)->getTitle() == dummyDevice.getTitle() ) return true; + return false; + } + T device(addr); + return device.identify(); + } +}; + + +//We define a class named i2cDevices to outsource the hardware dependent program parts. We want to +//access components of integrated curcuits, like the ads1115 or other subdevices via i2c-bus. +//The main aim here is, that the user does not have to be concerned about the c like low level operations +//of I2C access +// First, we define an abstract base class with all low-level i2c acess functions implemented. +// For device specific implementations, classes can inherit this base class +// virtual methods should be reimplemented in the child classes to make sense there, e.g. devicePresent() +class i2cDevice { + +public: + enum MODE { MODE_NONE = 0, + MODE_NORMAL = 0x01, + MODE_FORCE = 0x02, + MODE_UNREACHABLE = 0x04, + MODE_FAILED = 0x08, + MODE_LOCKED = 0x10 }; + + i2cDevice(); + i2cDevice(const char* busAddress = "/dev/i2c-1"); + i2cDevice(uint8_t slaveAddress); + i2cDevice(const char* busAddress, uint8_t slaveAddress); + virtual ~i2cDevice(); + + void setAddress(uint8_t address); + uint8_t getAddress() const { return fAddress; } + static unsigned int getNrDevices() { return fNrDevices; } + unsigned int getNrBytesRead() const { return fNrBytesRead; } + unsigned int getNrBytesWritten() const { return fNrBytesWritten; } + unsigned int getNrIOErrors() const { return fIOErrors; } + static unsigned int getGlobalNrBytesRead() { return fGlobalNrBytesRead; } + static unsigned int getGlobalNrBytesWritten() { return fGlobalNrBytesWritten; } + static std::vector& getGlobalDeviceList() { return fGlobalDeviceList; } + virtual bool devicePresent(); + uint8_t getStatus() const { return fMode; } + void lock(bool locked = true); + + double getLastTimeInterval() const { return fLastTimeInterval; } + + void setDebugLevel(int level) { fDebugLevel = level; } + int getDebugLevel() const { return fDebugLevel; } + + void setTitle(const std::string& a_title) { fTitle = a_title; } + const std::string& getTitle() const { return fTitle; } + + // read nBytes bytes into buffer buf + // return value: + // the number of bytes actually read if successful + // -1 on error + int read(uint8_t* buf, int nBytes); + + // write nBytes bytes from buffer buf + // return value: + // the number of bytes actually written if successful + // -1 on error + int write(uint8_t* buf, int nBytes); + + // write nBytes bytes from buffer buf in register reg + // return value: + // the number of bytes actually written if successful + // -1 on error + // note: first byte of the write sequence is the register address, + // the following bytes from buf are then written in a sequence + int writeReg(uint8_t reg, uint8_t* buf, int nBytes); + + // read nBytes bytes into buffer buf from register reg + // return value: + // the number of bytes actually read if successful + // -1 on error + // note: first writes reg address and after a repeated start + // reads in a sequence of bytes + // not all devices support this procedure + // refer to the device's datasheet + int readReg(uint8_t reg, uint8_t* buf, int nBytes); + + int8_t readBit(uint8_t regAddr, uint8_t bitNum, uint8_t* data); + int8_t readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t* data); + bool readByte(uint8_t regAddr, uint8_t* data); + int16_t readBytes(uint8_t regAddr, uint16_t length, uint8_t* data); + bool writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data); + bool writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); + bool writeByte(uint8_t regAddr, uint8_t data); + bool writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data); + bool writeWords(uint8_t regAddr, uint16_t length, uint16_t* data); + bool writeWord(uint8_t regAddr, uint16_t data); + int16_t readWords(uint8_t regAddr, uint16_t length, uint16_t* data); + int16_t readWords(uint16_t length, uint16_t* data); + bool readWord(uint8_t regAddr, uint16_t* data); + bool readWord(uint16_t* data); + + void getCapabilities(); + + virtual bool identify(); + +protected: + int fHandle { 0 }; + uint8_t fAddress { 0x00 }; + static unsigned int fNrDevices; + unsigned long int fNrBytesWritten { 0 }; + unsigned long int fNrBytesRead { 0 }; + static unsigned long int fGlobalNrBytesRead; + static unsigned long int fGlobalNrBytesWritten; + double fLastTimeInterval { 0. }; // the last time measurement's result is stored here + struct timeval fT1, fT2; + int fDebugLevel { 0 }; + static std::vector fGlobalDeviceList; + std::string fTitle { "I2C device" }; + uint8_t fMode { MODE_NONE }; + unsigned int fIOErrors { 0 }; + std::mutex fMutex; + + // fuctions for measuring time intervals + void startTimer(); + void stopTimer(); +}; + +#endif // _I2CDEVICE_H_ diff --git a/daemon/include/hardware/i2c/i2cutil.h b/daemon/include/hardware/i2c/i2cutil.h new file mode 100644 index 00000000..5c0715ed --- /dev/null +++ b/daemon/include/hardware/i2c/i2cutil.h @@ -0,0 +1,35 @@ +#ifndef _I2CUTIL_H_ +#define _I2CUTIL_H_ + +#include "hardware/i2c/i2cdevice.h" +#include +#include +#include +#include + +class I2cGeneralCall : private i2cDevice { +public: + static void resetDevices(); + static void wakeUp(); + static void softwareUpdate(); +private: + I2cGeneralCall(); + I2cGeneralCall(const char* busAddress); +}; + +template +std::vector findI2cDeviceType( const std::set& possible_addresses = std::set() ) { + std::vector addr_list { }; + for ( uint16_t addr = 0x04; addr <= 0x78; addr++) { + if ( !possible_addresses.empty() && possible_addresses.find( static_cast( addr ) ) == possible_addresses.cend() ) continue; + bool ident { false }; + ident = T::identifyDevice( static_cast(addr) ); + if ( ident ) { +// std::cout<<"device identified at 0x"<(addr)); + } + } + return addr_list; +} + +#endif // !_I2CUTIL_H_ diff --git a/daemon/include/hardware/i2c/lm75.h b/daemon/include/hardware/i2c/lm75.h new file mode 100644 index 00000000..2489c62a --- /dev/null +++ b/daemon/include/hardware/i2c/lm75.h @@ -0,0 +1,29 @@ +#ifndef _LM75_H_ +#define _LM75_H_ +#include "hardware/i2c/i2cdevice.h" +#include "hardware/device_types.h" + +class LM75 : public i2cDevice, public DeviceFunction, public static_device_base { +public: + LM75(); + LM75(const char* busAddress, uint8_t slaveAddress); + LM75(uint8_t slaveAddress); + virtual ~LM75(); + float getTemperature() override; + + bool identify() override; + bool probeDevicePresence() override { return devicePresent(); } +protected: + int16_t readRaw(); + + enum REG : uint8_t { + TEMP = 0x00, + CONF = 0x01, + THYST = 0x02, + TOS = 0x03 + }; + + unsigned int fLastConvTime; + signed int fLastRawValue; +}; +#endif // !_LM75_H_ diff --git a/daemon/include/hardware/i2c/mcp4728.h b/daemon/include/hardware/i2c/mcp4728.h new file mode 100644 index 00000000..e28954e5 --- /dev/null +++ b/daemon/include/hardware/i2c/mcp4728.h @@ -0,0 +1,84 @@ +#ifndef _MCP4728_H_ +#define _MCP4728_H_ +#include "hardware/i2c/i2cdevice.h" +#include "hardware/device_types.h" +#include + +/* MCP4728 4ch 12bit DAC */ + +class MCP4728 : public i2cDevice, public DeviceFunction, public static_device_base { + // the DAC supports writing to input register but not sending latch bit to update the output register + // here we will always send the "UDAC" (latch) bit because we don't need this functionality + // MCP4728 listens to I2C Generall Call Commands + // reset, wake-up, software update, read address bits + // reset is "0x00 0x06" + // wake-up is "0x00 0x09" +public: + enum CFG_GAIN { GAIN1 = 0, + GAIN2 = 1 }; + enum CFG_VREF { VREF_VDD = 0, + VREF_2V = 1 }; + + // struct that characterizes one dac output channel + // setting the eeprom flag enables access to the eeprom registers instead of the dac output registers + struct DacChannel { + uint8_t pd = 0x00; + CFG_GAIN gain = GAIN1; + CFG_VREF vref = VREF_2V; + bool eeprom = false; + uint16_t value = 0; + }; + + MCP4728() + : i2cDevice(0x60) + { + fTitle = fName = "MCP4728"; + } + MCP4728(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = fName = "MCP4728"; + } + MCP4728(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = fName = "MCP4728"; + } + bool devicePresent() override; + bool setVoltage( unsigned int channel, float voltage ) override; + bool storeSettings() override; + bool writeChannel( uint8_t channel, const DacChannel& channelData ); + bool readChannel( uint8_t channel, DacChannel& channelData ); + bool setVRef( unsigned int channel, CFG_VREF vref_setting ); + bool setVRef( CFG_VREF vref_setting ); + + static float code2voltage(const DacChannel& channelData); + + bool identify() override; + bool probeDevicePresence() override { return devicePresent(); } + +private: + static constexpr float fVddRefVoltage { 3.3 }; ///< voltage at which the device is powered + enum COMMAND: uint8_t { + DAC_FAST_WRITE = 0b00000000, + DAC_MULTI_WRITE = 0b00001000, + DAC_EEP_SEQ_WRITE = 0b00001010, + DAC_EEP_SINGLE_WRITE= 0b00001011, + ADDR_BITS_WRITE = 0b00001100, + VREF_WRITE = 0b00010000, + GAIN_WRITE = 0b00011000, + PD_WRITE = 0b00010100 + }; + DacChannel fChannelSetting[4], fChannelSettingEep[4]; + std::chrono::time_point fLastRegisterUpdate { }; + bool fBusy { false }; + + bool setVoltage( uint8_t channel, float voltage, bool toEEPROM ); + bool setValue( uint8_t channel, uint16_t value, CFG_GAIN gain = GAIN1, bool toEEPROM = false ); + bool readRegisters(); + void parseChannelData( uint8_t* buf ); + void dumpRegisters(); + bool waitEepReady(); +}; + +#endif //!_MCP4728_H_ diff --git a/daemon/include/hardware/i2c/mic184.h b/daemon/include/hardware/i2c/mic184.h new file mode 100644 index 00000000..b314d9d5 --- /dev/null +++ b/daemon/include/hardware/i2c/mic184.h @@ -0,0 +1,34 @@ +#ifndef _MIC184_H_ +#define _MIC184_H_ +#include "hardware/i2c/i2cdevice.h" +//#include "hardware/i2c/lm75.h" +#include "hardware/device_types.h" + +class MIC184 : public i2cDevice, public DeviceFunction, public static_device_base { +public: + MIC184(); + MIC184(const char* busAddress, uint8_t slaveAddress); + MIC184(uint8_t slaveAddress); + virtual ~MIC184(); + + float getTemperature() override; + bool probeDevicePresence() override { return devicePresent(); } + + bool identify() override; + bool isExternal() const { return fExternal; } + bool setExternal( bool enable_external = true ); +private: + int16_t readRaw(); + + enum REG : uint8_t { + TEMP = 0x00, + CONF = 0x01, + THYST = 0x02, + TOS = 0x03 + }; + + unsigned int fLastConvTime; + signed int fLastRawValue; + bool fExternal { false }; +}; +#endif // !_MIC184_H_ diff --git a/daemon/include/hardware/i2c/pca9536.h b/daemon/include/hardware/i2c/pca9536.h new file mode 100644 index 00000000..24c55d6f --- /dev/null +++ b/daemon/include/hardware/i2c/pca9536.h @@ -0,0 +1,46 @@ +#ifndef _PCA9536_H_ +#define _PCA9536_H_ +#include "hardware/i2c/i2cdevice.h" +#include "hardware/device_types.h" + +/* PCA9536 */ +class PCA9536 : public i2cDevice, public DeviceFunction, public static_device_base { + // the device supports reading the incoming logic levels of the pins if set to input in the configuration register (will probably not use this feature) + // the device supports polarity inversion (by configuring the polarity inversion register) (will probably not use this feature) +public: + enum CFG_PORT { C0 = 0, + C1 = 2, + C3 = 4, + C4 = 8 }; + PCA9536() + : i2cDevice(0x41) + { + fTitle = fName = "PCA9536"; + } + PCA9536(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = fName = "PCA9536"; + } + PCA9536(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = fName = "PCA9536"; + } + bool setOutputPorts(uint8_t portMask) override; + bool setOutputState(uint8_t portMask) override; + uint8_t getInputState() override; + bool devicePresent() override; + bool identify() override; + bool probeDevicePresence() override { return devicePresent(); } + +private: + enum REG { + INPUT = 0x00, + OUTPUT = 0x01, + POLARITY = 0x02, + CONFIG = 0x03 + }; +}; + +#endif // !_PCA9536_H_ diff --git a/daemon/include/hardware/i2c/sht21.h b/daemon/include/hardware/i2c/sht21.h new file mode 100644 index 00000000..1ebd331c --- /dev/null +++ b/daemon/include/hardware/i2c/sht21.h @@ -0,0 +1,39 @@ +#ifndef _SHT21_H_ +#define _SHT21_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* SHT21 */ + +class SHT21 : public i2cDevice { +public: + SHT21() + : i2cDevice(0x40) + { + fTitle = "SHT21"; + } + SHT21(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "SHT21"; + } + SHT21(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = "SHT21"; + } + + uint16_t readUT(); //read temperature; nothing gets passed + uint16_t readUH(); //read humidity; nothing gets passed + + bool softReset(); //reset, datasheet, page 9, Rückgabetyp in void geändert + uint8_t readResolutionSettings(); + void setResolutionSettings(uint8_t settingsByte); //Sets the resolution Bits for humidity and temperature + float getTemperature(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_temp() + float getHumidity(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_hum(); + +private: + bool checksumCorrect(uint8_t data[]); // expects 3 byte long data array; Source: https://www2.htw-dresden.de/~wiki_sn/index.php/SHT21 +}; + +#endif //!_SHT21_H_ diff --git a/source/daemon/include/i2c/i2cdevices/sht31/sht31.h b/daemon/include/hardware/i2c/sht31.h similarity index 91% rename from source/daemon/include/i2c/i2cdevices/sht31/sht31.h rename to daemon/include/hardware/i2c/sht31.h index aa5246cc..83646add 100644 --- a/source/daemon/include/i2c/i2cdevices/sht31/sht31.h +++ b/daemon/include/hardware/i2c/sht31.h @@ -1,7 +1,7 @@ #ifndef _SHT31_H_ #define _SHT31_H_ -#include "../i2cdevice.h" +#include "hardware/i2c/i2cdevice.h" /* SHT21 */ @@ -13,7 +13,7 @@ class SHT31 : public i2cDevice { bool readRaw(uint16_t &UT, uint16_t &UH); //read temperature; nothing gets passed bool breakCommand(); - bool softReset(); //reset, datasheet, page 9, Rückgabetyp in void geändert + bool softReset(); //reset, datasheet, page 9, Rückgabetyp in void geändert bool heater(bool on); bool getValues(float &ftemp, float &fhum); //float getTemperature(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_temp() @@ -23,4 +23,4 @@ class SHT31 : public i2cDevice { bool checksumCorrect(uint8_t data[]); // expects 3 byte long data array; Source: https://www2.htw-dresden.de/~wiki_sn/index.php/SHT21 }; -#endif //!_SHT31_H_ \ No newline at end of file +#endif //!_SHT31_H_ diff --git a/source/daemon/include/i2c/i2cdevices/tca9546a/tca9546a.h b/daemon/include/hardware/i2c/tca9546a.h similarity index 93% rename from source/daemon/include/i2c/i2cdevices/tca9546a/tca9546a.h rename to daemon/include/hardware/i2c/tca9546a.h index 07d98155..c3351ee2 100644 --- a/source/daemon/include/i2c/i2cdevices/tca9546a/tca9546a.h +++ b/daemon/include/hardware/i2c/tca9546a.h @@ -1,7 +1,7 @@ #ifndef _TCA9546A_H_ #define _TCA9546A_H_ -#include "../i2cdevice.h" +#include "hardware/i2c/i2cdevice.h" /* TCA9546A */ diff --git a/daemon/include/hardware/i2c/ubloxi2c.h b/daemon/include/hardware/i2c/ubloxi2c.h new file mode 100644 index 00000000..dd4d31c4 --- /dev/null +++ b/daemon/include/hardware/i2c/ubloxi2c.h @@ -0,0 +1,32 @@ +#ifndef _UBLOXI2C_H_ +#define _UBLOXI2C_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* Ublox GPS receiver, I2C interface */ + +class UbloxI2c : public i2cDevice { +public: + UbloxI2c() + : i2cDevice(0x42) + { + fTitle = "UBLOX I2C"; + } + UbloxI2c(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "UBLOX I2C"; + } + UbloxI2c(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = "UBLOX I2C"; + } + bool devicePresent(); + std::string getData(); + bool getTxBufCount(uint16_t& nrBytes); + +private: +}; + +#endif // !_UBLOXI2C_H_ diff --git a/daemon/include/hardware/i2c/x9119.h b/daemon/include/hardware/i2c/x9119.h new file mode 100644 index 00000000..62d9d388 --- /dev/null +++ b/daemon/include/hardware/i2c/x9119.h @@ -0,0 +1,37 @@ +#ifndef _X9119_H_ +#define _X9119_H_ + +#include "hardware/i2c/i2cdevice.h" + +/* X9119 */ + +class X9119 : public i2cDevice { +public: + X9119() + : i2cDevice(0x28) + { + fTitle = "X9119"; + } + X9119(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) + { + fTitle = "X9119"; + } + X9119(uint8_t slaveAddress) + : i2cDevice(slaveAddress) + { + fTitle = "X9119"; + } + + unsigned int readWiperReg(); + unsigned int readWiperReg2(); + unsigned int readWiperReg3(); + void writeWiperReg(unsigned int value); + unsigned int readDataReg(uint8_t reg); + void writeDataReg(uint8_t reg, unsigned int value); + +private: + unsigned int fWiperReg; +}; + +#endif // !_X9119_H_ diff --git a/daemon/include/hardware/i2cdevices.h b/daemon/include/hardware/i2cdevices.h new file mode 100644 index 00000000..1b9438b0 --- /dev/null +++ b/daemon/include/hardware/i2cdevices.h @@ -0,0 +1,27 @@ +#ifndef _I2CDEVICES_H_ +#define _I2CDEVICES_H_ + +#include "hardware/i2c/adafruit_ssd1306.h" +#include "hardware/i2c/ads1015.h" +#include "hardware/i2c/ads1115.h" +#include "hardware/i2c/bme280.h" +#include "hardware/i2c/bmp180.h" +#include "hardware/i2c/eeprom24aa02.h" +#include "hardware/i2c/hmc5883.h" +#include "hardware/i2c/lm75.h" +#include "hardware/i2c/mcp4728.h" +#include "hardware/i2c/pca9536.h" +#include "hardware/i2c/sht21.h" +#include "hardware/i2c/sht31.h" +#include "hardware/i2c/tca9546a.h" +#include "hardware/i2c/ubloxi2c.h" +#include "hardware/i2c/x9119.h" +#include "hardware/i2c/mic184.h" + +//#include "hardware/i2c/i2cdevice.h" + +class i2cDevice; + +i2cDevice* instantiateI2cDevice( uint8_t addr ); + +#endif // !_I2CDEVICES_H_ diff --git a/source/daemon/include/tdc7200.h b/daemon/include/hardware/spi/tdc7200.h similarity index 86% rename from source/daemon/include/tdc7200.h rename to daemon/include/hardware/spi/tdc7200.h index f73f9281..5ad91262 100644 --- a/source/daemon/include/tdc7200.h +++ b/daemon/include/hardware/spi/tdc7200.h @@ -5,13 +5,11 @@ #include Q_DECLARE_METATYPE(std::string) -//Q_DECLARE_METATYPE(uint8_t) -class TDC7200 : public QObject -{ +class TDC7200 : public QObject { Q_OBJECT public: - explicit TDC7200(unsigned int _INTB = 20, QObject *parent = nullptr); + explicit TDC7200(unsigned int _INTB = 20, QObject* parent = nullptr); signals: void readData(uint8_t reg, unsigned int bytesRead); @@ -37,7 +35,7 @@ private slots: void processData(); bool devicePresent = false; uint8_t INTB; - uint8_t config[2]= {0x02, 0b00000000}; // sets meas MODE 2, number of calibration cycles: 20 + uint8_t config[2] = { 0x02, 0b00000000 }; // sets meas MODE 2, number of calibration cycles: 20 // multi-cycle averaging mode: 16 cycles and num_stop: single // and then the different masks for start and stop (now all 0 so not written at all) double CLOCKperiod = 62.5e-9; // 62.5 ns corresponds to 16 MHz oscillator diff --git a/daemon/include/hardware/spidevices.h b/daemon/include/hardware/spidevices.h new file mode 100644 index 00000000..b6021bc7 --- /dev/null +++ b/daemon/include/hardware/spidevices.h @@ -0,0 +1,6 @@ +#ifndef _SPIDEVICES_H_ +#define _SPIDEVICES_H_ + +#include "hardware/spi/tdc7200.h" + +#endif // !_SPIDEVICES_H_ diff --git a/daemon/include/logengine.h b/daemon/include/logengine.h new file mode 100644 index 00000000..5c7392d7 --- /dev/null +++ b/daemon/include/logengine.h @@ -0,0 +1,33 @@ +#ifndef LOGENGINE_H +#define LOGENGINE_H +#include +#include +#include +#include +#include +#include "logparameter.h" + +class LogEngine : public QObject { + Q_OBJECT + +public: + LogEngine(QObject* parent = nullptr); + ~LogEngine(); + void setHashLength(int hash_length); + +signals: + void sendLogString(const QString& str); + void logIntervalSignal(); + +public slots: + void onLogParameterReceived(const LogParameter& logpar); + void onLogInterval(); + void onOnceLogTrigger() { onceLogFlag = true; } + +private: + QMap> logData; + bool onceLogFlag = true; + int hashLength { MuonPi::Config::Log::max_geohash_length }; +}; + +#endif // LOGENGINE_H diff --git a/daemon/include/logparameter.h b/daemon/include/logparameter.h new file mode 100644 index 00000000..0054f0bf --- /dev/null +++ b/daemon/include/logparameter.h @@ -0,0 +1,38 @@ +#ifndef LOGPARAMETER_H +#define LOGPARAMETER_H +#include + +struct LogParameter { +public: + enum { LOG_NEVER = 0, + LOG_ONCE, + LOG_EVERY, + LOG_LATEST, + LOG_AVERAGE, + LOG_ON_CHANGE }; + + LogParameter() = default; + LogParameter(const QString& a_name, const QString& a_value, int a_logType = LOG_EVERY, bool updatedRecently = false) + : fName(a_name) + , fValue(a_value) + , updated(updatedRecently) + , fLogType(a_logType) + { + } + + void setUpdatedRecently(bool updatedRecently) { updated = updatedRecently; } + void setName(const QString& a_name) { fName = a_name; } + void setValue(const QString& a_value) { fValue = a_value; } + + const QString& value() const { return fValue; } + const QString& name() const { return fName; } + bool updatedRecently() const { return updated; } + int logType() const { return fLogType; } + +private: + QString fName, fValue; + bool updated; + int fLogType = LOG_NEVER; +}; + +#endif // LOGPARAMETER_H diff --git a/source/daemon/include/pigpiodhandler.h b/daemon/include/pigpiodhandler.h similarity index 93% rename from source/daemon/include/pigpiodhandler.h rename to daemon/include/pigpiodhandler.h index bdde740b..4428737a 100644 --- a/source/daemon/include/pigpiodhandler.h +++ b/daemon/include/pigpiodhandler.h @@ -1,16 +1,16 @@ #ifndef PIGPIODHANDLER_H #define PIGPIODHANDLER_H -#include -#include #include #include +#include #include +#include #include #include #include -#include +#include "utility/gpio_mapping.h" #include #include @@ -23,9 +23,8 @@ static QVector DEFAULT_VECTOR; -class PigpiodHandler : public QObject -{ - Q_OBJECT +class PigpiodHandler : public QObject { + Q_OBJECT public: enum PinBias : std::uint8_t { BiasDisabled = 0x00, @@ -75,7 +74,7 @@ public slots: bool spiInitialised = false; bool spiInitialise(); // will be executed at first spi read/write command bool isSpiInitialised(); - unsigned int spiClkFreq;//3906250; // TDC7200: up to 20MHz SCLK + unsigned int spiClkFreq; //3906250; // TDC7200: up to 20MHz SCLK // Raspi: Core clock speed of 250MHz can be devided by any even number from 2 to 65536 // => 3.814kHz to 125MHz /* @@ -86,7 +85,7 @@ public slots: 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 word size bits msb msb only-3wire 3wire aux CEx? activ-low? spi-mode */ - unsigned int spiFlags; // fixed value for now + unsigned int spiFlags; // fixed value for now QTimer gpioClockTimeMeasurementTimer; void measureGpioClockTime(); @@ -104,5 +103,4 @@ public slots: std::mutex fMutex; }; - #endif // PIGPIODHANDLER_H diff --git a/source/daemon/include/qtserialublox.h b/daemon/include/qtserialublox.h similarity index 77% rename from source/daemon/include/qtserialublox.h rename to daemon/include/qtserialublox.h index c3c98aae..72e4b895 100644 --- a/source/daemon/include/qtserialublox.h +++ b/daemon/include/qtserialublox.h @@ -1,34 +1,41 @@ #ifndef QTSERIALUBLOX_H #define QTSERIALUBLOX_H +#include +#include +#include #include -#include "ublox_structs.h" -#include -#include #include -#include #include -#include - +#include +#include struct GeodeticPos; struct GnssMonHwStruct; struct GnssMonHw2Struct; struct UbxTimeMarkStruct; -class QtSerialUblox : public QObject -{ +class QtSerialUblox : public QObject { Q_OBJECT public: - - enum { RESET_HOT=0x00000000, RESET_WARM=0x00010000, RESET_COLD=0xFFFF0000, - RESET_HW=0x000000, RESET_SW=0x00000001, RESET_SW_GNSS=0x00000002, RESET_HW_AFTER_SHUTDOWN=0x00000004, GNSS_STOP=0x00000008, GNSS_START=0x00000009 }; - - enum { DEV_BBR=0x01, DEV_FLASH=0x02, DEV_EEPROM=0x04, DEV_SPI_FLASH=0x10 }; + enum { RESET_HOT = 0x00000000, + RESET_WARM = 0x00010000, + RESET_COLD = 0xFFFF0000, + RESET_HW = 0x000000, + RESET_SW = 0x00000001, + RESET_SW_GNSS = 0x00000002, + RESET_HW_AFTER_SHUTDOWN = 0x00000004, + GNSS_STOP = 0x00000008, + GNSS_START = 0x00000009 }; + + enum { DEV_BBR = 0x01, + DEV_FLASH = 0x02, + DEV_EEPROM = 0x04, + DEV_SPI_FLASH = 0x10 }; explicit QtSerialUblox(const QString serialPortName, int newTimeout, int baudRate, - bool newDumpRaw, int newVerbose, bool newShowout, bool newShowin, QObject *parent = 0); + bool newDumpRaw, int newVerbose, bool newShowout, bool newShowin, QObject* parent = 0); signals: // all messages coming from QtSerialUblox class that should be displayed on console @@ -54,11 +61,8 @@ class QtSerialUblox : public QObject std::chrono::duration updateAge); void gpsPropertyUpdatedGeodeticPos(GeodeticPos pos); void timTM2(QString timTM2String); - //void UBXReceivedTimeTM2(timespec rising, timespec falling, uint32_t accEst, bool valid, uint8_t timeBase, bool utcAvailable); void UBXReceivedTimeTM2(const UbxTimeMarkStruct& tm); void gpsVersion(const QString& swVersion, const QString& hwVersion, const QString& protVersion); - //void gpsMonHW(uint16_t noise, uint16_t agc, uint8_t antStatus, uint8_t antPower, uint8_t jamInd, uint8_t flags); - //void gpsMonHW2(int8_t ofsI, uint8_t magI, int8_t ofsQ, uint8_t magQ, uint8_t cfgSrc); void gpsMonHW(const GnssMonHwStruct& hw); void gpsMonHW2(const GnssMonHw2Struct& hw2); void UBXReceivedGnssConfig(uint8_t numTrkCh, const std::vector& gnssConfigs); @@ -84,8 +88,10 @@ public slots: void UBXSetMinMaxSVs(uint8_t minSVs, uint8_t maxSVs); void UBXSetMinCNO(uint8_t minCNO); void UBXSetCfgTP5(const UbxTimePulseStruct& tp); - void UBXSetAopCfg(bool enable=true, uint16_t maxOrbErr=0); - void UBXSaveCfg(uint8_t devMask=DEV_BBR | DEV_FLASH); + void UBXSetAopCfg(bool enable = true, uint16_t maxOrbErr = 0); + void UBXSaveCfg(uint8_t devMask = DEV_BBR | DEV_FLASH); + + void closeAll(); void ackTimeout(); // outPortMask is something like 1 for only UBX protocol or 0b11 for UBX and NMEA @@ -93,43 +99,35 @@ public slots: void setDynamicModel(uint8_t model); static const std::string& getProtVersionString() { return fProtVersionString; } static double getProtVersion(); - /* - float getProtVersion(); - int getProtVersionMajor(); - int getProtVersionMinor(); - */ + private: // all functions for sending and receiving raw data used by other functions in "public slots" section // and scanning raw data up to the point where "UbxMessage" object is generated - bool scanUnknownMessage(std::string &buffer, UbxMessage &message); - void calcChkSum(const std::string &buf, unsigned char* chkA, unsigned char* chkB); + bool scanUnknownMessage(std::string& buffer, UbxMessage& message); + void calcChkSum(const std::string& buf, unsigned char* chkA, unsigned char* chkB); bool sendUBX(uint16_t msgID, const std::string& payload, uint16_t nBytes); bool sendUBX(uint16_t msgID, unsigned char* payload, uint16_t nBytes); - bool sendUBX(UbxMessage &msg); + bool sendUBX(UbxMessage& msg); void sendQueuedMsg(bool afterTimeout = false); void delay(int millisecondsWait); -// void enqueueMsg(const UbxMessage& msg); // all functions only used for processing and showing "UbxMessage" void processMessage(const UbxMessage& msg); bool UBXNavClock(uint32_t& itow, int32_t& bias, int32_t& drift, uint32_t& tAccuracy, uint32_t& fAccuracy); bool UBXTimTP(uint32_t& itow, int32_t& quantErr, uint16_t& weekNr); - //bool UBXTimTP(); bool UBXTimTP(const std::string& msg); bool UBXTimTM2(const std::string& msg); - //std::vector UBXNavSat(bool allSats); std::vector UBXNavSat(const std::string& msg, bool allSats); - //std::vector UBXNavSVinfo(bool allSats); std::vector UBXNavSVinfo(const std::string& msg, bool allSats); GeodeticPos UBXNavPosLLH(const std::string& msg); - void UBXCfgGNSS(const std::string &msg); - void UBXCfgNav5(const std::string &msg); + void UBXCfgGNSS(const std::string& msg); + void UBXCfgNav5(const std::string& msg); std::vector UBXMonVer(); void UBXNavClock(const std::string& msg); void UBXNavTimeGPS(const std::string& msg); void UBXNavTimeUTC(const std::string& msg); - void UBXNavStatus(const std::string &msg); + void UBXNavStatus(const std::string& msg); void UBXMonHW(const std::string& msg); void UBXMonHW2(const std::string& msg); void UBXMonTx(const std::string& msg); @@ -138,11 +136,10 @@ public slots: void UBXCfgNavX5(const std::string& msg); void UBXCfgAnt(const std::string& msg); void UBXCfgTP5(const std::string& msg); - void UBXNavDOP(const std::string &msg); + void UBXNavDOP(const std::string& msg); static std::string toStdString(unsigned char* data, int dataSize); - // all global variables used in QtSerialUblox class until UbxMessage was created QPointer serialPort; QString _portName; @@ -151,14 +148,14 @@ public slots: int verbose = 0; int timeout = 5000; bool dumpRaw = false; // if true show all messages coming from the gps board that can - // be interpreted as QString by QString(message) (basically all NMEA) + // be interpreted as QString by QString(message) (basically all NMEA) bool discardAllNMEA = true; // if true discard all NMEA messages and do not parse them bool showout = false; // if true show the ubx messages sent to the gps board as hex bool showin = false; - std::queue outMsgBuffer; + std::queue outMsgBuffer; UbxMessage* msgWaitingForAck = nullptr; QPointer ackTimer; - int sendRetryCounter=0; + int sendRetryCounter = 0; // all global variables used for keeping track of satellites and statistics (gpsProperty) gpsProperty leapSeconds; @@ -174,11 +171,10 @@ public slots: gpsProperty eventCounter; gpsProperty clkBias; gpsProperty clkDrift; - gpsProperty > m_satList; + gpsProperty> m_satList; gpsProperty geodeticPos; - const int MSGTIMEOUT = 1500; + const int MSGTIMEOUT = 1500; std::queue fTimestamps; - //std::list fMessageBuffer; static std::string fProtVersionString; }; diff --git a/source/daemon/include/custom_io_operators.h b/daemon/include/utility/custom_io_operators.h similarity index 99% rename from source/daemon/include/custom_io_operators.h rename to daemon/include/utility/custom_io_operators.h index 6dfe2503..8bb3a095 100644 --- a/source/daemon/include/custom_io_operators.h +++ b/daemon/include/utility/custom_io_operators.h @@ -2,9 +2,8 @@ #define CUSTOM_IO_OPERATORS_H #include #include -#include #include - +#include std::ostream& operator<<(std::ostream& os, const QString& someQString); std::ostream& operator<<(std::ostream& os, const std::chrono::time_point& timestamp); diff --git a/source/daemon/include/filehandler.h b/daemon/include/utility/filehandler.h similarity index 79% rename from source/daemon/include/filehandler.h rename to daemon/include/utility/filehandler.h index b592ced3..c167aee7 100644 --- a/source/daemon/include/filehandler.h +++ b/daemon/include/utility/filehandler.h @@ -1,21 +1,20 @@ #ifndef FILEHANDLER_H #define FILEHANDLER_H +#include #include #include +#include #include #include -#include #include -#include -#include #include +#include "logparameter.h" -class FileHandler : public QObject -{ +class FileHandler : public QObject { Q_OBJECT public: - FileHandler(const QString& userName, const QString& passWord, quint32 fileSizeMB = 500, QObject *parent = nullptr); + FileHandler(const QString& userName, const QString& passWord, quint32 fileSizeMB = 500, QObject* parent = nullptr); QString getCurrentDataFileName() const; QString getCurrentLogFileName() const; QFileInfo dataFileInfo() const; @@ -25,7 +24,7 @@ class FileHandler : public QObject signals: void logIntervalSignal(); void mqttConnect(QString username, QString password); - void logRotateSignal(); + void logRotateSignal(); public slots: void start(); @@ -37,8 +36,8 @@ private slots: private: // save and send data everyday - QFile *dataFile = nullptr; // the file date is currently written to. (timestamps) - QFile *logFile = nullptr; // the file log information is written to. + QFile* dataFile = nullptr; // the file date is currently written to. (timestamps) + QFile* logFile = nullptr; // the file log information is written to. QString hashedMacAddress; QString configFilePath; QString loginDataFilePath; @@ -48,9 +47,7 @@ private slots: QString currentWorkingLogPath; QString username; QString password; - QFlags defaultPermissions = QFileDevice::WriteOwner|QFileDevice::WriteUser| - QFileDevice::WriteGroup|QFileDevice::ReadOwner|QFileDevice::ReadUser| - QFileDevice::ReadGroup|QFileDevice::ReadOther; + QFlags defaultPermissions = QFileDevice::WriteOwner | QFileDevice::WriteUser | QFileDevice::WriteGroup | QFileDevice::ReadOwner | QFileDevice::ReadUser | QFileDevice::ReadGroup | QFileDevice::ReadOther; QStringList notUploadedFilesNames; bool saveLoginData(QString username, QString password); bool readLoginData(); @@ -65,8 +62,6 @@ private slots: quint32 fileSize; // in MB QDateTime lastUploadDateTime; QTime dailyUploadTime; -// float temperature = 0.0; -// quint8 pcaChannel = 0; }; #endif // FILEHANDLER_H diff --git a/daemon/include/utility/geohash.h b/daemon/include/utility/geohash.h new file mode 100644 index 00000000..5a015b88 --- /dev/null +++ b/daemon/include/utility/geohash.h @@ -0,0 +1,14 @@ +#ifndef GEOHASH_H +#define GEOHASH_H + +#include +#include + +class GeoHash : public QObject { + Q_OBJECT +public: + GeoHash() = delete; + static QString hashFromCoordinates(double lon, double lat, int precision = 6); +}; + +#endif // GEOHASH_H diff --git a/daemon/include/utility/gpio_mapping.h b/daemon/include/utility/gpio_mapping.h new file mode 100644 index 00000000..e0742fbe --- /dev/null +++ b/daemon/include/utility/gpio_mapping.h @@ -0,0 +1,80 @@ +#ifndef GPIO_MAPPING_H +#define GPIO_MAPPING_H +#include +#include + +#define MAX_HW_VER 3 + + +// Mapping between signals of the MuonPi hardware interface and the actual GPIO pins of the RaspberryPi +// ATTENTION: +// All pins are numbered according to the BCM designation + +static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER + 1] = { + { + /* Pin mapping, HW Version 0, proxy to be never used nor initializing something */ + }, + { /* Pin mapping, HW Version 1 */ + { UBIAS_EN, 4 }, + { PREAMP_1, 20 }, + { PREAMP_2, 21 }, + { EVT_AND, 5 }, + { EVT_XOR, 6 }, + { GAIN_HL, 17 }, + { ADC_READY, 23 }, + { TIMEPULSE, 18 }, + { STATUS1, 13 }, + { STATUS2, 19 }, + { STATUS3, 26 }, + { TDC_INTB, 24 }, + { TDC_STATUS, 25 }, + { EXT_TRIGGER, 16 } + } , + { + /* Pin mapping, HW Version 2 */ + { UBIAS_EN, 26 }, + { PREAMP_1, 4 }, + { PREAMP_2, 17 }, + { EVT_AND, 22 }, + { EVT_XOR, 27 }, + { GAIN_HL, 6 }, + { ADC_READY, 12 }, + { TIMEPULSE, 18 }, + { TIME_MEAS_OUT, 5 }, + { STATUS1, 13 }, + { STATUS2, 19 }, + { PREAMP_FAULT, 23 }, + { TDC_INTB, 20 }, + { TDC_STATUS, 21 }, + { EXT_TRIGGER, 16 } }, + { /* Pin mapping, HW Version 3 */ + { UBIAS_EN, 26 }, + { PREAMP_1, 4 }, + { PREAMP_2, 17 }, + { EVT_AND, 22 }, + { EVT_XOR, 27 }, + { GAIN_HL, 6 }, + { ADC_READY, 12 }, + { TIMEPULSE, 18 }, + { TIME_MEAS_OUT, 5 }, + { STATUS1, 13 }, + { STATUS2, 19 }, + { PREAMP_FAULT, 23 }, + { TDC_INTB, 20 }, + { TDC_STATUS, 21 }, + { EXT_TRIGGER, 16 }, + { IN_POL1, 24 }, + { IN_POL2, 25 } } +}; + +extern std::map GPIO_PINMAP; + +inline GPIO_SIGNAL bcmToGpioSignal(unsigned int bcmGpioNumber) +{ + std::map::const_iterator i = GPIO_PINMAP.cbegin(); + while (i != GPIO_PINMAP.cend() && i->second!=bcmGpioNumber) ++i; + if (i==GPIO_PINMAP.cend()) return UNDEFINED_SIGNAL; + return i->first; +} + +#endif //GPIO_MAPPING_H diff --git a/source/daemon/include/ratebuffer.h b/daemon/include/utility/ratebuffer.h similarity index 98% rename from source/daemon/include/ratebuffer.h rename to daemon/include/utility/ratebuffer.h index 8735353c..63d5a42e 100644 --- a/source/daemon/include/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -4,7 +4,7 @@ #include #include #include -#include +#include #include #include #include @@ -13,9 +13,10 @@ class PigpiodHandler; +using namespace std::literals; + constexpr double MAX_AVG_RATE { 100. }; constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; -using namespace std::literals; constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6/MAX_AVG_RATE) }; diff --git a/daemon/include/utility/unixtime_from_gps.h b/daemon/include/utility/unixtime_from_gps.h new file mode 100644 index 00000000..b95f3e1b --- /dev/null +++ b/daemon/include/utility/unixtime_from_gps.h @@ -0,0 +1,20 @@ +#ifndef UNIXTIME_FROM_GPS_H +#define UNIXTIME_FROM_GPS_H + +#include +#include + +static timespec unixtime_from_gps(int week_nr, long int s_of_week, long int ns) { + QDateTime gpsTimeStart(QDate(1980,1,6),QTime(0,0,0,0),Qt::UTC); + quint64 gpsOffsetToEpoch = gpsTimeStart.toMSecsSinceEpoch()/1000; + quint64 secs = gpsOffsetToEpoch; + secs += week_nr*7*24*3600; // 7 days per week, 24 hours per day and 3600 seconds per hour + secs += s_of_week; + struct timespec ts; + ts.tv_sec = secs; + ts.tv_nsec = ns; + + return ts; +} + +#endif // UNIXTIME_FROM_GPS_H diff --git a/source/daemon/muondetector.conf.template b/daemon/muondetector.conf.template similarity index 100% rename from source/daemon/muondetector.conf.template rename to daemon/muondetector.conf.template diff --git a/daemon/src/calibration.cpp b/daemon/src/calibration.cpp new file mode 100644 index 00000000..64993145 --- /dev/null +++ b/daemon/src/calibration.cpp @@ -0,0 +1,278 @@ +#include "calibration.h" +#include +#include +#include +#include + +#define AS_U32(f) (*(uint32_t*)&(f)) +#define AS_U16(f) (*(uint16_t*)&(f)) +#define AS_TIME(u) (*(time_t*)&(u)) +#define AS_I8(f) (*(int8_t*)&(f)) +#define AS_I32(f) (*(int32_t*)&(f)) +#define AS_I16(f) (*(int16_t*)&(f)) +#define AS_FLOAT(u) (*(float*)&(u)) +#define AS_FLOAT_C(u) (*(const float*)&(u)) + +using namespace std; + +const CalibStruct ShowerDetectorCalib::InvalidCalibStruct = CalibStruct("", "", 0, ""); + +void ShowerDetectorCalib::init() +{ + const uint16_t n = 256; + for (int i = 0; i < n; i++) + fEepBuffer[i] = 0; + buildCalibList(); + if ( fEeprom ) { + fEepromValid = fEeprom->probeDevicePresence() && readFromEeprom(); + } +} + +void ShowerDetectorCalib::buildCalibList() +{ + fCalibList.clear(); + std::vector>::const_iterator it; + uint8_t addr = 0x02; // calib range starts at 0x02 behind header + for (it = CALIBITEMS.begin(); it != CALIBITEMS.end(); it++) { + CalibStruct calibItem; + calibItem.name = std::get<0>(*it); + calibItem.type = std::get<1>(*it); + calibItem.address = addr; + addr += getTypeSize(std::get<1>(*it)); + calibItem.value = std::get<2>(*it); + fCalibList.push_back(calibItem); + } +} + +uint8_t ShowerDetectorCalib::getTypeSize(const std::string& a_type) +{ + string str = a_type; + std::transform(a_type.begin(), a_type.end(), str.begin(), + [](unsigned char c) { return std::toupper(c); }); + uint8_t size = 0; + if (str == "UINT8") + size = 1; + else if (str == "UINT16") + size = 2; + else if (str == "UINT32") + size = 4; + else if (str == "FLOAT") + size = 4; + else if (str == "INT8") + size = 1; + else if (str == "INT16") + size = 2; + else if (str == "INT32") + size = 4; + + return size; +} + +const CalibStruct& ShowerDetectorCalib::getCalibItem(unsigned int i) const +{ + if (i < fCalibList.size()) + return fCalibList[i]; + else + return InvalidCalibStruct; +} + +const CalibStruct& ShowerDetectorCalib::getCalibItem(const std::string& name) +{ + string str = name; + std::transform(name.begin(), name.end(), str.begin(), + [](unsigned char c) { return std::toupper(c); }); + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&str](const CalibStruct& item) { return item.name == str; }); + if (result != std::end(fCalibList)) + return *result; + else + return InvalidCalibStruct; +} + +void ShowerDetectorCalib::setCalibItem(const std::string& name, const CalibStruct& item) +{ + string str = name; + std::transform(name.begin(), name.end(), str.begin(), + [](unsigned char c) { return std::toupper(c); }); + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&str](const CalibStruct& s) { return s.name == str; }); + + if (result != std::end(fCalibList)) { + *result = item; + } +} + +bool ShowerDetectorCalib::readFromEeprom() +{ + if ( !fEeprom ) { + return false; + } + const uint16_t n = 256; + for (int i = 0; i < n; i++) + fEepBuffer[i] = 0; + bool success = ( fEeprom->readBytes(0, n, fEepBuffer) == n ); + if (!success) { + fEepromValid = false; + return false; + } + uint16_t eepheader = AS_U16(fEepBuffer[0]); + if (eepheader == CALIB_HEADER) + fValid = true; + else { + fValid = false; + return true; + } + + for (auto it = fCalibList.begin(); it != fCalibList.end(); it++) { + string str = it->type; + std::ostringstream ostr; + if (str == "UINT8") { + uint8_t val = fEepBuffer[it->address]; + it->value = std::to_string(val); + } else if (str == "UINT16") { + uint16_t val = AS_U16(fEepBuffer[it->address]); + it->value = std::to_string(val); + } else if (str == "UINT32") { + uint32_t val = AS_U32(fEepBuffer[it->address]); + it->value = std::to_string(val); + } else if (str == "FLOAT") { + uint32_t _x = AS_U32(fEepBuffer[it->address]); + if (fVerbose > 5) + cout << "as U32=" << _x << " "; + float val = AS_FLOAT_C(_x); + if (fVerbose > 5) + cout << "as FLOAT=" << val << " "; + ostr << std::setprecision(7) << std::scientific << val; + it->value = ostr.str(); + } else if (str == "INT8") { + int8_t val = AS_I8(fEepBuffer[it->address]); + it->value = std::to_string(val); + } else if (str == "INT16") { + int16_t val = AS_I16(fEepBuffer[it->address]); + it->value = std::to_string(val); + } else if (str == "INT32") { + int32_t val = AS_I32(fEepBuffer[it->address]); + it->value = std::to_string(val); + } else { + } + } + return true; +} + +bool ShowerDetectorCalib::writeToEeprom() +{ + if ( !fEepromValid ) + return false; + // before we write to eeprom, increase the write cycle counter + CalibStruct item = getCalibItem("WRITE_CYCLES"); + uint32_t cycleCounter; + getValueFromString(item.value, cycleCounter); + cycleCounter++; + setCalibItem("WRITE_CYCLES", cycleCounter); + // write content of all calib parameters to buffer before actually writing to the eep + updateBuffer(); + bool success = fEeprom->writeBytes(0, 256, fEepBuffer); + if (!success) { + cerr << "error: write to eeprom failed!" << endl; + return false; + } + if (fVerbose > 1) + cout << "eep write took " << fEeprom->getLastTimeInterval() << " ms" << endl; + // reset update flags of all properties since we just wrote them freshly into the EEPROM + return true; +} + +void ShowerDetectorCalib::updateBuffer() +{ + // write fixed header + AS_U16(fEepBuffer[0]) = CALIB_HEADER; + + for (auto it = fCalibList.begin(); it != fCalibList.end(); it++) { + string str = it->type; + if (str == "UINT8") { + unsigned int val; + getValueFromString(it->value, val); + fEepBuffer[it->address] = (uint8_t)val; + } else if (str == "UINT16") { + unsigned int val; + getValueFromString(it->value, val); + AS_U16(fEepBuffer[it->address]) = (uint16_t)val; + } else if (str == "UINT32") { + unsigned int val; + getValueFromString(it->value, val); + AS_U32(fEepBuffer[it->address]) = (uint32_t)val; + } else if (str == "FLOAT") { + float val; + getValueFromString(it->value, val); + AS_FLOAT(fEepBuffer[it->address]) = val; + } else if (str == "INT8") { + int val; + getValueFromString(it->value, val); + AS_I8(fEepBuffer[it->address]) = (int8_t)val; + } else if (str == "INT16") { + int val; + getValueFromString(it->value, val); + AS_I16(fEepBuffer[it->address]) = (int16_t)val; + } else if (str == "INT32") { + int val; + getValueFromString(it->value, val); + AS_I32(fEepBuffer[it->address]) = (int32_t)val; + } else { + } + } +} + +void ShowerDetectorCalib::printBuffer() +{ + cout << "*** Calibration buffer content ***" << endl; + for (int j = 0; j < 16; j++) { + cout << hex << std::setfill('0') << std::setw(2) << j * 16 << ": "; + for (int i = 0; i < 16; i++) { + cout << hex << std::setfill('0') << std::setw(2) << (int)fEepBuffer[j * 16 + i] << " "; + } + cout << endl; + } + cout << dec; +} + +void ShowerDetectorCalib::printCalibList() +{ + cout << "*** Calibration parameters ***" << dec << endl; + int i = 0; + for (auto it = fCalibList.begin(); it != fCalibList.end(); it++) { + cout << ++i << ": " << it->name; + if (it->type == "FLOAT") { + float val; + getValueFromString(it->value, val); + cout << " \t= " << std::setprecision(8) << val << " '" << it->value << "'" + << " (" << it->type << ") @" << (int)it->address << endl; + } else + cout << " \t= " << it->value << " (" << it->type << ") @" << (int)it->address << endl; + } +} + +// partial specialization of member function template. Must reside OUTSIDE header file +template <> +void ShowerDetectorCalib::setCalibItem(const std::string& name, float value) +{ + CalibStruct item; + item = getCalibItem(name); + if (item.name == name) { + std::ostringstream ostr; + ostr << std::setprecision(7); + ostr << std::scientific << (double)value; + item.value = ostr.str(); + setCalibItem(name, item); + } +} + +uint64_t ShowerDetectorCalib::getSerialID() +{ + // we assume that the unique ID is stored in the six last bytes of the EEPROM memory + uint64_t id = 0x0000000000000000; + id = fEepBuffer[255]; + id |= (uint64_t)fEepBuffer[254] << 8; + id |= (uint64_t)fEepBuffer[253] << 16; + id |= (uint64_t)fEepBuffer[252] << 24; + id |= (uint64_t)fEepBuffer[251] << 32; + id |= (uint64_t)fEepBuffer[250] << 40; + return id; +} diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp new file mode 100644 index 00000000..f4e2b0c5 --- /dev/null +++ b/daemon/src/daemon.cpp @@ -0,0 +1,2585 @@ +#include +#include +#include +#include +#include +#include +#include +#include "utility/geohash.h" +#include "utility/gpio_mapping.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "hardware/i2cdevices.h" +#include "hardware/i2c/i2cutil.h" +#include "hardware/device_types.h" + +#define DAC_BIAS 2 // channel of the dac where bias voltage is set +#define DAC_TH1 0 // channel of the dac where threshold 1 is set +#define DAC_TH2 1 // channel of the dac where threshold 2 is set + +#define DEGREE_CHARCODE 248 + +// REMEMBER: "emit" keyword is just syntactic sugar and not needed AT ALL ... learned it after 1 year *clap* *clap* + +using namespace std; + +static unsigned int HW_VERSION = 0; // default value is set in calibration.h + +int64_t msecdiff(timespec& ts, timespec& st) +{ + int64_t diff; + diff = (int64_t)ts.tv_sec - (int64_t)st.tv_sec; + diff *= 1000; + diff += ((int64_t)ts.tv_nsec - (int64_t)st.tv_nsec) / 1000000; + return diff; +} + +static QVector allMsgCfgID({ UBX_TIM_TM2, UBX_TIM_TP, + UBX_NAV_CLOCK, UBX_NAV_DGPS, UBX_NAV_AOPSTATUS, UBX_NAV_DOP, + UBX_NAV_POSECEF, UBX_NAV_POSLLH, UBX_NAV_PVT, UBX_NAV_SBAS, UBX_NAV_SOL, + UBX_NAV_STATUS, UBX_NAV_SVINFO, UBX_NAV_TIMEGPS, UBX_NAV_TIMEUTC, UBX_NAV_VELECEF, + UBX_NAV_VELNED, + UBX_MON_HW, UBX_MON_HW2, UBX_MON_IO, UBX_MON_MSGPP, + UBX_MON_RXBUF, UBX_MON_RXR, UBX_MON_TXBUF }); + +// signal handling stuff: put code to execute before shutdown down there +static int setup_unix_signal_handlers() +{ + struct sigaction hup, term, inte; + + hup.sa_handler = Daemon::hupSignalHandler; + sigemptyset(&hup.sa_mask); + hup.sa_flags = 0; + hup.sa_flags |= SA_RESTART; + + if (sigaction(SIGHUP, &hup, 0)) { + return 1; + } + + term.sa_handler = Daemon::termSignalHandler; + sigemptyset(&term.sa_mask); + term.sa_flags = 0; + term.sa_flags |= SA_RESTART; + + if (sigaction(SIGTERM, &term, 0)) { + return 2; + } + + inte.sa_handler = Daemon::intSignalHandler; + sigemptyset(&inte.sa_mask); + inte.sa_flags = 0; + inte.sa_flags |= SA_RESTART; + + if (sigaction(SIGINT, &inte, 0)) { + return 3; + } + return 0; +} +int Daemon::sighupFd[2]; +int Daemon::sigtermFd[2]; +int Daemon::sigintFd[2]; + +void Daemon::handleSigTerm() +{ + snTerm->setEnabled(false); + char tmp; + ::read(sigtermFd[1], &tmp, sizeof(tmp)); + + // do Qt stuff + if (verbose > 1) { + cout << "\nSIGTERM received" << endl; + } + + // save ublox config in built-in flash to provide latest orbit info of sats for next start-up + // and effectively reduce time-to-first-fix (TTFF) + emit UBXSaveCfg(); + + emit aboutToQuit(); + exit(0); + snTerm->setEnabled(true); +} + +void Daemon::handleSigHup() +{ + snHup->setEnabled(false); + char tmp; + ::read(sighupFd[1], &tmp, sizeof(tmp)); + + // do Qt stuff + if (verbose > 1) { + cout << "\nSIGHUP received" << endl; + } + + // save ublox config in built-in flash to provide latest orbit info of sats for next start-up + // and effectively reduce time-to-first-fix (TTFF) + emit UBXSaveCfg(); + + emit aboutToQuit(); + exit(0); + snHup->setEnabled(true); +} + +void Daemon::handleSigInt() +{ + snInt->setEnabled(false); + char tmp; + ::read(sigintFd[1], &tmp, sizeof(tmp)); + + // do Qt stuff + if (verbose > 1) { + cout << "\nSIGINT received" << endl; + } + if (showin || showout) { + qDebug() << allMsgCfgID.size(); + qDebug() << msgRateCfgs.size(); + for (QMap::iterator it = msgRateCfgs.begin(); it != msgRateCfgs.end(); it++) { + qDebug().nospace() << "0x" << hex << (uint8_t)(it.key() >> 8) << " 0x" << hex << (uint8_t)(it.key() & 0xff) << " " << dec << it.value(); + } + } + + // save ublox config in built-in flash to provide latest orbit info of sats for next start-up + // and effectively reduce time-to-first-fix (TTFF) + emit UBXSaveCfg(); + + emit aboutToQuit(); + exit(0); + snInt->setEnabled(true); +} + +Daemon::Daemon(configuration cfg, QObject* parent) + : QTcpServer { parent } + , config { cfg } +{ + // first, we must set the locale to be independent of the number format of the system's locale. + // We rely on parsing floating point numbers with a decimal point (not a komma) which might fail if not setting the classic locale + std::locale::global(std::locale::classic()); + + qRegisterMetaType("TcpMessage"); + qRegisterMetaType("GeodeticPos"); + qRegisterMetaType("int32_t"); + qRegisterMetaType("uint32_t"); + qRegisterMetaType("uint16_t"); + qRegisterMetaType("uint8_t"); + qRegisterMetaType("int8_t"); + qRegisterMetaType("bool"); + qRegisterMetaType("CalibStruct"); + qRegisterMetaType>("std::vector"); + qRegisterMetaType>("std::vector"); + qRegisterMetaType>("std::chrono::duration"); + qRegisterMetaType("std::string"); + qRegisterMetaType("LogParameter"); + qRegisterMetaType("UbxTimePulseStruct"); + qRegisterMetaType("UbxDopStruct"); + qRegisterMetaType("timespec"); + qRegisterMetaType("GPIO_SIGNAL"); + qRegisterMetaType("GnssMonHwStruct"); + qRegisterMetaType("GnssMonHw2Struct"); + qRegisterMetaType("UbxTimeMarkStruct"); + qRegisterMetaType("I2cDeviceEntry"); + qRegisterMetaType("ADC_SAMPLING_MODE"); + qRegisterMetaType("PigpiodHandler::EventEdge"); + qRegisterMetaType("EventTime"); + + // signal handling + setup_unix_signal_handlers(); + if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sighupFd)) { + qFatal("Couldn't create HUP socketpair"); + } + + if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sigtermFd)) { + qFatal("Couldn't create TERM socketpair"); + } + if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sigintFd)) { + qFatal("Couldn't createe INT socketpair"); + } + + snHup = new QSocketNotifier(sighupFd[1], QSocketNotifier::Read, this); + connect(snHup, SIGNAL(activated(int)), this, SLOT(handleSigHup())); + snTerm = new QSocketNotifier(sigtermFd[1], QSocketNotifier::Read, this); + connect(snTerm, SIGNAL(activated(int)), this, SLOT(handleSigTerm())); + snInt = new QSocketNotifier(sigintFd[1], QSocketNotifier::Read, this); + connect(snInt, SIGNAL(activated(int)), this, SLOT(handleSigInt())); + + // general + verbose = cfg.verbose; + if (verbose > 4) { + qDebug() << "daemon running in thread " << this->thread()->objectName(); + } + + if (verbose > 3) { + qDebug() << "QT version is " << QString::number(QT_VERSION, 16); + } + if (verbose > 3) { + this->thread()->setObjectName("muondetector-daemon"); + qInfo() << this->thread()->objectName() << " thread id (pid): " << syscall(SYS_gettid); + } + + // connect logParameter signal to log engine before anything else is done + // since we want to log some initial one-time log parameters on start-up + connect(this, &Daemon::logParameter, &logEngine, &LogEngine::onLogParameterReceived); + + // reset the I2C bus by issuing a general call reset + I2cGeneralCall::resetDevices(); + + // try to find out on which hardware version we are running + // for this to work, we have to initialize and read the eeprom first + // EEPROM 24AA02 type + std::shared_ptr eep24aa02_p; + std::set possible_addresses { 0x50 }; + auto found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + eep24aa02_p = std::make_shared( found_dev_addresses.front() ); + } + if ( eep24aa02_p && eep24aa02_p->identify() ) + { + eep_p = std::static_pointer_cast>( eep24aa02_p ); + std::cout << "eeprom " << eep24aa02_p->getName() <<" identified at 0x" << std::hex << (int)eep24aa02_p->getAddress() << std::endl; + } else { + eep24aa02_p.reset(); + qCritical() << "eeprom device NOT found!"; + } + + calib = new ShowerDetectorCalib( eep24aa02_p ); + if ( eep_p->probeDevicePresence() ) { + calib->readFromEeprom(); + if (verbose > 2) { + + // Caution, only for debugging. This code snippet writes a test sequence into the eeprom + if (1 == 0) { + uint8_t buf[256]; + for (int i = 0; i < 256; i++) + buf[i] = i; + if ( !eep24aa02_p->writeBytes(0, 256, buf) ) + cerr << "error: write to eeprom failed!" << endl; + if (verbose > 2) + cout << "eep write took " << eep24aa02_p->getLastTimeInterval() << " ms" << endl; + readEeprom(); + } + if (1 == 1) { + calib->printCalibList(); + } + } + uint64_t id = calib->getSerialID(); + QString hwIdStr = QString::number(id, 16); + logParameter(LogParameter("uniqueId", hwIdStr, LogParameter::LOG_ONCE)); + hwIdStr = "0x"+hwIdStr; + qInfo() << "EEP unique ID:" << hwIdStr; + } + CalibStruct verStruct = calib->getCalibItem("VERSION"); + unsigned int version = 0; + ShowerDetectorCalib::getValueFromString(verStruct.value, version); + if (version > 0) { + HW_VERSION = version; + qInfo() << "Found HW version" << version << "in eeprom"; + } + + // set up the pin definitions (hw version specific) + GPIO_PINMAP = GPIO_PINMAP_VERSIONS[HW_VERSION]; + + if (verbose > 1) { + // print out the current gpio pin mapping + // (function, gpio-pin, direction) + cout << "GPIO pin mapping:" << endl; + + for (auto signalIt = GPIO_PINMAP.begin(); signalIt != GPIO_PINMAP.end(); signalIt++) { + const GPIO_SIGNAL signalId = signalIt->first; + cout << GPIO_SIGNAL_MAP[signalId].name << " \t: " << signalIt->second; + switch (GPIO_SIGNAL_MAP[signalId].direction) { + case DIR_IN: + cout << " (in)"; + break; + case DIR_OUT: + cout << " (out)"; + break; + case DIR_IO: + cout << " (i/o)"; + break; + default: + cout << " (undef)"; + } + cout << endl; + } + } + + mqttHandlerThread = new QThread(); + mqttHandlerThread->setObjectName("muondetector-daemon-mqtt"); + connect(this, &Daemon::aboutToQuit, mqttHandlerThread, &QThread::quit); + connect(mqttHandlerThread, &QThread::finished, mqttHandlerThread, &QThread::deleteLater); + + mqttHandler = new MuonPi::MqttHandler(cfg.station_ID, verbose - 1); + mqttHandler->moveToThread(mqttHandlerThread); + connect(mqttHandler, &MuonPi::MqttHandler::mqttConnectionStatus, this, &Daemon::sendMqttStatus); + connect(mqttHandler, &MuonPi::MqttHandler::giving_up, this, &Daemon::handleSigTerm); + connect(fileHandlerThread, &QThread::finished, mqttHandler, &MuonPi::MqttHandler::deleteLater); + connect(this, &Daemon::requestMqttConnectionStatus, mqttHandler, &MuonPi::MqttHandler::onRequestConnectionStatus); + mqttHandlerThread->start(); + + // create fileHandler + fileHandlerThread = new QThread(); + fileHandlerThread->setObjectName("muondetector-daemon-filehandler"); + connect(this, &Daemon::aboutToQuit, fileHandlerThread, &QThread::quit); + connect(fileHandlerThread, &QThread::finished, fileHandlerThread, &QThread::deleteLater); + + fileHandler = new FileHandler(cfg.username, cfg.password); + fileHandler->moveToThread(fileHandlerThread); + connect(this, &Daemon::aboutToQuit, fileHandler, &FileHandler::deleteLater); + connect(fileHandlerThread, &QThread::started, fileHandler, &FileHandler::start); + connect(fileHandlerThread, &QThread::finished, fileHandler, &FileHandler::deleteLater); + connect(fileHandler, &FileHandler::mqttConnect, mqttHandler, &MuonPi::MqttHandler::start); + fileHandlerThread->start(); + + // connect log signals to and from log engine and filehandler + connect(&logEngine, &LogEngine::sendLogString, mqttHandler, &MuonPi::MqttHandler::sendLog); + connect(&logEngine, &LogEngine::sendLogString, fileHandler, &FileHandler::writeToLogFile); + // connect to the regular log timer signal to log several non-regularly polled parameters + connect(&logEngine, &LogEngine::logIntervalSignal, this, &Daemon::onLogParameterPolled); + // connect the once-log flag reset slot of log engine with the logRotate signal of filehandler + connect(fileHandler, &FileHandler::logRotateSignal, &logEngine, &LogEngine::onOnceLogTrigger); + + // instantiate, detect and initialize all other i2c devices + + // MIC184 or LM75 temp sensor + possible_addresses = { 0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, 0x4f }; + found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + temp_sensor_p = std::make_shared( found_dev_addresses.front() ); + } else { + // LM75A temp sensor + found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + temp_sensor_p = std::make_shared( found_dev_addresses.front() ); + } else { + qWarning() << "temp sensor NOT present!"; + } + } + + if ( temp_sensor_p && temp_sensor_p->probeDevicePresence() ) { + std::cout << "temp sensor "<< temp_sensor_p->getName() << " identified at 0x" << std::hex << (int)dynamic_cast(temp_sensor_p.get())->getAddress() << std::endl; + if (verbose > 2) { + std::cout << "function is " << temp_sensor_p->typeString() << std::endl; + std::cout << "temperature is " << temp_sensor_p->getTemperature() << std::endl; + std::cout << "readout took " << std::dec << dynamic_cast(temp_sensor_p.get())->getLastTimeInterval() << "ms" << std::endl; + } + if ( dynamic_cast(temp_sensor_p.get())->getTitle() == "MIC184" ) { + dynamic_cast( temp_sensor_p.get() )->setExternal( false ); + } + } + + // detect and instantiate the I2C ADC ADS1015/1115 + std::shared_ptr ads1115_p; + possible_addresses = { 0x48, 0x49, 0x4a, 0x4b }; + found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + ads1115_p = std::make_shared( found_dev_addresses.front() ); + adc_p = std::static_pointer_cast>( ads1115_p ); + std::cout << "ADS1115 identified at 0x" << std::hex << (int)ads1115_p->getAddress() << std::endl; + } else { + adcSamplingMode = ADC_SAMPLING_MODE::DISABLED; + qWarning() << "ADS1115 device NOT present!"; + } + + if ( ads1115_p && ads1115_p->probeDevicePresence() ) { + ads1115_p->setPga(ADS1115::PGA4V); // set full scale range to 4 Volts + ads1115_p->setRate( ADS1115::SPS860 ); // set sampling rate to the maximum of 860 samples per second + ads1115_p->setAGC(false); // turn AGC off for all channels + if (!ads1115_p->setDataReadyPinMode()) { + qWarning() << "error: failed setting data ready pin mode (setting thresh regs)"; + } + + // set up sampling timer used for continuous sampling mode + samplingTimer.setInterval(MuonPi::Config::Hardware::trace_sampling_interval); + samplingTimer.setSingleShot(false); + samplingTimer.setTimerType(Qt::PreciseTimer); + connect(&samplingTimer, &QTimer::timeout, this, &Daemon::sampleAdc0TraceEvent); + + // set up peak sampling mode + setAdcSamplingMode(ADC_SAMPLING_MODE::PEAK); + + // set callback function for sample-ready events of the ADC + adc_p->registerConversionReadyCallback( [this](ADS1115::Sample sample) { this->onAdcSampleReady(sample); } ); + + if (verbose > 2) { + bool ok = ads1115_p->setLowThreshold(0b0000000000000000); + ok = ok && ads1115_p->setHighThreshold(0b1000000000000000); + if (ok) + qDebug() << "successfully setting threshold registers"; + else + qWarning() << "error: failed setting threshold registers"; + qDebug() << "single ended channels:"; + qDebug() << "ch0: " << ads1115_p->readADC(0) << " ch1: " << ads1115_p->readADC(1) + << " ch2: " << ads1115_p->readADC(2) << " ch3: " << ads1115_p->readADC(3); + ads1115_p->setDiffMode(true); + qDebug() << "diff channels:"; + qDebug() << "ch0-1: " << ads1115_p->readADC(0) << " ch0-3: " << ads1115_p->readADC(1) + << " ch1-3: " << ads1115_p->readADC(2) << " ch2-3: " << ads1115_p->readADC(3); + ads1115_p->setDiffMode(false); + qDebug() << "readout took " << ads1115_p->getLastTimeInterval() << " ms"; + } + } + + // 4ch DAC MCP4728 + std::shared_ptr mcp4728_p; + possible_addresses = { 0x60, 0x61, 0x62, 0x63, 0x64, 0x65, 0x66, 0x67 }; + found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + mcp4728_p = std::make_shared( found_dev_addresses.front() ); + dac_p = std::static_pointer_cast>( mcp4728_p ); + std::cout << "MCP4728 identified at 0x" << std::hex << (int)mcp4728_p->getAddress() << std::endl; + } else { + qFatal("MCP4728 device NOT present!"); + // this error is critical, since the whole concept of counting muons is based on + // the function of the threshold discriminator + // we should quit here returning an error code (?) + } + + if ( mcp4728_p && mcp4728_p->probeDevicePresence() ) { + //mcp4728_p->setVRef( MCP4728::VREF_VDD ); + if (verbose > 2) { + qInfo() << "MCP4728 device is present."; + qDebug() << "DAC registers / output voltages:"; + for (int i = 0; i < 4; i++) { + MCP4728::DacChannel dacChannel; + MCP4728::DacChannel eepromChannel; + eepromChannel.eeprom = true; + mcp4728_p->readChannel(i, dacChannel); + mcp4728_p->readChannel(i, eepromChannel); + qDebug() << " ch" << i << ": " << dacChannel.value << " = " << MCP4728::code2voltage(dacChannel) << " V" + " (stored: " + << eepromChannel.value << " = " << MCP4728::code2voltage(eepromChannel) << " V)"; + } + qDebug() << "readout took " << mcp4728_p->getLastTimeInterval() << " ms"; + } + } + + for (int i = std::min(DAC_TH1, DAC_TH2); i <= std::max(DAC_TH1, DAC_TH2); i++) { + if ( cfg.dacThresh[i] < 0. && mcp4728_p->probeDevicePresence() ) { + MCP4728::DacChannel dacChannel; + MCP4728::DacChannel eepromChannel; + eepromChannel.eeprom = true; + mcp4728_p->readChannel(i, dacChannel); + mcp4728_p->readChannel(i, eepromChannel); + cfg.dacThresh[i] = MCP4728::code2voltage(dacChannel); + } + } + dacThresh.push_back(cfg.dacThresh[0]); + dacThresh.push_back(cfg.dacThresh[1]); + + if ( mcp4728_p->probeDevicePresence() ) { + MCP4728::DacChannel eeprom_value; + eeprom_value.eeprom = true; + mcp4728_p->readChannel(DAC_BIAS, eeprom_value); + if (eeprom_value.value == 0) { + setBiasVoltage(MuonPi::Config::Hardware::DAC::Voltage::bias); + setDacThresh(0, MuonPi::Config::Hardware::DAC::Voltage::threshold[0]); + setDacThresh(1, MuonPi::Config::Hardware::DAC::Voltage::threshold[1]); + } + } + + biasVoltage = cfg.biasVoltage; + if (biasVoltage < 0. && mcp4728_p->probeDevicePresence()) { + MCP4728::DacChannel dacChannel; + MCP4728::DacChannel eepromChannel; + eepromChannel.eeprom = true; + mcp4728_p->readChannel(DAC_BIAS, dacChannel); + mcp4728_p->readChannel(DAC_BIAS, eepromChannel); + biasVoltage = MCP4728::code2voltage(dacChannel); + } + + // PCA9536 4 bit I/O I2C device used for selecting the UBX timing input + std::shared_ptr pca9536_p; + possible_addresses = { 0x41 }; + found_dev_addresses = findI2cDeviceType( possible_addresses ); + if ( found_dev_addresses.size() > 0 ) { + pca9536_p = std::make_shared( found_dev_addresses.front() ); + io_extender_p = std::static_pointer_cast>( pca9536_p ); + std::cout << "PCA9536 identified at 0x" << std::hex << (int)pca9536_p->getAddress() << std::endl; + } else { + qWarning() << "PCA9536 device NOT found!"; + } + +// pca = new PCA9536(); + if ( io_extender_p && io_extender_p->probeDevicePresence() ) { + pca9536_p->identify(); + if (verbose > 2) { + qInfo() << "PCA9536 device is present." << endl; + qDebug() << " inputs: 0x" << hex << (int)io_extender_p->getInputState(); + qDebug() << "readout took " << dec << pca9536_p->getLastTimeInterval() << " ms"; + } + io_extender_p->setOutputPorts(0b00000111); + setPcaChannel(cfg.pcaPortMask); + } + + if ( mcp4728_p->probeDevicePresence() ) { + if (dacThresh[0] > 0) + dac_p->setVoltage(DAC_TH1, dacThresh[0]); + if (dacThresh[1] > 0) + dac_p->setVoltage(DAC_TH2, dacThresh[1]); + if (biasVoltage > 0) + dac_p->setVoltage(DAC_BIAS, biasVoltage); + } + + // removed initialization of ublox i2c interface since it doesn't work properly on RPi + // the Ublox i2c relies on clock stretching, which RPi is not supporting + // the ublox's i2c address is still occupied but locked, i.e. access is prohibited + ublox_i2c_p = std::make_shared( 0x42 ); + ublox_i2c_p->lock(); + if ( (verbose > 2) && ublox_i2c_p->devicePresent() ) { + qInfo() << "ublox I2C device interface is present."; + uint16_t bufcnt = 0; + bool ok = ublox_i2c_p->getTxBufCount(bufcnt); + if (ok) qDebug() << "bytes in TX buf: " << bufcnt; + } + + // check if also an Adafruit-SSD1306 compatible i2c OLED display is present + // initialize and start loop for display of several state variables + oled_p = std::make_shared( 0x3c ); + if ( !oled_p->devicePresent() ) { + oled_p = std::make_shared( 0x3d ); + } + if ( oled_p->devicePresent() ) { + if (verbose > -1) { + qInfo() << "I2C SSD1306-type OLED display found at address 0x" << hex << oled_p->getAddress(); + } + oled_p->begin(); + oled_p->clearDisplay(); + + // text display tests + oled_p->setTextSize(1); + oled_p->setTextColor(Adafruit_SSD1306::WHITE); + oled_p->setCursor(0, 2); + oled_p->print("*Cosmic Shower Det.*\n"); + oled_p->print("V"); + oled_p->print(MuonPi::Version::software.string().c_str()); + oled_p->print("\n"); + oled_p->display(); + usleep(50000L); + connect(&oledUpdateTimer, SIGNAL(timeout()), this, SLOT(updateOledDisplay())); + + oledUpdateTimer.start(MuonPi::Config::Hardware::OLED::update_interval); + } else { + oled_p.reset(); + } + + // for pigpio signals: + preampStatus[0] = cfg.preamp[0]; + preampStatus[1] = cfg.preamp[1]; + gainSwitch = cfg.gain; + biasON = cfg.bias_ON; + eventTrigger = cfg.eventTrigger; + polarity1 = cfg.polarity[0]; + polarity2 = cfg.polarity[1]; + + // for diagnostics: + // print out some i2c device statistics + if (verbose > 2) { + std::cout << "Nr. of invoked I2C devices (plain count): " << std::dec << i2cDevice::getNrDevices() << std::endl; + std::cout << "Nr. of invoked I2C devices (gl. device list's size): " << i2cDevice::getGlobalDeviceList().size() << std::endl; + std::cout << "Nr. of bytes read on I2C bus: " << i2cDevice::getGlobalNrBytesRead() << std::endl; + std::cout << "Nr. of bytes written on I2C bus: " << i2cDevice::getGlobalNrBytesWritten() << std::endl; + std::cout << "list of device addresses: " << std::endl; + for (uint8_t i = 0; i < i2cDevice::getGlobalDeviceList().size(); i++) { + std::cout << (int)i + 1 << " 0x" << std::hex << (int)i2cDevice::getGlobalDeviceList()[i]->getAddress() << " " << i2cDevice::getGlobalDeviceList()[i]->getTitle(); + if (i2cDevice::getGlobalDeviceList()[i]->devicePresent()) + std::cout << " present" << endl; + else + std::cout << " missing" << endl; + } + if ( temp_sensor_p ) dynamic_cast(temp_sensor_p.get())->getCapabilities(); + } + + // for ublox gnss module + gpsdevname = cfg.gpsdevname; + dumpRaw = cfg.dumpRaw; + baudrate = cfg.baudrate; + configGnss = cfg.configGnss; + showout = cfg.showout; + showin = cfg.showin; + + // for tcp connection with fileServer + peerPort = cfg.peerPort; + if (peerPort == 0) { + peerPort = 51508; + } + peerAddress = cfg.peerAddress; + if (peerAddress.isEmpty() || peerAddress == "local" || peerAddress == "localhost") { + peerAddress = QHostAddress(QHostAddress::LocalHost).toString(); + } + + if (cfg.serverAddress.isEmpty()) { + // if not otherwise specified: listen on all available addresses + daemonAddress = QHostAddress(QHostAddress::Any); + if (verbose > 3) { + qDebug() << "daemon address: " << daemonAddress.toString(); + } + } + daemonPort = cfg.serverPort; + if (daemonPort == 0) { + // maybe think about other fall back solution + daemonPort = MuonPi::Settings::gui.port; + } + if (!this->listen(daemonAddress, daemonPort)) { + qCritical() << tr("Unable to start the server: %1.\n").arg(this->errorString()); + } else { + if (verbose > 3) { + qInfo() << tr("\nThe server is running on\n\nIP: %1\nport: %2\n") + .arg(daemonAddress.toString()) + .arg(serverPort()); + } + } + flush(cout); + + // set up histograms + setupHistos(); + + // connect to the pigpio daemon interface for gpio control + connectToPigpiod(); + + // set up the rate buffer for all GPIO signals + rateBuffer.clear(); + connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); + +// connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) + connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if ( histoMap.find("gpioEventInterval")!=histoMap.end() + && ( GPIO_PINMAP[eventTrigger] == gpio ) ) + { + histoMap["gpioEventInterval"].fill( 1e-6 * ns.count() ); + } + } ); + + connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) +// connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if ( histoMap.find("gpioEventIntervalShort")!=histoMap.end() ) + { + if ( nsecs/1000 <= histoMap["gpioEventIntervalShort"].getMax() ) { + histoMap["gpioEventIntervalShort"].fill( 1e-3 * nsecs ); + } + } + } ); + + // establish ublox gnss module connection + connectToGps(); + + // configure the ublox module with preset ubx messages, if required + if (configGnss) { + configGps(); + } + pollAllUbxMsgRate(); + + // set up cyclic timer monitoring following operational parameters: + // temp, vadc, vbias, ibias + parameterMonitorTimer.setInterval(MuonPi::Config::Hardware::monitor_interval); + parameterMonitorTimer.setSingleShot(false); + connect(¶meterMonitorTimer, &QTimer::timeout, this, &Daemon::aquireMonitoringParameters); + parameterMonitorTimer.start(); + + logEngine.setHashLength(cfg.maxGeohashLength); +} + +Daemon::~Daemon() +{ + snHup.clear(); + snTerm.clear(); + snInt.clear(); + if (calib != nullptr) { + delete calib; + calib = nullptr; + } + pigHandler.clear(); + unsigned long timeout = 2000; + if (!mqttHandlerThread->wait(timeout)) { + qWarning() << "Timeout waiting for thread " + mqttHandlerThread->objectName(); + } + if (!fileHandlerThread->wait(timeout)) { + qWarning() << "Timeout waiting for thread " + fileHandlerThread->objectName(); + } + if (!pigThread->wait(timeout)) { + qWarning() << "Timeout waiting for thread " + pigThread->objectName(); + } + if (!gpsThread->wait(timeout)) { + qWarning() << "Timeout waiting for thread " + gpsThread->objectName(); + } + if (!tcpThread->wait(timeout)) { + qWarning() << "Timeout waiting for thread " + tcpThread->objectName(); + } + while ( !i2cDevice::getGlobalDeviceList().empty() ) { + if ( i2cDevice::getGlobalDeviceList().front() != nullptr ) delete i2cDevice::getGlobalDeviceList().front(); + } +} + +void Daemon::connectToPigpiod(){ +/* + const QVector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], + GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); +*/ + const std::vector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], + GPIO_PINMAP[TIMEPULSE] }); + pigHandler = new PigpiodHandler(gpio_pins); + //tdc7200 = new TDC7200(GPIO_PINMAP[TDC_INTB]); + pigThread = new QThread(); + pigThread->setObjectName("muondetector-daemon-pigpio"); + pigHandler->moveToThread(pigThread); + //tdc7200->moveToThread(pigThread); + connect(this, &Daemon::aboutToQuit, pigThread, &QThread::quit); + connect(pigThread, &QThread::finished, pigThread, &QThread::deleteLater); + + //pighandler <-> tdc +/* + connect(pigHandler, &PigpiodHandler::spiData, tdc7200, &TDC7200::onDataReceived); + connect(pigHandler, &PigpiodHandler::signal, tdc7200, &TDC7200::onDataAvailable); + connect(tdc7200, &TDC7200::readData, pigHandler, &PigpiodHandler::readSpi); + connect(tdc7200, &TDC7200::writeData, pigHandler, &PigpiodHandler::writeSpi); + + //tdc <-> thread & daemon + connect(tdc7200, &TDC7200::tdcEvent, this, [this](double usecs){ + if (histoMap.find("Time-to-Digital Time Diff")!=histoMap.end()) { + histoMap["Time-to-Digital Time Diff"].fill(usecs); + } + }); + connect(tdc7200, &TDC7200::statusUpdated, this, [this](bool isPresent) { + spiDevicePresent = isPresent; + sendSpiStats(); + }); + connect(pigThread, &QThread::started, tdc7200, &TDC7200::initialise); + connect(pigThread, &QThread::finished, tdc7200, &TDC7200::deleteLater); +*/ + //pigHandler <-> thread & daemon + connect(this, &Daemon::aboutToQuit, pigHandler, &PigpiodHandler::stop); + connect(pigThread, &QThread::finished, pigHandler, &PigpiodHandler::deleteLater); + connect(this, &Daemon::GpioSetOutput, pigHandler, &PigpiodHandler::setPinOutput); + connect(this, &Daemon::GpioSetInput, pigHandler, &PigpiodHandler::setPinInput); +// connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); +// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); + connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState ); + connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); + //connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::sendGpioPinEvent); +/* + connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin) { + if ( gpio_pin == GPIO_PINMAP[TIME_MEAS_OUT] ) { + onStatusLed2Event( 50 ); + } + } + ); +*/ + struct timespec ts_res; + clock_getres(CLOCK_REALTIME, &ts_res); + if (verbose > 3) { + qInfo() << "the timing resolution of the system clock is " << ts_res.tv_nsec << " ns"; + } + + timespec_get(&lastRateInterval, TIME_UTC); + startOfProgram = lastRateInterval; + + pigThread->start(); + rateBufferReminder.setInterval(rateBufferInterval); + rateBufferReminder.setSingleShot(false); + connect(&rateBufferReminder, &QTimer::timeout, this, &Daemon::onRateBufferReminder); + rateBufferReminder.start(); + emit GpioSetOutput(GPIO_PINMAP[UBIAS_EN]); + emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION == 1) ? (biasON ? 1 : 0) : (biasON ? 0 : 1)); + emit GpioSetOutput(GPIO_PINMAP[PREAMP_1]); + emit GpioSetOutput(GPIO_PINMAP[PREAMP_2]); + emit GpioSetOutput(GPIO_PINMAP[GAIN_HL]); + emit GpioSetState(GPIO_PINMAP[PREAMP_1], preampStatus[0]); + emit GpioSetState(GPIO_PINMAP[PREAMP_2], preampStatus[1]); + emit GpioSetState(GPIO_PINMAP[GAIN_HL], gainSwitch); + emit GpioSetOutput(GPIO_PINMAP[STATUS1]); + emit GpioSetOutput(GPIO_PINMAP[STATUS2]); + emit GpioSetState(GPIO_PINMAP[STATUS1], 0); + emit GpioSetState(GPIO_PINMAP[STATUS2], 0); + emit GpioSetPullUp(GPIO_PINMAP[ADC_READY]); + //emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], PigpiodHandler::EventEdge::RisingEdge); + auto it=GPIO_PINMAP.find(eventTrigger); + if (it != GPIO_PINMAP.end()) { +// pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); + emit GpioRegisterForCallback(GPIO_PINMAP[eventTrigger], PigpiodHandler::EventEdge::RisingEdge); + } +// connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); + + if (HW_VERSION > 1) { + //emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); + emit GpioRegisterForCallback(GPIO_PINMAP[PREAMP_FAULT], PigpiodHandler::EventEdge::FallingEdge); + emit GpioSetPullUp(GPIO_PINMAP[PREAMP_FAULT]); + //emit GpioSetInput(GPIO_PINMAP[TDC_INTB]); + emit GpioRegisterForCallback(GPIO_PINMAP[TDC_INTB], PigpiodHandler::EventEdge::FallingEdge); + //emit GpioSetInput(GPIO_PINMAP[TIME_MEAS_OUT]); + emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], PigpiodHandler::EventEdge::RisingEdge); + } + if (HW_VERSION >= 3) { + emit GpioSetOutput(GPIO_PINMAP[IN_POL1]); + emit GpioSetOutput(GPIO_PINMAP[IN_POL2]); + emit GpioSetState(GPIO_PINMAP[IN_POL1], polarity1); + emit GpioSetState(GPIO_PINMAP[IN_POL2], polarity2); + } +} + +void Daemon::connectToGps() +{ + // before connecting to gps we have to make sure all other programs are closed + // and serial echo is off + if (gpsdevname.isEmpty()) { + return; + } + QProcess prepareSerial; + QString command = "stty"; + QStringList args = { "-F", "/dev/ttyAMA0", "-echo", "-onlcr" }; + prepareSerial.start(command, args, QIODevice::ReadWrite); + prepareSerial.waitForFinished(); + + // here is where the magic threading happens look closely + qtGps = new QtSerialUblox(gpsdevname, gpsTimeout, baudrate, dumpRaw, verbose - 1, showout, showin); + gpsThread = new QThread(); + gpsThread->setObjectName("muondetector-daemon-gnss"); + qtGps->moveToThread(gpsThread); + // connect all signals about quitting + connect(this, &Daemon::aboutToQuit, gpsThread, &QThread::quit); + connect(this, &Daemon::aboutToQuit, qtGps, &QtSerialUblox::closeAll); + connect(gpsThread, &QThread::finished, gpsThread, &QThread::deleteLater); + connect(gpsThread, &QThread::finished, qtGps, &QtSerialUblox::deleteLater); + // connect all signals not coming from Daemon to gps + connect(qtGps, &QtSerialUblox::toConsole, this, &Daemon::gpsToConsole); + connect(gpsThread, &QThread::started, qtGps, &QtSerialUblox::makeConnection); + connect(qtGps, &QtSerialUblox::gpsRestart, this, &Daemon::connectToGps); + // connect all command signals for ublox module here + connect(this, &Daemon::UBXSetCfgPrt, qtGps, &QtSerialUblox::UBXSetCfgPrt); + connect(this, &Daemon::UBXSetCfgMsgRate, qtGps, &QtSerialUblox::UBXSetCfgMsgRate); + connect(this, &Daemon::UBXSetCfgRate, qtGps, &QtSerialUblox::UBXSetCfgRate); + connect(this, &Daemon::sendPollUbxMsgRate, qtGps, &QtSerialUblox::pollMsgRate); + connect(this, &Daemon::sendPollUbxMsg, qtGps, &QtSerialUblox::pollMsg); + connect(this, &Daemon::sendUbxMsg, qtGps, &QtSerialUblox::enqueueMsg); + connect(qtGps, &QtSerialUblox::UBXReceivedAckNak, this, &Daemon::UBXReceivedAckNak); + connect(qtGps, &QtSerialUblox::UBXreceivedMsgRateCfg, this, &Daemon::UBXReceivedMsgRateCfg); + connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedGeodeticPos, this, &Daemon::onGpsPropertyUpdatedGeodeticPos); + connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedGnss, this, &Daemon::onGpsPropertyUpdatedGnss); + connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedUint32, this, &Daemon::gpsPropertyUpdatedUint32); + connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedInt32, this, &Daemon::gpsPropertyUpdatedInt32); + connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedUint8, this, &Daemon::gpsPropertyUpdatedUint8); + connect(qtGps, &QtSerialUblox::gpsMonHW, this, &Daemon::onGpsMonHWUpdated); + connect(qtGps, &QtSerialUblox::gpsMonHW2, this, &Daemon::onGpsMonHW2Updated); + connect(qtGps, &QtSerialUblox::gpsVersion, this, &Daemon::UBXReceivedVersion); + connect(qtGps, &QtSerialUblox::UBXCfgError, this, &Daemon::toConsole); + connect(qtGps, &QtSerialUblox::UBXReceivedGnssConfig, this, &Daemon::onUBXReceivedGnssConfig); + connect(qtGps, &QtSerialUblox::UBXReceivedTP5, this, &Daemon::onUBXReceivedTP5); + connect(qtGps, &QtSerialUblox::UBXReceivedTxBuf, this, &Daemon::onUBXReceivedTxBuf); + connect(qtGps, &QtSerialUblox::UBXReceivedRxBuf, this, &Daemon::onUBXReceivedRxBuf); + connect(this, &Daemon::UBXSetDynModel, qtGps, &QtSerialUblox::setDynamicModel); + connect(this, &Daemon::resetUbxDevice, qtGps, &QtSerialUblox::UBXReset); + connect(this, &Daemon::setGnssConfig, qtGps, &QtSerialUblox::onSetGnssConfig); + connect(this, &Daemon::UBXSetCfgTP5, qtGps, &QtSerialUblox::UBXSetCfgTP5); + connect(this, &Daemon::UBXSetMinMaxSVs, qtGps, &QtSerialUblox::UBXSetMinMaxSVs); + connect(this, &Daemon::UBXSetMinCNO, qtGps, &QtSerialUblox::UBXSetMinCNO); + connect(this, &Daemon::UBXSetAopCfg, qtGps, &QtSerialUblox::UBXSetAopCfg); + connect(this, &Daemon::UBXSaveCfg, qtGps, &QtSerialUblox::UBXSaveCfg); + connect(qtGps, &QtSerialUblox::UBXReceivedTimeTM2, this, &Daemon::onUBXReceivedTimeTM2); + + connect(qtGps, &QtSerialUblox::UBXReceivedDops, this, [this](const UbxDopStruct& dops) { + currentDOP = dops; + emit logParameter(LogParameter("positionDOP", QString::number(dops.pDOP / 100.), LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("timeDOP", QString::number(dops.tDOP / 100.), LogParameter::LOG_AVERAGE)); + }); + + // connect fileHandler related stuff + if (fileHandler != nullptr) { + //connect(qtGps, &QtSerialUblox::timTM2, fileHandler, &FileHandler::writeToDataFile); + if (config.storeLocal) { + connect(this, &Daemon::eventMessage, fileHandler, &FileHandler::writeToDataFile); + } + //connect(qtGps, &QtSerialUblox::timTM2, mqttHandler, &MuonPi::MqttHandler::sendData); + connect(this, &Daemon::eventMessage, mqttHandler, &MuonPi::MqttHandler::sendData); + } + // after thread start there will be a signal emitted which starts the qtGps makeConnection function + gpsThread->start(); +} + +void Daemon::incomingConnection(qintptr socketDescriptor) +{ + if (verbose > 4) { + qDebug() << "incoming connection"; + } + tcpThread = new QThread(); + tcpThread->setObjectName("muondetector-daemon-tcp"); + tcpConnection = new TcpConnection(socketDescriptor, verbose); + tcpConnection->moveToThread(tcpThread); + // connect all signals about quitting + connect(this, &Daemon::aboutToQuit, tcpConnection, &TcpConnection::closeThisConnection); + connect(this, &Daemon::closeConnection, tcpConnection, &TcpConnection::closeConnection); + connect(tcpConnection, &TcpConnection::finished, tcpThread, &QThread::quit); + connect(tcpThread, &QThread::finished, tcpThread, &QThread::deleteLater); + connect(tcpThread, &QThread::finished, tcpConnection, &TcpConnection::deleteLater); + // connect all other signals + connect(tcpThread, &QThread::started, tcpConnection, &TcpConnection::receiveConnection); + connect(this, &Daemon::sendTcpMessage, tcpConnection, &TcpConnection::sendTcpMessage); + connect(tcpConnection, &TcpConnection::receivedTcpMessage, this, &Daemon::receivedTcpMessage); + connect(tcpConnection, &TcpConnection::toConsole, this, &Daemon::toConsole); + connect(tcpConnection, &TcpConnection::madeConnection, this, &Daemon::onMadeConnection); + connect(tcpConnection, &TcpConnection::connectionTimeout, this, &Daemon::onStoppedConnection); + tcpThread->start(); + + pollAllUbxMsgRate(); + emit requestMqttConnectionStatus(); +} + +// Histogram functions +void Daemon::setupHistos() +{ + Histogram hist = Histogram("geoHeight", 200, 0., 199.); + hist.setUnit("m"); + hist.setAutoscale(); + histoMap["geoHeight"] = hist; + hist = Histogram("geoLongitude", 200, 0., 0.003); + hist.setUnit("deg"); + hist.setAutoscale(); + histoMap["geoLongitude"] = hist; + hist = Histogram("geoLatitude", 200, 0., 0.003); + hist.setUnit("deg"); + hist.setAutoscale(); + histoMap["geoLatitude"] = hist; + hist = Histogram("weightedGeoHeight", 200, 0., 199.); + hist.setUnit("m"); + hist.setAutoscale(); + histoMap["weightedGeoHeight"] = hist; + hist = Histogram("pulseHeight", 500, 0., 3.8); + hist.setUnit("V"); + hist.setAutoscale( false ); + histoMap["pulseHeight"] = hist; + hist = Histogram("adcSampleTime", 500, 0., 10.0); + hist.setUnit("ms"); + hist.setAutoscale(); + histoMap["adcSampleTime"] = hist; + hist = Histogram("UbxEventLength", 100, 50., 149.); + hist.setUnit("ns"); + hist.setAutoscale(); + histoMap["UbxEventLength"] = hist; + hist = Histogram("gpioEventInterval", 400, 0., 2000.); + hist.setUnit("ms"); + hist.setAutoscale(); + histoMap["gpioEventInterval"] = hist; + hist = Histogram("gpioEventIntervalShort", 50, 0., 49.); + hist.setUnit("us"); + hist.setAutoscale( false ); + histoMap["gpioEventIntervalShort"] = hist; + hist = Histogram("UbxEventInterval", 200, 0., 2000.); + hist.setUnit("ms"); + hist.setAutoscale(); + histoMap["UbxEventInterval"] = hist; + hist = Histogram("TPTimeDiff", 200, -999., 1000.); + hist.setUnit("us"); + hist.setAutoscale(); + histoMap["TPTimeDiff"] = hist; + hist = Histogram("Time-to-Digital Time Diff", 400, 0., 1e6); + hist.setUnit("ns"); + hist.setAutoscale(); + histoMap["Time-to-Digital Time Diff"] = hist; + hist = Histogram("Bias Voltage", 200, 0., 1.); + hist.setUnit("V"); + hist.setAutoscale(); + histoMap["Bias Voltage"] = hist; + hist = Histogram("Bias Current", 200, 0., 50.); + hist.setUnit("uA"); + hist.setAutoscale(); + histoMap["Bias Current"] = hist; +} + +void Daemon::clearHisto(const QString& histoName) +{ + if (histoMap.find(histoName) != histoMap.end()) { + histoMap[histoName].clear(); + emit sendHistogram(histoMap[histoName]); + } + return; +} + +// ALL FUNCTIONS ABOUT TCPMESSAGE SENDING AND RECEIVING +void Daemon::receivedTcpMessage(TcpMessage tcpMessage) +{ + TCP_MSG_KEY msgID = static_cast(tcpMessage.getMsgID()); + if (msgID == TCP_MSG_KEY::MSG_THRESHOLD) { + uint8_t channel; + float threshold; + *(tcpMessage.dStream) >> channel >> threshold; + if (threshold < 0.001) { + if (verbose > 2) + qWarning() << "setting DAC " << channel << " to 0!"; + } else + setDacThresh(channel, threshold); + sendDacThresh(DAC_TH1); + sendDacThresh(DAC_TH2); + return; + } + if (msgID == TCP_MSG_KEY::MSG_THRESHOLD_REQUEST) { + sendDacThresh(DAC_TH1); + sendDacThresh(DAC_TH2); + return; + } + if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE) { + float voltage; + *(tcpMessage.dStream) >> voltage; + setBiasVoltage(voltage); + if (histoMap.find("pulseHeight") != histoMap.end()) + histoMap["pulseHeight"].clear(); + sendBiasVoltage(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST) { + sendBiasVoltage(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_BIAS_SWITCH) { + bool status; + *(tcpMessage.dStream) >> status; + setBiasStatus(status); + sendBiasStatus(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST) { + sendBiasStatus(); + } + if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH) { + quint8 channel; + bool status; + *(tcpMessage.dStream) >> channel >> status; + if (channel == 0) { + preampStatus[0] = status; + emit GpioSetState(GPIO_PINMAP[PREAMP_1], status); + emit logParameter(LogParameter("preampSwitch1", QString::number((int)preampStatus[0]), LogParameter::LOG_EVERY)); + } else if (channel == 1) { + preampStatus[1] = status; + emit GpioSetState(GPIO_PINMAP[PREAMP_2], status); + emit logParameter(LogParameter("preampSwitch2", QString::number((int)preampStatus[1]), LogParameter::LOG_EVERY)); + } + sendPreampStatus(0); + sendPreampStatus(1); + return; + } + if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST) { + sendPreampStatus(0); + sendPreampStatus(1); + } + if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH) { + bool pol1, pol2; + *(tcpMessage.dStream) >> pol1 >> pol2; + if (HW_VERSION >= 3 && pol1 != polarity1) { + polarity1 = pol1; + emit GpioSetState(GPIO_PINMAP[IN_POL1], polarity1); + emit logParameter(LogParameter("polaritySwitch1", QString::number((int)polarity1), LogParameter::LOG_EVERY)); + } + if (HW_VERSION >= 3 && pol2 != polarity2) { + polarity2 = pol2; + emit GpioSetState(GPIO_PINMAP[IN_POL2], polarity2); + emit logParameter(LogParameter("polaritySwitch2", QString::number((int)polarity2), LogParameter::LOG_EVERY)); + } + sendPolarityStatus(); + } + if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH_REQUEST) { + sendPolarityStatus(); + } + if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH) { + bool status; + *(tcpMessage.dStream) >> status; + gainSwitch = status; + emit GpioSetState(GPIO_PINMAP[GAIN_HL], status); + if (histoMap.find("pulseHeight") != histoMap.end()) + histoMap["pulseHeight"].clear(); + emit logParameter(LogParameter("gainSwitch", QString::number((int)gainSwitch), LogParameter::LOG_EVERY)); + sendGainSwitchStatus(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH_REQUEST) { + sendGainSwitchStatus(); + } + if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE_REQUEST) { + sendUbxMsgRates(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_UBX_RESET) { + uint32_t resetFlags = QtSerialUblox::RESET_WARM | QtSerialUblox::RESET_SW; + emit resetUbxDevice(resetFlags); + pollAllUbxMsgRate(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_UBX_CONFIG_DEFAULT) { + configGps(); + pollAllUbxMsgRate(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE) { + QMap ubxMsgRates; + *(tcpMessage.dStream) >> ubxMsgRates; + setUbxMsgRates(ubxMsgRates); + } + if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH) { + quint8 portMask; + *(tcpMessage.dStream) >> portMask; + setPcaChannel((uint8_t)portMask); + sendPcaChannel(); + if (histoMap.find("UbxEventLength") != histoMap.end()) + histoMap["UbxEventLength"].clear(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH_REQUEST) { + sendPcaChannel(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER) { + unsigned int signal; + *(tcpMessage.dStream) >> signal; + setEventTriggerSelection((GPIO_SIGNAL)signal); + usleep(1000); + sendEventTriggerSelection(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER_REQUEST) { + sendEventTriggerSelection(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE_REQUEST) { + quint8 whichRate; + quint16 number; + *(tcpMessage.dStream) >> number >> whichRate; + sendGpioRates(number, whichRate); + } + if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE_RESET) { + clearRates(); + return; + } + if (msgID == TCP_MSG_KEY::MSG_DAC_REQUEST) { + quint8 channel; + *(tcpMessage.dStream) >> channel; + MCP4728::DacChannel channelData; + if ( !dac_p || !dac_p->probeDevicePresence() ) + return; + dynamic_cast( dac_p.get() )->readChannel(channel, channelData); + float voltage = MCP4728::code2voltage(channelData); + sendDacReadbackValue(channel, voltage); + } + if (msgID == TCP_MSG_KEY::MSG_ADC_SAMPLE_REQUEST) { + quint8 channel; + *(tcpMessage.dStream) >> channel; + sampleAdcEvent(channel); + } + if (msgID == TCP_MSG_KEY::MSG_TEMPERATURE_REQUEST) { + getTemperature(); + } + if (msgID == TCP_MSG_KEY::MSG_I2C_STATS_REQUEST) { + sendI2cStats(); + } + if (msgID == TCP_MSG_KEY::MSG_I2C_SCAN_BUS) { + scanI2cBus(); + sendI2cStats(); + } + if (msgID == TCP_MSG_KEY::MSG_SPI_STATS_REQUEST) { + sendSpiStats(); + } + if (msgID == TCP_MSG_KEY::MSG_CALIB_REQUEST) { + sendCalib(); + } + if (msgID == TCP_MSG_KEY::MSG_CALIB_SAVE) { + if (calib != nullptr) + calib->writeToEeprom(); + sendCalib(); + } + if (msgID == TCP_MSG_KEY::MSG_CALIB_SET) { + std::vector calibs; + quint8 nrEntries = 0; + *(tcpMessage.dStream) >> nrEntries; + for (int i = 0; i < nrEntries; i++) { + CalibStruct item; + *(tcpMessage.dStream) >> item; + calibs.push_back(item); + } + receivedCalibItems(calibs); + } + if (msgID == TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG) { + std::vector configs; + int nrEntries = 0; + *(tcpMessage.dStream) >> nrEntries; + for (int i = 0; i < nrEntries; i++) { + GnssConfigStruct config; + *(tcpMessage.dStream) >> config.gnssId >> config.resTrkCh >> config.maxTrkCh >> config.flags; + configs.push_back(config); + } + emit setGnssConfig(configs); + usleep(150000L); + emit sendPollUbxMsg(UBX_CFG_GNSS); + } + if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_TP5) { + UbxTimePulseStruct tp; + *(tcpMessage.dStream) >> tp; + emit UBXSetCfgTP5(tp); + emit sendPollUbxMsg(UBX_CFG_TP5); + return; + } + if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_SAVE) { + emit UBXSaveCfg(); + emit sendPollUbxMsg(UBX_CFG_TP5); + emit sendPollUbxMsg(UBX_CFG_GNSS); + return; + } + if (msgID == TCP_MSG_KEY::MSG_QUIT_CONNECTION) { + QString closeAddress; + *(tcpMessage.dStream) >> closeAddress; + emit closeConnection(closeAddress); + } + if (msgID == TCP_MSG_KEY::MSG_DAC_EEPROM_SET) { + saveDacValuesToEeprom(); + } + if (msgID == TCP_MSG_KEY::MSG_HISTOGRAM_CLEAR) { + QString histoName; + *(tcpMessage.dStream) >> histoName; + clearHisto(histoName); + } + if (msgID == TCP_MSG_KEY::MSG_ADC_MODE_REQUEST) { + TcpMessage answer(TCP_MSG_KEY::MSG_ADC_MODE); + *(answer.dStream) << static_cast(adcSamplingMode); + emit sendTcpMessage(answer); + } + if (msgID == TCP_MSG_KEY::MSG_ADC_MODE) { + quint8 mode { 0 }; + *(tcpMessage.dStream) >> mode; + setAdcSamplingMode( static_cast(mode) ); + TcpMessage answer(TCP_MSG_KEY::MSG_ADC_MODE); + *(answer.dStream) << static_cast(adcSamplingMode); + emit sendTcpMessage(answer); + } + if (msgID == TCP_MSG_KEY::MSG_LOG_INFO) { + sendLogInfo(); + } + if (msgID == TCP_MSG_KEY::MSG_GPIO_INHIBIT) { + bool inhibit = true; + *(tcpMessage.dStream) >> inhibit; + if (pigHandler != nullptr) + pigHandler->setInhibited(inhibit); + } +} + +void Daemon::setAdcSamplingMode(ADC_SAMPLING_MODE mode) +{ + adcSamplingMode = mode; + if (mode == ADC_SAMPLING_MODE::TRACE) + samplingTimer.start(); + else + samplingTimer.stop(); +} + +void Daemon::scanI2cBus() +{ + for (uint8_t addr = 0x04; addr <= 0x78; addr++) { + bool alreadyThere = false; + for (uint8_t i = 0; i < i2cDevice::getGlobalDeviceList().size(); i++) { + if (addr == i2cDevice::getGlobalDeviceList()[i]->getAddress()) { + alreadyThere = true; + break; + } + } + if (alreadyThere) { + continue; + } + + i2cDevice* new_dev { instantiateI2cDevice( addr ) }; + if ( new_dev && !new_dev->devicePresent() ) delete new_dev; + } +} + +void Daemon::sendLogInfo() +{ + LogInfoStruct lis; + lis.logFileName = fileHandler->logFileInfo().absoluteFilePath(); + lis.dataFileName = fileHandler->dataFileInfo().absoluteFilePath(); + lis.logFileSize = fileHandler->logFileInfo().size(); + lis.dataFileSize = fileHandler->dataFileInfo().size(); + lis.status = (quint8)(fileHandler->dataFileInfo().exists() && fileHandler->logFileInfo().exists()); + lis.logAge = (qint32)fileHandler->currentLogAge(); + TcpMessage answer(TCP_MSG_KEY::MSG_LOG_INFO); + *(answer.dStream) << lis; + emit sendTcpMessage(answer); +} + +void Daemon::sendI2cStats() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_I2C_STATS); + quint8 nrDevices = i2cDevice::getGlobalDeviceList().size(); + quint32 bytesRead = i2cDevice::getGlobalNrBytesRead(); + quint32 bytesWritten = i2cDevice::getGlobalNrBytesWritten(); + *(tcpMessage.dStream) << nrDevices << bytesRead << bytesWritten; + + for (uint8_t i = 0; i < i2cDevice::getGlobalDeviceList().size(); i++) { + uint8_t addr = i2cDevice::getGlobalDeviceList()[i]->getAddress(); + QString title = QString::fromStdString(i2cDevice::getGlobalDeviceList()[i]->getTitle()); + i2cDevice::getGlobalDeviceList()[i]->devicePresent(); + uint8_t status = i2cDevice::getGlobalDeviceList()[i]->getStatus(); + *(tcpMessage.dStream) << addr << title << status; + } + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendSpiStats() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_SPI_STATS); + *(tcpMessage.dStream) << spiDevicePresent; + emit sendTcpMessage(spiDevicePresent); +} + +void Daemon::sendCalib() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_CALIB_SET); + bool valid = calib->isValid(); + bool eepValid = calib->isEepromValid(); + quint16 nrPars = calib->getCalibList().size(); + quint64 id = calib->getSerialID(); + *(tcpMessage.dStream) << valid << eepValid << id << nrPars; + for (int i = 0; i < nrPars; i++) { + *(tcpMessage.dStream) << calib->getCalibItem(i); + } + emit sendTcpMessage(tcpMessage); +} + +void Daemon::receivedCalibItems(const std::vector& newCalibs) +{ + for (unsigned int i = 0; i < newCalibs.size(); i++) { + calib->setCalibItem(newCalibs[i].name, newCalibs[i]); + } +} + +void Daemon::onGpsPropertyUpdatedGeodeticPos(const GeodeticPos& pos) +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GEO_POS); + (*tcpMessage.dStream) << pos.iTOW << pos.lon << pos.lat + << pos.height << pos.hMSL << pos.hAcc + << pos.vAcc; + emit sendTcpMessage(tcpMessage); + + QString geohash = GeoHash::hashFromCoordinates(1e-7 * pos.lon, 1e-7 * pos.lat, 10); + + emit logParameter(LogParameter("geoLongitude", QString::number(1e-7 * pos.lon, 'f', 7) + " deg", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("geoLatitude", QString::number(1e-7 * pos.lat, 'f', 7) + " deg", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("geoHash", geohash + " ", LogParameter::LOG_LATEST)); + emit logParameter(LogParameter("geoHeightMSL", QString::number(1e-3 * pos.hMSL, 'f', 2) + " m", LogParameter::LOG_AVERAGE)); + if (histoMap.find("geoHeight") != histoMap.end()) + emit logParameter(LogParameter("meanGeoHeightMSL", QString::number(histoMap["geoHeight"].getMean(), 'f', 2) + " m", LogParameter::LOG_LATEST)); + emit logParameter(LogParameter("geoHorAccuracy", QString::number(1e-3 * pos.hAcc, 'f', 2) + " m", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("geoVertAccuracy", QString::number(1e-3 * pos.vAcc, 'f', 2) + " m", LogParameter::LOG_AVERAGE)); + + if (1e-3 * pos.vAcc < 100.) { + QString name = "geoHeight"; + if (histoMap.find(name) != histoMap.end()) { + histoMap[name].fill(1e-3 * pos.hMSL); + if (currentDOP.vDOP > 0) { + name = "weightedGeoHeight"; + double heightWeight = 100. / currentDOP.vDOP; + histoMap[name].fill(1e-3 * pos.hMSL, heightWeight); + } + } + } + if (1e-3 * pos.hAcc < 100.) { + QString name = "geoLongitude"; + histoMap[name].fill(1e-7 * pos.lon); + name = "geoLatitude"; + histoMap[name].fill(1e-7 * pos.lat); + } +} + +void Daemon::sendHistogram(const Histogram& hist) +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_HISTOGRAM); + (*tcpMessage.dStream) << hist; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendUbxMsgRates() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MSG_RATE); + *(tcpMessage.dStream) << msgRateCfgs; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendDacThresh(uint8_t channel) +{ + if (channel > 1) { + return; + } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_THRESHOLD); + *(tcpMessage.dStream) << (quint8)channel << dacThresh[(int)channel]; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) +{ + if (channel > 3) { + return; + } + + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_DAC_READBACK); + *(tcpMessage.dStream) << (quint8)channel << voltage; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { + // reverse lookup of gpio function from given pin (first occurence) + auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) + { return item.second == gpio; } + ); + if (result != GPIO_PINMAP.end()) { + if ( result->first == TIMEPULSE) { + auto usecs = std::chrono::duration_cast(event_time.time_since_epoch()).count(); + usecs = usecs % 1000000LL; + if ( usecs > 500000L ) { + usecs -= 1000000LL; + } + if (histoMap.find("TPTimeDiff") != histoMap.end()) { + histoMap["TPTimeDiff"].fill((double)usecs); + } + if (verbose>2) qDebug()<<"TP time diff:"<first == EVT_XOR || result->first == EVT_AND ) { + rateCounterIntervalActualisation(); + if ( result->first == EVT_XOR ) { + xorCounts.back()++; + } else if ( result->first == EVT_AND ) { + andCounts.back()++; + } + } + if ( result->first == eventTrigger ) { + /* + auto nsecs = rateBuffer.lastInterval(gpio).count(); + if ( nsecs > 0 ) { + emit eventInterval( rateBuffer.lastInterval(gpio).count() ); + } + */ + emit sampleAdc0Event(); + } + + if ( result->first == TIME_MEAS_OUT ) { + auto start_gpio = GPIO_PINMAP.find(eventTrigger); + if ( start_gpio != GPIO_PINMAP.end() ) { + long long nsecs { 0 }; + if ( result->first != eventTrigger ) { + nsecs = rateBuffer.lastInterval( gpio, start_gpio->second ).count(); + if ( nsecs < 0 ) nsecs = rateBuffer.lastInterval( start_gpio->second, gpio ).count(); + } else { + nsecs = rateBuffer.lastInterval( gpio ).count(); + } + if ( nsecs > 0 ) { + //emit eventInterval( nsecs ); + if ( nsecs < 100000L ) { + emit eventInterval( nsecs ); + std::cout<<"trigger interval="<& item) + { return item.second==gpio; } + ); + if (result != GPIO_PINMAP.end()) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); + *(tcpMessage.dStream) << (GPIO_SIGNAL)result->first; + emit sendTcpMessage(tcpMessage); + } +} + +void Daemon::sendBiasVoltage() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_VOLTAGE); + *(tcpMessage.dStream) << biasVoltage; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendBiasStatus() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_SWITCH); + *(tcpMessage.dStream) << biasON; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendGainSwitchStatus() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GAIN_SWITCH); + *(tcpMessage.dStream) << gainSwitch; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendPreampStatus(uint8_t channel) +{ + if (channel > 1) { + return; + } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PREAMP_SWITCH); + *(tcpMessage.dStream) << (quint8)channel << preampStatus[channel]; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendPolarityStatus() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_POLARITY_SWITCH); + *(tcpMessage.dStream) << polarity1 << polarity2; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendPcaChannel() +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PCA_SWITCH); + *(tcpMessage.dStream) << (quint8)pcaPortMask; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendEventTriggerSelection() +{ + if (pigHandler == nullptr) + return; + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); + *(tcpMessage.dStream) << eventTrigger; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::sendMqttStatus(bool connected) +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_MQTT_STATUS); + *(tcpMessage.dStream) << connected; + if (connected != mqttConnectionStatus) { + if (connected) { + qInfo() << "MQTT (re)connected"; + emit GpioSetState(GPIO_PINMAP[STATUS1], 1); + } else { + qWarning() << "MQTT connection lost"; + emit GpioSetState(GPIO_PINMAP[STATUS1], 0); + } + } + mqttConnectionStatus = connected; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::rateCounterIntervalActualisation() +{ + if (xorCounts.isEmpty()) { + xorCounts.push_back(0); + } + if (andCounts.isEmpty()) { + andCounts.push_back(0); + } + timespec now; + timespec_get(&now, TIME_UTC); + int64_t diff = msecdiff(now, lastRateInterval); + while (diff > 1000) { + xorCounts.push_back(0); + andCounts.push_back(0); + while ((quint32)xorCounts.size() > (rateBufferTime)) { + xorCounts.pop_front(); + } + while ((quint32)andCounts.size() > (rateBufferTime)) { + andCounts.pop_front(); + } + lastRateInterval.tv_sec += 1; + diff = msecdiff(now, lastRateInterval); + } +} + +void Daemon::clearRates() +{ + xorCounts.clear(); + xorCounts.push_back(0); + andCounts.clear(); + andCounts.push_back(0); + xorRatePoints.clear(); + andRatePoints.clear(); +} + +qreal Daemon::getRateFromCounts(quint8 which_rate) +{ + rateCounterIntervalActualisation(); + QList* counts; + if (which_rate == XOR_RATE) { + counts = &xorCounts; + } else if (which_rate == AND_RATE) { + counts = &andCounts; + } else { + return -1.0; + } + quint64 sum = 0; + for (auto count : *counts) { + sum += count; + } + timespec now; + timespec_get(&now, TIME_UTC); + qreal timeInterval = ((qreal)(1000 * (counts->size() - 1))) + (qreal)msecdiff(now, lastRateInterval); // in ms + qreal rate = sum / timeInterval * 1000; + return (rate); +} + +void Daemon::onRateBufferReminder() +{ + qreal secsSinceStart = 0.001 * (qreal)msecdiff(lastRateInterval, startOfProgram); + qreal xorRate = getRateFromCounts(XOR_RATE); + qreal andRate = getRateFromCounts(AND_RATE); + QPointF xorPoint(secsSinceStart, xorRate); + QPointF andPoint(secsSinceStart, andRate); + xorRatePoints.append(xorPoint); + andRatePoints.append(andPoint); + emit logParameter(LogParameter("rateXOR", QString::number(xorRate) + " Hz", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("rateAND", QString::number(andRate) + " Hz", LogParameter::LOG_AVERAGE)); + while ((quint32)xorRatePoints.size() > rateMaxShowInterval / rateBufferInterval) { + xorRatePoints.pop_front(); + } + while ((quint32)andRatePoints.size() > rateMaxShowInterval / rateBufferInterval) { + andRatePoints.pop_front(); + } +} + +void Daemon::sendGpioRates(int number, quint8 whichRate) +{ + if (pigHandler == nullptr) { + return; + } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_RATE); + QVector* ratePoints; + if (whichRate == XOR_RATE) { + ratePoints = &xorRatePoints; + } else if (whichRate == AND_RATE) { + ratePoints = &andRatePoints; + } else { + return; + } + QVector someRates; + if (number >= ratePoints->size() || number == 0) { + number = ratePoints->size() - 1; + } + if (!ratePoints->isEmpty()) { + for (int i = 0; i < number; i++) { + someRates.push_front(ratePoints->at(ratePoints->size() - 1 - i)); + } + } + *(tcpMessage.dStream) << whichRate << someRates; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::onAdcSampleReady(ADS1115::Sample sample) { + const uint8_t channel = sample.channel; + float voltage = sample.voltage; + if ( channel != 0 ) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_SAMPLE); + *(tcpMessage.dStream) << (quint8)channel << voltage; + emit sendTcpMessage(tcpMessage); + } else { + if (adcSamplingMode == ADC_SAMPLING_MODE::TRACE ) { + adcSamplesBuffer.push_back(voltage); + if (adcSamplesBuffer.size() > MuonPi::Config::Hardware::ADC::buffer_size) + adcSamplesBuffer.pop_front(); + if ( currentAdcSampleIndex == 0 ) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_SAMPLE); + *(tcpMessage.dStream) << (quint8)channel << voltage; + emit sendTcpMessage(tcpMessage); + histoMap["pulseHeight"].fill(voltage); + } + if ( currentAdcSampleIndex >= 0 ) { + currentAdcSampleIndex++; + if (currentAdcSampleIndex >= (MuonPi::Config::Hardware::ADC::buffer_size - MuonPi::Config::Hardware::ADC::pretrigger)) + { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_TRACE); + *(tcpMessage.dStream) << (quint16)adcSamplesBuffer.size(); + for (int i = 0; i < adcSamplesBuffer.size(); i++) { + *(tcpMessage.dStream) << adcSamplesBuffer[i]; + } + emit sendTcpMessage(tcpMessage); + currentAdcSampleIndex = -1; + } + } + } else if ( adcSamplingMode == ADC_SAMPLING_MODE::PEAK ) { + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_SAMPLE); + *(tcpMessage.dStream) << (quint8)channel << voltage; + emit sendTcpMessage(tcpMessage); + histoMap["pulseHeight"].fill(voltage); + currentAdcSampleIndex = 0; + } + } + if ( adc_p ) { + emit logParameter(LogParameter("adcSamplingTime", QString::number(adc_p->getLastConvTime()) + " ms", LogParameter::LOG_AVERAGE)); + histoMap["adcSampleTime"].fill(adc_p->getLastConvTime()); + } +} + +void Daemon::sampleAdcEvent(uint8_t channel) +{ + if ( adc_p == nullptr || adcSamplingMode == ADC_SAMPLING_MODE::DISABLED) { + return; + } + if ( std::dynamic_pointer_cast(adc_p)->getStatus() & i2cDevice::MODE_UNREACHABLE ) { + return; + } + //adc->setActiveChannel( channel ); + adc_p->triggerConversion( channel ); +} + +void Daemon::sampleAdc0Event() +{ + sampleAdcEvent(0); + currentAdcSampleIndex = 0; +} + +void Daemon::sampleAdc0TraceEvent() +{ + sampleAdcEvent(0); +} + + +void Daemon::getTemperature() +{ + if ( !temp_sensor_p ) { + return; + } + if ( dynamic_cast(temp_sensor_p.get())->getStatus() & i2cDevice::MODE_UNREACHABLE ) { + return; + } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_TEMPERATURE); + if ( temp_sensor_p->getName() == "MIC184" && dynamic_cast(temp_sensor_p.get())->getAddress() < 0x4c ) { + // the attached temp sensor has a remote zone + if ( dynamic_cast(temp_sensor_p.get())->isExternal() ) return; + } + float value = temp_sensor_p->getTemperature(); + *(tcpMessage.dStream) << value; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) +{ + if (pigHandler == nullptr) + return; + auto it = GPIO_PINMAP.find(signal); + if (it == GPIO_PINMAP.end()) + return; + + if (verbose > 0) { + qInfo() << "changed event selection to signal" << GPIO_SIGNAL_MAP[signal].name; + } + emit GpioRegisterForCallback( it->second, PigpiodHandler::EventEdge::RisingEdge ); + eventTrigger = signal; + emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); +} + +// ALL FUNCTIONS ABOUT SETTINGS FOR THE I2C-DEVICES (DAC, ADC, PCA...) +void Daemon::setPcaChannel(uint8_t channel) +{ + if (!io_extender_p || !io_extender_p->probeDevicePresence()) { + return; + } + if (channel > ((HW_VERSION == 1) ? 3 : 7)) { + qWarning() << "invalid PCA channel selection: ch" << (int)channel << "...ignoring"; + return; + } + if (verbose > 0) { + qInfo() << "changed pcaPortMask to " << channel; + } + pcaPortMask = channel; + io_extender_p->setOutputState(channel); + emit logParameter(LogParameter("ubxInputSwitch", "0x" + QString::number(pcaPortMask, 16), LogParameter::LOG_EVERY)); +} + +void Daemon::setBiasVoltage(float voltage) +{ + biasVoltage = voltage; + if (verbose > 0) { + qInfo() << "change biasVoltage to " << voltage; + } + if ( dac_p && dac_p->probeDevicePresence() ) { + dac_p->setVoltage(DAC_BIAS, voltage); + emit logParameter(LogParameter("biasDAC", QString::number(voltage) + " V", LogParameter::LOG_EVERY)); + } + clearRates(); +} + +void Daemon::setBiasStatus(bool status) +{ + biasON = status; + if (verbose > 0) { + qInfo() << "change biasStatus to " << status; + } + + if (status) { + emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION == 1) ? 1 : 0); + } else { + emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION == 1) ? 0 : 1); + } + emit logParameter(LogParameter("biasSwitch", QString::number(status), LogParameter::LOG_EVERY)); + clearRates(); +} + +void Daemon::setDacThresh(uint8_t channel, float threshold) +{ + if (threshold < 0 || channel > 3) { + return; + } + if (channel == 2 || channel == 3) { + if ( dac_p ) { + dac_p->setVoltage(channel, threshold); + } + return; + } + if (threshold > 4.095) { + threshold = 4.095; + } + if (verbose > 0) { + qInfo() << "change dacThresh " << channel << " to " << threshold; + } + dacThresh[channel] = threshold; + clearRates(); + if ( dac_p && dac_p->setVoltage(channel, threshold) ) { + emit logParameter(LogParameter("thresh" + QString::number(channel + 1), QString::number(dacThresh[channel]) + " V", LogParameter::LOG_EVERY)); + } +} + +void Daemon::saveDacValuesToEeprom() +{ + if ( !dac_p || !dac_p->probeDevicePresence() ) return; + bool ok = dac_p->storeSettings(); + if ( !ok ) std::cerr << "error writing DAC eeprom" << std::endl; +} + +bool Daemon::readEeprom() +{ + if ( !eep_p || !eep_p->probeDevicePresence() ) { + return false; + } + uint16_t n = 256; + uint8_t buf[256]; + for (int i = 0; i < n; i++) + buf[i] = 0; + bool retval = ( eep_p->readBytes(0, n, buf) == n); + cout << "*** EEPROM content ***" << endl; + for (int j = 0; j < 16; j++) { + cout << hex << std::setfill('0') << std::setw(2) << j * 16 << ": "; + for (int i = 0; i < 16; i++) { + cout << hex << std::setfill('0') << std::setw(2) << (int)buf[j * 16 + i] << " "; + } + cout << endl; + } + return retval; +} + +void Daemon::setUbxMsgRates(QMap& ubxMsgRates) +{ + for (QMap::iterator it = ubxMsgRates.begin(); it != ubxMsgRates.end(); it++) { + emit UBXSetCfgMsgRate(it.key(), 1, it.value()); + emit sendPollUbxMsgRate(it.key()); + waitingForAppliedMsgRate++; + } +} + +// ALL FUNCTIONS ABOUT UBLOX GPS MODULE +void Daemon::configGps() +{ + // set up ubx as only outPortProtocol + emit UBXSetCfgPrt(1, PROTO_UBX); + + // set dynamic model: Stationary + emit UBXSetDynModel(2); + + emit UBXSetAopCfg(true); + + emit sendPollUbxMsg(UBX_MON_VER); + + int measrate = 10; + emit UBXSetCfgRate(1000 / measrate, 1); // UBX_RATE + + emit UBXSetCfgMsgRate(UBX_TIM_TM2, 1, 1); // TIM-TM2 + emit UBXSetCfgMsgRate(UBX_TIM_TP, 1, 0); // TIM-TP + emit UBXSetCfgMsgRate(UBX_NAV_TIMEUTC, 1, 131); // NAV-TIMEUTC + emit UBXSetCfgMsgRate(UBX_MON_HW, 1, 47); // MON-HW + emit UBXSetCfgMsgRate(UBX_MON_HW2, 1, 49); // MON-HW + emit UBXSetCfgMsgRate(UBX_NAV_POSLLH, 1, 127); // MON-POSLLH + // probably also configured with UBX-CFG-INFO... + emit UBXSetCfgMsgRate(UBX_NAV_TIMEGPS, 1, 0); // NAV-TIMEGPS + emit UBXSetCfgMsgRate(UBX_NAV_SOL, 1, 0); // NAV-SOL + emit UBXSetCfgMsgRate(UBX_NAV_STATUS, 1, 71); // NAV-STATUS + emit UBXSetCfgMsgRate(UBX_NAV_CLOCK, 1, 189); // NAV-CLOCK + emit UBXSetCfgMsgRate(UBX_MON_RXBUF, 1, 53); // MON-TXBUF + emit UBXSetCfgMsgRate(UBX_MON_TXBUF, 1, 51); // MON-TXBUF + emit UBXSetCfgMsgRate(UBX_NAV_SBAS, 1, 0); // NAV-SBAS + emit UBXSetCfgMsgRate(UBX_NAV_DOP, 1, 254); // NAV-DOP + // this poll is for checking the port cfg (which protocols are enabled etc.) + emit sendPollUbxMsg(UBX_CFG_PRT); + emit sendPollUbxMsg(UBX_MON_VER); + emit sendPollUbxMsg(UBX_MON_VER); + emit sendPollUbxMsg(UBX_MON_VER); + emit sendPollUbxMsg(UBX_CFG_GNSS); + emit sendPollUbxMsg(UBX_CFG_NAVX5); + emit sendPollUbxMsg(UBX_CFG_ANT); + emit sendPollUbxMsg(UBX_CFG_TP5); + + configGpsForVersion(); +} + +void Daemon::configGpsForVersion() +{ + if (QtSerialUblox::getProtVersion() <= 0.1) + return; + if (QtSerialUblox::getProtVersion() > 15.0) { + if (std::find(allMsgCfgID.begin(), allMsgCfgID.end(), UBX_NAV_SAT) == allMsgCfgID.end()) { + allMsgCfgID.push_back(UBX_NAV_SAT); + } + emit UBXSetCfgMsgRate(UBX_NAV_SAT, 1, 69); // NAV-SAT + emit UBXSetCfgMsgRate(UBX_NAV_SVINFO, 1, 0); + } else + emit UBXSetCfgMsgRate(UBX_NAV_SVINFO, 1, 69); // NAV-SVINFO +} + +void Daemon::pollAllUbxMsgRate() +{ + for (const auto& elem : allMsgCfgID) { + emit sendPollUbxMsgRate(elem); + } +} + +void Daemon::UBXReceivedAckNak(uint16_t ackedMsgID, uint16_t ackedCfgMsgID) +{ + // the value was already set correctly before by either poll or set, + // if not acknowledged or timeout we set the value to -1 (unknown/undefined) + switch (ackedMsgID) { + case UBX_CFG_MSG: + msgRateCfgs.insert(ackedCfgMsgID, -1); + break; + default: + break; + } +} + +void Daemon::UBXReceivedMsgRateCfg(uint16_t msgID, uint8_t rate) +{ + msgRateCfgs.insert(msgID, rate); + waitingForAppliedMsgRate--; + if (waitingForAppliedMsgRate < 0) { + waitingForAppliedMsgRate = 0; + } + if (waitingForAppliedMsgRate == 0) { + sendUbxMsgRates(); + } +} +void Daemon::onGpsMonHWUpdated(const GnssMonHwStruct& hw) +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MONHW); + (*tcpMessage.dStream) << hw; + emit sendTcpMessage(tcpMessage); + emit logParameter(LogParameter("preampNoise", QString::number(-hw.noise) + " dBHz", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("preampAGC", QString::number(hw.agc), LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("antennaStatus", QString::number(hw.antStatus), LogParameter::LOG_LATEST)); + emit logParameter(LogParameter("antennaPower", QString::number(hw.antPower), LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("jammingLevel", QString::number(hw.jamInd / 2.55, 'f', 1) + " %", LogParameter::LOG_AVERAGE)); +} + +void Daemon::onGpsMonHW2Updated(const GnssMonHw2Struct& hw2) +{ + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MONHW2); + (*tcpMessage.dStream) << hw2; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::onGpsPropertyUpdatedGnss(const std::vector& sats, + std::chrono::duration lastUpdated) +{ + vector visibleSats = sats; + std::sort(visibleSats.begin(), visibleSats.end(), GnssSatellite::sortByCnr); + while (visibleSats.size() > 0 && visibleSats.back().getCnr() == 0) + visibleSats.pop_back(); + + if (verbose > 3) { + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(lastUpdated) + << "Nr of satellites: " << visibleSats.size() << " (out of " << sats.size() << endl; + // read nrSats property without evaluation to prevent separate display of this property + // in the common message poll below + GnssSatellite::PrintHeader(true); + for (unsigned int i = 0; i < sats.size(); i++) { + sats[i].Print(i, false); + } + } + int N = sats.size(); + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GNSS_SATS); + (*tcpMessage.dStream) << N; + for (int i = 0; i < N; i++) { + (*tcpMessage.dStream) << sats[i]; + } + emit sendTcpMessage(tcpMessage); + nrSats = Property("nrSats", N); + nrVisibleSats = QVariant { static_cast(visibleSats.size()) }; + + propertyMap["nrSats"] = Property("nrSats", N); + propertyMap["visSats"] = Property("visSats", visibleSats.size()); + + int usedSats = 0, maxCnr = 0; + if (visibleSats.size()) { + for (auto sat : visibleSats) { + if (sat.fUsed) + usedSats++; + if (sat.fCnr > maxCnr) + maxCnr = sat.fCnr; + } + } + propertyMap["usedSats"] = Property("usedSats", usedSats); + propertyMap["maxCNR"] = Property("maxCNR", maxCnr); + + emit logParameter(LogParameter("sats", QString("%1").arg(visibleSats.size()), LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("usedSats", QString("%1").arg(usedSats), LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("maxCNR", QString("%1").arg(maxCnr) + " dB", LogParameter::LOG_AVERAGE)); +} + +void Daemon::onUBXReceivedGnssConfig(uint8_t numTrkCh, const std::vector& gnssConfigs) +{ + if (verbose > 3) { + // put some verbose output here + } + int N = gnssConfigs.size(); + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG); + (*tcpMessage.dStream) << (int)numTrkCh << N; + for (int i = 0; i < N; i++) { + (*tcpMessage.dStream) << gnssConfigs[i].gnssId << gnssConfigs[i].resTrkCh << gnssConfigs[i].maxTrkCh << gnssConfigs[i].flags; + } + emit sendTcpMessage(tcpMessage); +} + +void Daemon::onUBXReceivedTP5(const UbxTimePulseStruct& tp) +{ + static uint8_t forceUtcSetCounter = 0; + if (verbose > 3) { + // put some verbose output here + } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_CFG_TP5); + (*tcpMessage.dStream) << tp; + emit sendTcpMessage(tcpMessage); + // check here if UTC is selected as time source + // this should probably be implemented somewhere else, maybe at ublox init + // however, for the timestamping to work correctly, setting the time grid to UTC is mandatory! + int timeGrid = (tp.flags & UbxTimePulseStruct::GRID_UTC_GPS) >> 7; + if (timeGrid != 0 && forceUtcSetCounter++ < 3) { + UbxTimePulseStruct newTp = tp; + newTp.flags &= ~((uint32_t)UbxTimePulseStruct::GRID_UTC_GPS); + emit UBXSetCfgTP5(newTp); + qDebug() << "forced time grid to UTC"; + emit sendPollUbxMsg(UBX_CFG_TP5); + } +} + +void Daemon::onUBXReceivedTxBuf(uint8_t txUsage, uint8_t txPeakUsage) +{ + TcpMessage* tcpMessage; + if (verbose > 3) { + qDebug() << "TX buf usage: " << (int)txUsage << " %"; + qDebug() << "TX buf peak usage: " << (int)txPeakUsage << " %"; + } + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_TXBUF); + *(tcpMessage->dStream) << (quint8)txUsage << (quint8)txPeakUsage; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("TXBufUsage", QString::number(txUsage) + " %", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("maxTXBufUsage", QString::number(txPeakUsage) + " %", LogParameter::LOG_LATEST)); +} + +void Daemon::onUBXReceivedRxBuf(uint8_t rxUsage, uint8_t rxPeakUsage) +{ + TcpMessage* tcpMessage; + if (verbose > 3) { + qDebug() << "RX buf usage: " << (int)rxUsage << " %"; + qDebug() << "RX buf peak usage: " << (int)rxPeakUsage << " %"; + } + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_RXBUF); + *(tcpMessage->dStream) << (quint8)rxUsage << (quint8)rxPeakUsage; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("RXBufUsage", QString::number(rxUsage) + " %", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("maxRXBufUsage", QString::number(rxPeakUsage) + " %", LogParameter::LOG_LATEST)); +} + +void Daemon::gpsPropertyUpdatedUint8(uint8_t data, std::chrono::duration updateAge, + char propertyName) +{ + TcpMessage* tcpMessage; + switch (propertyName) { + case 's': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "Nr of available satellites: " << (int)data << endl; + break; + case 'e': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "quant error: " << (int)data << " ps" << endl; + break; + case 'f': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "Fix value: " << (int)data << endl; + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_FIXSTATUS); + *(tcpMessage->dStream) << (quint8)data; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("fixStatus", QString::number(data), LogParameter::LOG_LATEST)); + emit logParameter(LogParameter("fixStatusString", FIX_TYPE_STRINGS[data], LogParameter::LOG_LATEST)); + fixStatus = QVariant(data); + propertyMap["fixStatus"] = Property("fixStatus", FIX_TYPE_STRINGS[data]); + break; + default: + break; + } +} + +void Daemon::gpsPropertyUpdatedUint32(uint32_t data, chrono::duration updateAge, + char propertyName) +{ + TcpMessage* tcpMessage; + switch (propertyName) { + case 'a': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "time accuracy: " << data << " ns" << endl; + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_TIME_ACCURACY); + *(tcpMessage->dStream) << (quint32)data; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("timeAccuracy", QString::number(data) + " ns", LogParameter::LOG_AVERAGE)); + break; + case 'f': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "frequency accuracy: " << data << " ps/s" << endl; + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_FREQ_ACCURACY); + *(tcpMessage->dStream) << (quint32)data; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("freqAccuracy", QString::number(data) + " ps/s", LogParameter::LOG_AVERAGE)); + break; + case 'u': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "Ublox uptime: " << data << " s" << endl; + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_UPTIME); + *(tcpMessage->dStream) << (quint32)data; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + emit logParameter(LogParameter("ubloxUptime", QString::number(data) + " s", LogParameter::LOG_LATEST)); + break; + case 'c': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "rising edge counter: " << data << endl; + propertyMap["events"] = Property("events", (quint16)data); + tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_EVENTCOUNTER); + *(tcpMessage->dStream) << (quint32)data; + emit sendTcpMessage(*tcpMessage); + delete tcpMessage; + break; + default: + break; + } +} + +void Daemon::gpsPropertyUpdatedInt32(int32_t data, std::chrono::duration updateAge, + char propertyName) +{ + switch (propertyName) { + case 'd': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "clock drift: " << data << " ns/s" << endl; + logParameter(LogParameter("clockDrift", QString::number(data) + " ns/s", LogParameter::LOG_AVERAGE)); + propertyMap["clkDrift"] = Property("clkDrift", (qint32)data); + break; + case 'b': + if (verbose > 3) + cout << std::chrono::system_clock::now() + - std::chrono::duration_cast(updateAge) + << "clock bias: " << data << " ns" << endl; + emit logParameter(LogParameter("clockBias", QString::number(data) + " ns", LogParameter::LOG_AVERAGE)); + propertyMap["clkBias"] = Property("clkBias", (qint32)data); + break; + default: + break; + } +} + +void Daemon::UBXReceivedVersion(const QString& swString, const QString& hwString, const QString& protString) +{ + static bool initialVersionInfo = true; + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_VERSION); + (*tcpMessage.dStream) << swString << hwString << protString; + emit sendTcpMessage(tcpMessage); + emit logParameter(LogParameter("UBX_SW_Version", swString, LogParameter::LOG_ONCE)); + emit logParameter(LogParameter("UBX_HW_Version", hwString, LogParameter::LOG_ONCE)); + emit logParameter(LogParameter("UBX_Prot_Version", protString, LogParameter::LOG_ONCE)); + if (initialVersionInfo) { + configGpsForVersion(); + qInfo() << "Ublox version: " << hwString << " (fw:" << swString << "prot:" << protString << ")"; + } + initialVersionInfo = false; +} + +void Daemon::toConsole(const QString& data) +{ + cout << data << endl; +} + +void Daemon::gpsToConsole(const QString& data) +{ + cout << data << flush; +} + +void Daemon::gpsConnectionError() +{ +} + +// ALL OTHER UTITLITY FUNCTIONS +void Daemon::onMadeConnection(QString remotePeerAddress, quint16 remotePeerPort, QString /*localAddress*/, quint16 /*localPort*/) +{ + if (verbose > 3) + cout << "established connection with " << remotePeerAddress << ":" << remotePeerPort << endl; + + emit sendPollUbxMsg(UBX_MON_VER); + emit sendPollUbxMsg(UBX_CFG_GNSS); + emit sendPollUbxMsg(UBX_CFG_NAV5); + emit sendPollUbxMsg(UBX_CFG_TP5); + emit sendPollUbxMsg(UBX_CFG_NAVX5); + + sendBiasStatus(); + sendBiasVoltage(); + sendDacThresh(0); + sendDacThresh(1); + sendPcaChannel(); + sendEventTriggerSelection(); +} + +void Daemon::onStoppedConnection(QString remotePeerAddress, quint16 remotePeerPort, QString /*localAddress*/, quint16 /*localPort*/, + quint32 timeoutTime, quint32 connectionDuration) +{ + if (verbose > 3) { + qDebug() << "stopped connection with " << remotePeerAddress << ":" << remotePeerPort << endl; + qDebug() << "connection timeout at " << timeoutTime << " connection lasted " << connectionDuration << "s" << endl; + } +} + +void Daemon::displayError(QString message) +{ + qDebug() << "Daemon: " << message; +} + +void Daemon::displaySocketError(int socketError, QString message) +{ + switch (socketError) { + case QAbstractSocket::HostNotFoundError: + qCritical() << tr("The host was not found. Please check the host and port settings."); + break; + case QAbstractSocket::ConnectionRefusedError: + qCritical() << tr("The connection was refused by the peer. " + "Make sure the server is running, " + "and check that the host name and port " + "settings are correct."); + break; + default: + qCritical() << tr("The following error occurred: %1.").arg(message); + } + flush(cout); +} + +void Daemon::delay(int millisecondsWait) +{ + QEventLoop loop; + QTimer t; + t.connect(&t, &QTimer::timeout, &loop, &QEventLoop::quit); + t.start(millisecondsWait); + loop.exec(); +} + +void Daemon::printTimestamp() +{ + std::chrono::time_point timestamp = std::chrono::system_clock::now(); + std::chrono::microseconds mus = std::chrono::duration_cast(timestamp.time_since_epoch()); + std::chrono::seconds secs = std::chrono::duration_cast(mus); + std::chrono::microseconds subs = mus - secs; + + cout << secs.count() << "." << setw(6) << setfill('0') << subs.count() << " " << setfill(' '); +} + +// some signal handling stuff +void Daemon::hupSignalHandler(int) +{ + char a = 1; + ::write(sighupFd[0], &a, sizeof(a)); +} + +void Daemon::termSignalHandler(int) +{ + char a = 1; + ::write(sigtermFd[0], &a, sizeof(a)); +} +void Daemon::intSignalHandler(int) +{ + char a = 1; + ::write(sigintFd[0], &a, sizeof(a)); +} + +void Daemon::aquireMonitoringParameters() +{ + if ( temp_sensor_p && temp_sensor_p->probeDevicePresence()) { + if ( temp_sensor_p->getName() == "MIC184" && dynamic_cast(temp_sensor_p.get())->getAddress() < 0x4c ) { + // the attached temp sensor has a remote zone + // switch zones alternating + bool is_ext { dynamic_cast(temp_sensor_p.get())->isExternal() }; + if ( is_ext ) { + emit logParameter(LogParameter("sensor_temperature", QString::number(temp_sensor_p->getTemperature()) + " degC", LogParameter::LOG_AVERAGE)); + } else { + emit logParameter(LogParameter("temperature", QString::number(temp_sensor_p->getTemperature()) + " degC", LogParameter::LOG_AVERAGE)); + } + dynamic_cast(temp_sensor_p.get())->setExternal( !is_ext ); + } else { + emit logParameter(LogParameter("temperature", QString::number(temp_sensor_p->getTemperature()) + " degC", LogParameter::LOG_AVERAGE)); + } + } + + double v1 = 0., v2 = 0.; + if ( adc_p && + (!(std::dynamic_pointer_cast(adc_p)->getStatus() & i2cDevice::MODE_UNREACHABLE)) && + (std::dynamic_pointer_cast(adc_p)->getStatus() & (i2cDevice::MODE_NORMAL | i2cDevice::MODE_FORCE)) + ) { + v1 = adc_p->getVoltage(2); + v2 = adc_p->getVoltage(3); + if (calib && calib->getCalibItem("VDIV").name == "VDIV") { + CalibStruct vdivItem = calib->getCalibItem("VDIV"); + std::istringstream istr(vdivItem.value); + double vdiv; + istr >> vdiv; + vdiv /= 100.; + logParameter(LogParameter("calib_vdiv", QString::number(vdiv), LogParameter::LOG_ONCE)); + istr.clear(); + istr.str(calib->getCalibItem("RSENSE").value); + double rsense; + istr >> rsense; + if (verbose > 2) { + qDebug() << "rsense:" << QString::fromStdString(calib->getCalibItem("RSENSE").value) << " (" << rsense << ")"; + } + rsense /= 10. * 1000.; // yields Rsense in MOhm + logParameter(LogParameter("calib_rsense", QString::number(rsense * 1000.) + " kOhm", LogParameter::LOG_ONCE)); + double ubias = v2 * vdiv; + logParameter(LogParameter("vbias", QString::number(ubias) + " V", LogParameter::LOG_AVERAGE)); + histoMap["Bias Voltage"].fill(ubias); + double usense = (v1 - v2) * vdiv; + logParameter(LogParameter("vsense", QString::number(usense) + " V", LogParameter::LOG_AVERAGE)); + + CalibStruct flagItem = calib->getCalibItem("CALIB_FLAGS"); + int calFlags = 0; + + istr.clear(); + istr.str(flagItem.value); + istr >> calFlags; + if (verbose > 2) { + qDebug() << "cal flags:" << QString::fromStdString(flagItem.value) << " (" << (int)calFlags << dec << ")"; + } + double icorr = 0.; + if (calFlags & CalibStruct::CALIBFLAGS_CURRENT_COEFFS) { + double islope, ioffs; + istr.clear(); + istr.str(calib->getCalibItem("COEFF2").value); + istr >> ioffs; + logParameter(LogParameter("calib_coeff2", QString::number(ioffs), LogParameter::LOG_ONCE)); + istr.clear(); + istr.str(calib->getCalibItem("COEFF3").value); + istr >> islope; + logParameter(LogParameter("calib_coeff3", QString::number(islope), LogParameter::LOG_ONCE)); + icorr = ubias * islope + ioffs; + } + double ibias = usense / rsense - icorr; + histoMap["Bias Current"].fill(ibias); + logParameter(LogParameter("ibias", QString::number(ibias) + " uA", LogParameter::LOG_AVERAGE)); + + } else { + logParameter(LogParameter("vadc3", QString::number(v1) + " V", LogParameter::LOG_AVERAGE)); + logParameter(LogParameter("vadc4", QString::number(v2) + " V", LogParameter::LOG_AVERAGE)); + } + } +} + +void Daemon::onLogParameterPolled() +{ + // connect to the regular log timer signal to log several non-regularly polled parameters + emit logParameter(LogParameter("biasSwitch", QString::number(biasON), LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("preampSwitch1", QString::number((int)preampStatus[0]), LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("preampSwitch2", QString::number((int)preampStatus[1]), LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("gainSwitch", QString::number((int)gainSwitch), LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("polaritySwitch1", QString::number((int)polarity1), LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("polaritySwitch2", QString::number((int)polarity2), LogParameter::LOG_ON_CHANGE)); + + if ( dac_p && dac_p->probeDevicePresence() ) { + emit logParameter(LogParameter("thresh1", QString::number(dacThresh[0]) + " V", LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("thresh2", QString::number(dacThresh[1]) + " V", LogParameter::LOG_ON_CHANGE)); + emit logParameter(LogParameter("biasDAC", QString::number(biasVoltage) + " V", LogParameter::LOG_ON_CHANGE)); + } + + if ( io_extender_p && io_extender_p->probeDevicePresence() ) + emit logParameter(LogParameter("ubxInputSwitch", "0x" + QString::number(pcaPortMask, 16), LogParameter::LOG_ON_CHANGE)); + if (pigHandler != nullptr) + emit logParameter(LogParameter("gpioTriggerSelection", "0x" + QString::number((int)eventTrigger, 16), LogParameter::LOG_ON_CHANGE)); + + for (auto& hist : histoMap) { + sendHistogram(hist); + hist.rescale(); + } + + sendLogInfo(); + if (verbose > 2) { + qDebug() << "current data file: " << fileHandler->dataFileInfo().absoluteFilePath(); + qDebug() << " file size: " << fileHandler->dataFileInfo().size() / (1024 * 1024) << "MiB"; + } + + // Since Linux 2.3.23 (i386) and Linux 2.3.48 (all architectures) the + // structure is: + // + // struct sysinfo { + // long uptime; /* Seconds since boot */ + // unsigned long loads[3]; /* 1, 5, and 15 minute load averages */ + // unsigned long totalram; /* Total usable main memory size */ + // unsigned long freeram; /* Available memory size */ + // unsigned long sharedram; /* Amount of shared memory */ + // unsigned long bufferram; /* Memory used by buffers */ + // unsigned long totalswap; /* Total swap space size */ + // unsigned long freeswap; /* Swap space still available */ + // unsigned short procs; /* Number of current processes */ + // unsigned long totalhigh; /* Total high memory size */ + // unsigned long freehigh; /* Available high memory size */ + // unsigned int mem_unit; /* Memory unit size in bytes */ + // char _f[20-2*sizeof(long)-sizeof(int)]; + // /* Padding to 64 bytes */ + // }; + // + // In the above structure, sizes of the memory and swap fields are given + // as multiples of mem_unit bytes. + struct sysinfo info; + memset(&info, 0, sizeof info); + int err = sysinfo(&info); + if (!err) { + double f_load = 1.0 / (1 << SI_LOAD_SHIFT); + if (verbose > 2) { + qDebug() << "*** Sysinfo Stats ***"; + qDebug() << "nr of cpus : " << get_nprocs(); + qDebug() << "uptime (h) : " << info.uptime / 3600.; + qDebug() << "load avg (1min) : " << info.loads[0] * f_load; + qDebug() << "free RAM : " << (1.0e-6 * info.freeram / info.mem_unit) << " Mb"; + qDebug() << "free swap : " << (1.0e-6 * info.freeswap / info.mem_unit) << " Mb"; + } + emit logParameter(LogParameter("systemNrCPUs", QString::number(get_nprocs()) + " ", LogParameter::LOG_ONCE)); + emit logParameter(LogParameter("systemUptime", QString::number(info.uptime / 3600.) + " h", LogParameter::LOG_LATEST)); + emit logParameter(LogParameter("systemFreeMem", QString::number(1e-6 * info.freeram / info.mem_unit) + " Mb", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("systemFreeSwap", QString::number(1e-6 * info.freeswap / info.mem_unit) + " Mb", LogParameter::LOG_AVERAGE)); + emit logParameter(LogParameter("systemLoadAvg", QString::number(info.loads[0] * f_load) + " ", LogParameter::LOG_AVERAGE)); + } + + // rate buffer debug output + if ( verbose > 2 ) { + qDebug() << "GPIO Rate Summary:"; + for (auto signalIt=GPIO_PINMAP.begin(); signalIt!=GPIO_PINMAP.end(); signalIt++) { + const GPIO_SIGNAL signalId=signalIt->first; + if (GPIO_SIGNAL_MAP[signalId].direction == DIR_IN ) { + qDebug()<second + <<"rate:"<second )<<"Hz" + <<"deadtime"<second ).count()<<"us"; + } + } + } +} + +void Daemon::onUBXReceivedTimeTM2(const UbxTimeMarkStruct& tm) +{ + if (!tm.risingValid && !tm.fallingValid) { + qDebug() << "Daemon::onUBXReceivedTimeTM2(const UbxTimeMarkStruct&): detected invalid time mark message; no rising or falling edge data"; + return; + } + static UbxTimeMarkStruct lastTimeMark {}; + + long double dts = (tm.falling.tv_sec - tm.rising.tv_sec) * 1.0e9L; + dts += (tm.falling.tv_nsec - tm.rising.tv_nsec); + if ((dts > 0.0L) && tm.fallingValid) { + histoMap["UbxEventLength"].fill(static_cast(dts)); + } + long double interval = (tm.rising.tv_sec - lastTimeMark.rising.tv_sec) * 1.0e9L; + interval += (tm.rising.tv_nsec - lastTimeMark.rising.tv_nsec); + if ( interval < 1e12 ) histoMap["UbxEventInterval"].fill(static_cast(1.0e-6L * interval)); + uint16_t diffCount = tm.evtCounter - lastTimeMark.evtCounter; + emit timeMarkIntervalCountUpdate(diffCount, static_cast(interval * 1.0e-9L)); + lastTimeMark = tm; + + // output is: rising falling timeAcc valid timeBase utcAvailable + std::stringstream tempStream; + tempStream << tm.rising << tm.falling << tm.accuracy_ns << " " << tm.evtCounter << " " + << static_cast(tm.valid) << " " << static_cast(tm.timeBase) << " " + << static_cast(tm.utcAvailable); + emit eventMessage(QString::fromStdString(tempStream.str())); + + if (!tm.risingValid || !tm.fallingValid) { + qDebug() << "detected timemark message with reconstructed edge time (" << QString((tm.risingValid) ? "falling" : "rising") << ")"; + qDebug() << "msg:" << QString::fromStdString(tempStream.str()); + } + + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_TIMEMARK); + (*tcpMessage.dStream) << tm; + emit sendTcpMessage(tcpMessage); +} + +void Daemon::updateOledDisplay() +{ + if ( !oled_p || !oled_p->devicePresent() ) return; + oled_p->clearDisplay(); + oled_p->setCursor(0, 2); + oled_p->print("*Cosmic Shower Det.*\n"); + oled_p->printf("Rates %4.1f %4.1f /s\n", getRateFromCounts(AND_RATE), getRateFromCounts(XOR_RATE)); + if ( temp_sensor_p && temp_sensor_p->probeDevicePresence() ) { + oled_p->printf("temp %4.2f %cC\n", temp_sensor_p->getTemperature(), DEGREE_CHARCODE); + } + oled_p->printf("%d(%d) Sats ", nrVisibleSats().toInt(), nrSats().toInt(), DEGREE_CHARCODE); + oled_p->printf("%s\n", FIX_TYPE_STRINGS[fixStatus().toInt()].toStdString().c_str()); + oled_p->display(); +} + +void Daemon::onStatusLed1Event( int onTimeMs ) +{ + emit GpioSetState( GPIO_PINMAP[STATUS1], true ); + if ( onTimeMs ) { + QTimer::singleShot( onTimeMs, [&]() { + emit GpioSetState( GPIO_PINMAP[STATUS1], false ); + } + ); + } +} + +void Daemon::onStatusLed2Event( int onTimeMs ) +{ + emit GpioSetState( GPIO_PINMAP[STATUS2], true ); + if ( onTimeMs ) { + QTimer::singleShot( onTimeMs, [&]() { + emit GpioSetState( GPIO_PINMAP[STATUS2], false ); + } + ); + } +} + diff --git a/daemon/src/hardware/i2c/Adafruit_GFX.cpp b/daemon/src/hardware/i2c/Adafruit_GFX.cpp new file mode 100644 index 00000000..8795aa21 --- /dev/null +++ b/daemon/src/hardware/i2c/Adafruit_GFX.cpp @@ -0,0 +1,555 @@ +/****************************************************************** + This is the core graphics library for all our displays, providing + basic graphics primitives (points, lines, circles, etc.). It needs + to be paired with a hardware-specific library for each display + device we carry (handling the lower-level functions). + + Adafruit invests time and resources providing this open + source code, please support Adafruit and open-source hardware + by purchasing products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, check license.txt for more information. + All text above must be included in any redistribution. + +02/18/2013 Charles-Henri Hallard (http://hallard.me) + Modified for compiling and use on Raspberry ArduiPi Board + LCD size and connection are now passed as arguments on + the command line (no more #define on compilation needed) + ArduiPi project documentation http://hallard.me/arduipi +07/01/2013 Charles-Henri Hallard (http://hallard.me) + Created Draw Bargraph feature + Added printf feature + + ******************************************************************/ + +#include "hardware/i2c/Adafruit_GFX.h" +#include "hardware/i2c/glcdfont.h" +#include +#include + +void Adafruit_GFX::constructor(int16_t w, int16_t h) +{ + _width = WIDTH = w; + _height = HEIGHT = h; + + rotation = 0; + cursor_y = cursor_x = 0; + textsize = 1; + textcolor = textbgcolor = 0xFFFF; + wrap = true; +} + +// the printf function +void Adafruit_GFX::printf(const char* format, ...) +{ + + char buffer[64]; + char* p = buffer; + int n; + va_list args; + va_start(args, format); + vsnprintf(buffer, sizeof(buffer) - 1, format, args); + n = strlen(buffer); + + while (*p != 0 && n-- > 0) { + write((uint8_t)*p++); + } + + va_end(args); +} + +// the print function +void Adafruit_GFX::print(const char* string) +{ + + const char* p = string; + int n = strlen(string); + + while (*p != 0 && n-- > 0) { + write((uint8_t)*p++); + } +} + +// draw a circle outline +void Adafruit_GFX::drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color) +{ + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + drawPixel(x0, y0 + r, color); + drawPixel(x0, y0 - r, color); + drawPixel(x0 + r, y0, color); + drawPixel(x0 - r, y0, color); + + while (x < y) { + if (f >= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + + x++; + ddF_x += 2; + f += ddF_x; + + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 - x, y0 + y, color); + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 - x, y0 - y, color); + drawPixel(x0 + y, y0 + x, color); + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 + y, y0 - x, color); + drawPixel(x0 - y, y0 - x, color); + } +} + +void Adafruit_GFX::drawCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername, uint16_t color) +{ + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x < y) { + if (f >= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + + x++; + ddF_x += 2; + f += ddF_x; + if (cornername & 0x4) { + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 + y, y0 + x, color); + } + if (cornername & 0x2) { + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 + y, y0 - x, color); + } + if (cornername & 0x8) { + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 - x, y0 + y, color); + } + if (cornername & 0x1) { + drawPixel(x0 - y, y0 - x, color); + drawPixel(x0 - x, y0 - y, color); + } + } +} + +void Adafruit_GFX::fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color) +{ + drawFastVLine(x0, y0 - r, 2 * r + 1, color); + fillCircleHelper(x0, y0, r, 3, 0, color); +} + +// used to do circles and roundrects! +void Adafruit_GFX::fillCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername, int16_t delta, uint16_t color) +{ + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x < y) { + if (f >= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + + x++; + ddF_x += 2; + f += ddF_x; + + if (cornername & 0x1) { + drawFastVLine(x0 + x, y0 - y, 2 * y + 1 + delta, color); + drawFastVLine(x0 + y, y0 - x, 2 * x + 1 + delta, color); + } + + if (cornername & 0x2) { + drawFastVLine(x0 - x, y0 - y, 2 * y + 1 + delta, color); + drawFastVLine(x0 - y, y0 - x, 2 * x + 1 + delta, color); + } + } +} + +// bresenham's algorithm - thx wikpedia +void Adafruit_GFX::drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint16_t color) +{ + int16_t steep = abs(y1 - y0) > abs(x1 - x0); + + if (steep) { + adafruit_swap(x0, y0); + adafruit_swap(x1, y1); + } + + if (x0 > x1) { + adafruit_swap(x0, x1); + adafruit_swap(y0, y1); + } + + int16_t dx, dy; + dx = x1 - x0; + dy = abs(y1 - y0); + + int16_t err = dx / 2; + int16_t ystep; + + if (y0 < y1) { + ystep = 1; + } else { + ystep = -1; + } + + for (; x0 <= x1; x0++) { + if (steep) { + drawPixel(y0, x0, color); + } else { + drawPixel(x0, y0, color); + } + err -= dy; + + if (err < 0) { + y0 += ystep; + err += dx; + } + } +} + +// draw a rectangle +void Adafruit_GFX::drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) +{ + drawFastHLine(x, y, w, color); + drawFastHLine(x, y + h - 1, w, color); + drawFastVLine(x, y, h, color); + drawFastVLine(x + w - 1, y, h, color); +} + +void Adafruit_GFX::drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color) +{ + // stupidest version - update in subclasses if desired! + drawLine(x, y, x, y + h - 1, color); +} + +void Adafruit_GFX::drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color) +{ + // stupidest version - update in subclasses if desired! + drawLine(x, y, x + w - 1, y, color); +} + +void Adafruit_GFX::fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) +{ + // stupidest version - update in subclasses if desired! + for (int16_t i = x; i < x + w; i++) { + drawFastVLine(i, y, h, color); + } +} + +// draw a vertical bargraph and fill it with percent value (0%..100%) +void Adafruit_GFX::drawVerticalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent) +{ + uint16_t vsize; + + // Create rectangle + drawRect(x, y, w, h, color); + + // Do not do stupid job + if (h > 2 && w > 2) { + // calculate pixel size of bargraph + vsize = ((h - 2) * percent) / 100; + + // Fill it from bottom (0%) to top (100%) + fillRect(x + 1, y + 1 + ((h - 2) - vsize), w - 2, vsize, color); + } +} + +// draw a horizontal bargraph and fill it with percent value (0%..100%) +void Adafruit_GFX::drawHorizontalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent) +{ + uint16_t hsize; + + // Create rectangle + drawRect(x, y, w, h, color); + + // Do not do stupid job + if (h > 2 && w > 2) { + // calculate pixel size of bargraph + hsize = ((w - 2) * percent) / 100; + + // Fill it from left (0%) to right (100%) + fillRect(x + 1, y + 1, hsize, h - 2, color); + } +} + +void Adafruit_GFX::fillScreen(uint16_t color) +{ + fillRect(0, 0, _width, _height, color); +} + +// draw a rounded rectangle! +void Adafruit_GFX::drawRoundRect(int16_t x, int16_t y, int16_t w, int16_t h, int16_t r, uint16_t color) +{ + + // smarter version + drawFastHLine(x + r, y, w - 2 * r, color); // Top + drawFastHLine(x + r, y + h - 1, w - 2 * r, color); // Bottom + drawFastVLine(x, y + r, h - 2 * r, color); // Left + drawFastVLine(x + w - 1, y + r, h - 2 * r, color); // Right + + // draw four corners + drawCircleHelper(x + r, y + r, r, 1, color); + drawCircleHelper(x + w - r - 1, y + r, r, 2, color); + drawCircleHelper(x + w - r - 1, y + h - r - 1, r, 4, color); + drawCircleHelper(x + r, y + h - r - 1, r, 8, color); +} + +// fill a rounded rectangle! +void Adafruit_GFX::fillRoundRect(int16_t x, int16_t y, int16_t w, int16_t h, int16_t r, uint16_t color) +{ + // smarter version + fillRect(x + r, y, w - 2 * r, h, color); + + // draw four corners + fillCircleHelper(x + w - r - 1, y + r, r, 1, h - 2 * r - 1, color); + fillCircleHelper(x + r, y + r, r, 2, h - 2 * r - 1, color); +} + +// draw a triangle! +void Adafruit_GFX::drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t x2, int16_t y2, uint16_t color) +{ + drawLine(x0, y0, x1, y1, color); + drawLine(x1, y1, x2, y2, color); + drawLine(x2, y2, x0, y0, color); +} + +// fill a triangle! +void Adafruit_GFX::fillTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t x2, int16_t y2, uint16_t color) +{ + + int16_t a, b, y, last; + + // Sort coordinates by Y order (y2 >= y1 >= y0) + if (y0 > y1) { + adafruit_swap(y0, y1); + adafruit_swap(x0, x1); + } + if (y1 > y2) { + adafruit_swap(y2, y1); + adafruit_swap(x2, x1); + } + if (y0 > y1) { + adafruit_swap(y0, y1); + adafruit_swap(x0, x1); + } + + if (y0 == y2) { // Handle awkward all-on-same-line case as its own thing + a = b = x0; + if (x1 < a) + a = x1; + else if (x1 > b) + b = x1; + if (x2 < a) + a = x2; + else if (x2 > b) + b = x2; + drawFastHLine(a, y0, b - a + 1, color); + return; + } + + int16_t + dx01 + = x1 - x0, + dy01 = y1 - y0, + dx02 = x2 - x0, + dy02 = y2 - y0, + dx12 = x2 - x1, + dy12 = y2 - y1, + sa = 0, + sb = 0; + + // For upper part of triangle, find scanline crossings for segments + // 0-1 and 0-2. If y1=y2 (flat-bottomed triangle), the scanline y1 + // is included here (and second loop will be skipped, avoiding a /0 + // error there), otherwise scanline y1 is skipped here and handled + // in the second loop...which also avoids a /0 error here if y0=y1 + // (flat-topped triangle). + if (y1 == y2) + last = y1; // Include y1 scanline + else + last = y1 - 1; // Skip it + + for (y = y0; y <= last; y++) { + a = x0 + sa / dy01; + b = x0 + sb / dy02; + sa += dx01; + sb += dx02; + if (a > b) + adafruit_swap(a, b); + + drawFastHLine(a, y, b - a + 1, color); + } + + // For lower part of triangle, find scanline crossings for segments + // 0-2 and 1-2. This loop is skipped if y1=y2. + sa = dx12 * (y - y1); + sb = dx02 * (y - y0); + for (; y <= y2; y++) { + a = x1 + sa / dy12; + b = x0 + sb / dy02; + sa += dx12; + sb += dx02; + if (a > b) + adafruit_swap(a, b); + + drawFastHLine(a, y, b - a + 1, color); + } +} + +void Adafruit_GFX::drawBitmap(int16_t x, int16_t y, const uint8_t* bitmap, int16_t w, int16_t h, uint16_t color) +{ + + int16_t i, j, byteWidth = (w + 7) / 8; + + for (j = 0; j < h; j++) { + for (i = 0; i < w; i++) { + if (*(bitmap + j * byteWidth + i / 8) & (128 >> (i & 7))) { + drawPixel(x + i, y + j, color); + } + } + } +} + +size_t Adafruit_GFX::write(uint8_t c) +{ + if (c == '\n') { + cursor_y += textsize * 8; + cursor_x = 0; + } else if (c == '\r') { + // skip em + } else { + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + cursor_x += textsize * 6; + + if (wrap && (cursor_x > (_width - textsize * 6))) { + cursor_y += textsize * 8; + cursor_x = 0; + } + } + return 1; +} + +// draw a character +void Adafruit_GFX::drawChar(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t bg, uint8_t size) +{ + + if ((x >= _width) || // Clip right + (y >= _height) || // Clip bottom + ((x + 5 * size - 1) < 0) || // Clip left + ((y + 8 * size - 1) < 0)) // Clip top + return; + + for (int8_t i = 0; i < 6; i++) { + uint8_t line; + if (i == 5) + line = 0x0; + else + line = font[(c * 5) + i]; + for (int8_t j = 0; j < 8; j++) { + if (line & 0x1) { + if (size == 1) // default size + drawPixel(x + i, y + j, color); + else { // big size + fillRect(x + (i * size), y + (j * size), size, size, color); + } + } else if (bg != color) { + if (size == 1) // default size + drawPixel(x + i, y + j, bg); + else { // big size + fillRect(x + i * size, y + j * size, size, size, bg); + } + } + + line >>= 1; + } + } +} + +void Adafruit_GFX::setCursor(int16_t x, int16_t y) +{ + cursor_x = x; + cursor_y = y; +} + +void Adafruit_GFX::setTextSize(uint8_t s) +{ + textsize = (s > 0) ? s : 1; +} + +void Adafruit_GFX::setTextColor(uint16_t c) +{ + textcolor = c; + textbgcolor = c; + // for 'transparent' background, we'll set the bg + // to the same as fg instead of using a flag +} + +void Adafruit_GFX::setTextColor(uint16_t c, uint16_t b) +{ + textcolor = c; + textbgcolor = b; +} + +void Adafruit_GFX::setTextWrap(bool w) +{ + wrap = w; +} + +uint8_t Adafruit_GFX::getRotation(void) +{ + rotation %= 4; + return rotation; +} + +void Adafruit_GFX::setRotation(uint8_t x) +{ + x %= 4; // cant be higher than 3 + rotation = x; + switch (x) { + case 0: + case 2: + _width = WIDTH; + _height = HEIGHT; + break; + + case 1: + case 3: + _width = HEIGHT; + _height = WIDTH; + break; + } +} + +void Adafruit_GFX::invertDisplay(bool i) +{ + // do nothing, can be subclassed +} + +// return the size of the display which depends on the rotation! +int16_t Adafruit_GFX::width(void) +{ + return _width; +} + +int16_t Adafruit_GFX::height(void) +{ + return _height; +} diff --git a/daemon/src/hardware/i2c/adafruit_ssd1306.cpp b/daemon/src/hardware/i2c/adafruit_ssd1306.cpp new file mode 100644 index 00000000..0c24389d --- /dev/null +++ b/daemon/src/hardware/i2c/adafruit_ssd1306.cpp @@ -0,0 +1,454 @@ +#include "hardware/i2c/adafruit_ssd1306.h" +#include +#include + +using namespace std; + +/********************************************************************* +This is a library for our Monochrome OLEDs based on SSD1306 drivers + +Pick one up today in the adafruit shop! +------> http://www.adafruit.com/category/63_98 + +These displays use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen below must be included in any redistribution + +02/18/2013 Charles-Henri Hallard (http://hallard.me) +Modified for compiling and use on Raspberry ArduiPi Board +LCD size and connection are now passed as arguments on +the command line (no more #define on compilation needed) +ArduiPi project documentation http://hallard.me/arduipi +07/01/2013 Charles-Henri Hallard +Reduced code size removed the Adafruit Logo (sorry guys) +Buffer for OLED is now dynamic to LCD size +Added support of Seeed OLED 64x64 Display + +*********************************************************************/ + +/*========================================================================= +SSDxxxx Common Displays +----------------------------------------------------------------------- +Common values to all displays +=========================================================================*/ + +#define SSD_Command_Mode 0x00 /* C0 and DC bit are 0 */ +#define SSD_Data_Mode 0x40 /* C0 bit is 0 and DC bit is 1 */ + +#define SSD_Inverse_Display 0xA7 + +#define SSD_Display_Off 0xAE +#define SSD_Display_On 0xAF + +#define SSD_Set_ContrastLevel 0x81 + +#define SSD_External_Vcc 0x01 +#define SSD_Internal_Vcc 0x02 + +#define SSD_Activate_Scroll 0x2F +#define SSD_Deactivate_Scroll 0x2E + +#define Scroll_Left 0x00 +#define Scroll_Right 0x01 + +#define Scroll_2Frames 0x07 +#define Scroll_3Frames 0x04 +#define Scroll_4Frames 0x05 +#define Scroll_5Frames 0x00 +#define Scroll_25Frames 0x06 +#define Scroll_64Frames 0x01 +#define Scroll_128Frames 0x02 +#define Scroll_256Frames 0x03 + +#define VERTICAL_MODE 01 +#define PAGE_MODE 01 +#define HORIZONTAL_MODE 02 + +/*========================================================================= +SSD1306 Displays +----------------------------------------------------------------------- +The driver is used in multiple displays (128x64, 128x32, etc.). +=========================================================================*/ +#define SSD1306_DISPLAYALLON_RESUME 0xA4 +#define SSD1306_DISPLAYALLON 0xA5 + +#define SSD1306_Normal_Display 0xA6 + +#define SSD1306_SETDISPLAYOFFSET 0xD3 +#define SSD1306_SETCOMPINS 0xDA +#define SSD1306_SETVCOMDETECT 0xDB +#define SSD1306_SETDISPLAYCLOCKDIV 0xD5 +#define SSD1306_SETPRECHARGE 0xD9 +#define SSD1306_SETMULTIPLEX 0xA8 +#define SSD1306_SETLOWCOLUMN 0x00 +#define SSD1306_SETHIGHCOLUMN 0x10 +#define SSD1306_SETSTARTLINE 0x40 +#define SSD1306_MEMORYMODE 0x20 +#define SSD1306_COMSCANINC 0xC0 +#define SSD1306_COMSCANDEC 0xC8 +#define SSD1306_SEGREMAP 0xA0 +#define SSD1306_CHARGEPUMP 0x8D + +// Scrolling #defines +#define SSD1306_SET_VERTICAL_SCROLL_AREA 0xA3 +#define SSD1306_RIGHT_HORIZONTAL_SCROLL 0x26 +#define SSD1306_LEFT_HORIZONTAL_SCROLL 0x27 +#define SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL 0x29 +#define SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL 0x2A + +/*========================================================================= +SSD1308 Displays +----------------------------------------------------------------------- +The driver is used in multiple displays (128x64, 128x32, etc.). +=========================================================================*/ +#define SSD1308_Normal_Display 0xA6 + +/*========================================================================= +SSD1327 Displays +----------------------------------------------------------------------- +The driver is used in Seeed 96x96 display +=========================================================================*/ +#define SSD1327_Normal_Display 0xA4 + +// Low level I2C Write function +inline void Adafruit_SSD1306::fastI2Cwrite(uint8_t d) +{ + i2cDevice::write(&d, 1); +} +inline void Adafruit_SSD1306::fastI2Cwrite(char* tbuf, uint32_t len) +{ + i2cDevice::write((uint8_t*)tbuf, len); +} + +#define _BV(bit) (1 << (bit)) +// the most basic function, set a single pixel +void Adafruit_SSD1306::drawPixel(int16_t x, int16_t y, uint16_t color) +{ + uint8_t* p = poledbuff; + + if ((x < 0) || (x >= width()) || (y < 0) || (y >= height())) + return; + + // check rotation, move pixel around if necessary + switch (getRotation()) { + case 1: + adafruit_swap(x, y); + x = WIDTH - x - 1; + break; + + case 2: + x = WIDTH - x - 1; + y = HEIGHT - y - 1; + break; + + case 3: + adafruit_swap(x, y); + y = HEIGHT - y - 1; + break; + } + + // Get where to do the change in the buffer + p = poledbuff + (x + (y / 8) * ssd1306_lcdwidth); + + // x is which column + if (color == WHITE) + *p |= _BV((y % 8)); + else + *p &= ~_BV((y % 8)); +} + +// initializer for OLED Type +void Adafruit_SSD1306::select_oled(uint8_t OLED_TYPE) +{ + // Default type + ssd1306_lcdwidth = 128; + ssd1306_lcdheight = 64; + + // default OLED are using internal boost VCC converter + vcc_type = SSD_Internal_Vcc; + + // Oled supported display + // Setup size and I2C address + switch (OLED_TYPE) { + case OLED_ADAFRUIT_I2C_128x32: + ssd1306_lcdheight = 32; + break; + + case OLED_ADAFRUIT_I2C_128x64: + break; + + case OLED_SEEED_I2C_128x64: + vcc_type = SSD_External_Vcc; + break; + + case OLED_SEEED_I2C_96x96: + ssd1306_lcdwidth = 96; + ssd1306_lcdheight = 96; + break; + + // houston, we have a problem + default: + return; + break; + } +} + +// initializer for I2C - we only indicate the reset pin and OLED type ! +bool Adafruit_SSD1306::init(uint8_t OLED_TYPE, int8_t RST) +{ + rst = RST; + + // Select OLED parameters + select_oled(OLED_TYPE); + + // De-Allocate memory for OLED buffer if any + if (poledbuff) + free(poledbuff); + + // Allocate memory for OLED buffer + poledbuff = (uint8_t*)malloc((ssd1306_lcdwidth * ssd1306_lcdheight / 8)); + if (!poledbuff) + return false; + + return (true); +} + +void Adafruit_SSD1306::close(void) +{ + // De-Allocate memory for OLED buffer if any + if (poledbuff) + free(poledbuff); + + poledbuff = NULL; +} + +void Adafruit_SSD1306::begin(void) +{ + uint8_t multiplex; + uint8_t chargepump; + uint8_t compins; + uint8_t contrast; + uint8_t precharge; + + constructor(ssd1306_lcdwidth, ssd1306_lcdheight); + + // Reset handling, todo + + // depends on OLED type configuration + if (ssd1306_lcdheight == 32) { + multiplex = 0x1F; + compins = 0x02; + contrast = 0x8F; + } else { + multiplex = 0x3F; + compins = 0x12; + contrast = (vcc_type == SSD_External_Vcc ? 0x9F : 0xCF); + } + + if (vcc_type == SSD_External_Vcc) { + chargepump = 0x10; + precharge = 0x22; + } else { + chargepump = 0x14; + precharge = 0xF1; + } + + ssd1306_command(SSD_Display_Off); // 0xAE + ssd1306_command(SSD1306_SETDISPLAYCLOCKDIV, 0x80); // 0xD5 + the suggested ratio 0x80 + ssd1306_command(SSD1306_SETMULTIPLEX, multiplex); + ssd1306_command(SSD1306_SETDISPLAYOFFSET, 0x00); // 0xD3 + no offset + ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 + ssd1306_command(SSD1306_CHARGEPUMP, chargepump); + ssd1306_command(SSD1306_MEMORYMODE, 0x00); // 0x20 0x0 act like ks0108 + ssd1306_command(SSD1306_SEGREMAP | 0x1); + ssd1306_command(SSD1306_COMSCANDEC); + ssd1306_command(SSD1306_SETCOMPINS, compins); // 0xDA + ssd1306_command(SSD_Set_ContrastLevel, contrast); + ssd1306_command(SSD1306_SETPRECHARGE, precharge); // 0xd9 + ssd1306_command(SSD1306_SETVCOMDETECT, 0x40); // 0xDB + ssd1306_command(SSD1306_DISPLAYALLON_RESUME); // 0xA4 + ssd1306_command(SSD1306_Normal_Display); // 0xA6 + + // Reset to default value in case of + // no reset pin available on OLED + ssd1306_command(0x21, 0, 127); + ssd1306_command(0x22, 0, 7); + stopscroll(); + + // Empty uninitialized buffer + clearDisplay(); + ssd1306_command(SSD_Display_On); //--turn on oled panel +} + +void Adafruit_SSD1306::invertDisplay(bool inv) +{ + if (inv) + ssd1306_command(SSD_Inverse_Display); + else + ssd1306_command(SSD1306_Normal_Display); +} + +void Adafruit_SSD1306::ssd1306_command(uint8_t c) +{ + char buff[2]; + + // Clear D/C to switch to command mode + buff[0] = SSD_Command_Mode; + buff[1] = c; + + // Write Data on I2C + fastI2Cwrite(buff, sizeof(buff)); +} + +void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1) +{ + char buff[3]; + buff[1] = c0; + buff[2] = c1; + + // Clear D/C to switch to command mode + buff[0] = SSD_Command_Mode; + + // Write Data on I2C + fastI2Cwrite(buff, 3); +} + +void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2) +{ + char buff[4]; + + buff[1] = c0; + buff[2] = c1; + buff[3] = c2; + + // Clear D/C to switch to command mode + buff[0] = SSD_Command_Mode; + + // Write Data on I2C + fastI2Cwrite(buff, sizeof(buff)); +} + +// startscrollright +// Activate a right handed scroll for rows start through stop +// Hint, the display is 16 rows tall. To scroll the whole display, run: +// display.scrollright(0x00, 0x0F) +void Adafruit_SSD1306::startscrollright(uint8_t start, uint8_t stop) +{ + ssd1306_command(SSD1306_RIGHT_HORIZONTAL_SCROLL); + ssd1306_command(0X00); + ssd1306_command(start); + ssd1306_command(0X00); + ssd1306_command(stop); + ssd1306_command(0X01); + ssd1306_command(0XFF); + ssd1306_command(SSD_Activate_Scroll); +} + +// startscrollleft +// Activate a right handed scroll for rows start through stop +// Hint, the display is 16 rows tall. To scroll the whole display, run: +// display.scrollright(0x00, 0x0F) +void Adafruit_SSD1306::startscrollleft(uint8_t start, uint8_t stop) +{ + ssd1306_command(SSD1306_LEFT_HORIZONTAL_SCROLL); + ssd1306_command(0X00); + ssd1306_command(start); + ssd1306_command(0X00); + ssd1306_command(stop); + ssd1306_command(0X01); + ssd1306_command(0XFF); + ssd1306_command(SSD_Activate_Scroll); +} + +// startscrolldiagright +// Activate a diagonal scroll for rows start through stop +// Hint, the display is 16 rows tall. To scroll the whole display, run: +// display.scrollright(0x00, 0x0F) +void Adafruit_SSD1306::startscrolldiagright(uint8_t start, uint8_t stop) +{ + ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); + ssd1306_command(0X00); + ssd1306_command(ssd1306_lcdheight); + ssd1306_command(SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL); + ssd1306_command(0X00); + ssd1306_command(start); + ssd1306_command(0X00); + ssd1306_command(stop); + ssd1306_command(0X01); + ssd1306_command(SSD_Activate_Scroll); +} + +// startscrolldiagleft +// Activate a diagonal scroll for rows start through stop +// Hint, the display is 16 rows tall. To scroll the whole display, run: +// display.scrollright(0x00, 0x0F) +void Adafruit_SSD1306::startscrolldiagleft(uint8_t start, uint8_t stop) +{ + ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); + ssd1306_command(0X00); + ssd1306_command(ssd1306_lcdheight); + ssd1306_command(SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL); + ssd1306_command(0X00); + ssd1306_command(start); + ssd1306_command(0X00); + ssd1306_command(stop); + ssd1306_command(0X01); + ssd1306_command(SSD_Activate_Scroll); +} + +void Adafruit_SSD1306::stopscroll(void) +{ + ssd1306_command(SSD_Deactivate_Scroll); +} + +void Adafruit_SSD1306::ssd1306_data(uint8_t c) +{ + char buff[2]; + + // Setup D/C to switch to data mode + buff[0] = SSD_Data_Mode; + buff[1] = c; + + // Write on i2c + fastI2Cwrite(buff, sizeof(buff)); +} + +void Adafruit_SSD1306::display(void) +{ + ssd1306_command(SSD1306_SETLOWCOLUMN | 0x0); // low col = 0 + ssd1306_command(SSD1306_SETHIGHCOLUMN | 0x0); // hi col = 0 + ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 + + uint16_t i = 0; + + // pointer to OLED data buffer + uint8_t* p = poledbuff; + + char buff[17]; + uint8_t x; + + // Setup D/C to switch to data mode + buff[0] = SSD_Data_Mode; + + // loop trough all OLED buffer and + // send a bunch of 16 data byte in one xmission + for (i = 0; i < (ssd1306_lcdwidth * ssd1306_lcdheight / 8); i += 16) { + for (x = 1; x <= 16; x++) + buff[x] = *p++; + + fastI2Cwrite(buff, 17); + } +} + +// clear everything (in the buffer) +void Adafruit_SSD1306::clearDisplay(void) +{ + memset(poledbuff, 0, (ssd1306_lcdwidth * ssd1306_lcdheight / 8)); +} diff --git a/daemon/src/hardware/i2c/ads1115.cpp b/daemon/src/hardware/i2c/ads1115.cpp new file mode 100644 index 00000000..31af895c --- /dev/null +++ b/daemon/src/hardware/i2c/ads1115.cpp @@ -0,0 +1,423 @@ +#include "hardware/i2c/ads1115.h" +#include +#include +#include + +/* +* ADS1115 4ch 16 bit ADC +*/ +constexpr uint16_t HI_RANGE_LIMIT { static_cast( ADS1115::MAX_ADC_VALUE * 0.8 ) }; +constexpr uint16_t LO_RANGE_LIMIT { static_cast( ADS1115::MAX_ADC_VALUE * 0.2 ) }; + +constexpr std::chrono::microseconds loop_delay { 100L }; + + +bool ADS1115::Sample::operator==(const Sample& other) +{ + return ( value==other.value && voltage==other.voltage && channel==other.channel && timestamp==other.timestamp ); +} + +bool ADS1115::Sample::operator!=(const Sample& other) +{ + return ( !(*this == other) ); +} + +auto ADS1115::adcToVoltage( int16_t adc, const CFG_PGA pga_setting ) -> float +{ + return ( adc * lsb_voltage(pga_setting) ); +} + +ADS1115::ADS1115() +: i2cDevice("/dev/i2c-1", 0x48) +{ + init(); +} + +ADS1115::ADS1115(uint8_t slaveAddress) +: i2cDevice(slaveAddress) +{ + init(); +} + +ADS1115::ADS1115(const char* busAddress, uint8_t slaveAddress) +: i2cDevice(busAddress, slaveAddress) +{ + init(); +} + +ADS1115::ADS1115(const char* busAddress, uint8_t slaveAddress, CFG_PGA pga) +: i2cDevice(busAddress, slaveAddress) +{ + init(); + setPga(pga); +} + +ADS1115::~ADS1115() { +} + +void ADS1115::init() +{ + fRate = 0x00; // RATE8 + fTitle = fName = "ADS1115"; +} + +void ADS1115::setPga(uint8_t channel, CFG_PGA pga) +{ + if (channel > 3) + return; + fPga[channel] = pga; +} + +void ADS1115::setActiveChannel( uint8_t channel, bool differential_mode ) { + fSelectedChannel = channel; + fDiffMode = differential_mode; +} + +bool ADS1115::setContinuousSampling( bool cont_sampling ) +{ + fConvMode = ( cont_sampling ) ? CONV_MODE::CONTINUOUS : CONV_MODE::SINGLE; + return writeConfig(); +} + +bool ADS1115::writeConfig( bool startNewConversion ) +{ + uint16_t conf_reg { 0 }; + + // read in the current contents of config reg only if conv_mode is unknown + if ( fConvMode == CONV_MODE::UNKNOWN ) { + if ( !readWord(static_cast(REG::CONFIG), &conf_reg) ) return false; + if ( ( conf_reg & 0x0100 ) == 0 ) { + fConvMode = CONV_MODE::CONTINUOUS; + } else { + fConvMode = CONV_MODE::SINGLE; + } + } + + conf_reg = 0; + + if ( fConvMode == CONV_MODE::SINGLE && startNewConversion ) { + conf_reg = 0x8000; // set OS bit + } + if ( !fDiffMode ) { + conf_reg |= 0x4000; // single ended mode channels + } + conf_reg |= ( fSelectedChannel & 0x03 ) << 12; // channel select + if ( fConvMode == CONV_MODE::SINGLE ) { + conf_reg |= 0x0100; // single shot mode + } + conf_reg |= ( static_cast( fPga[fSelectedChannel] ) & 0x07 ) << 9; // PGA gain select + + // This sets the 8 LSBs of the config register (bits 7-0) + conf_reg |= 0x00; // TODO: enable ALERT/RDY pin + conf_reg |= (fRate & 0x07) << 5; + + if ( !writeWord(static_cast(REG::CONFIG), conf_reg) ) return false; + fCurrentChannel = fSelectedChannel; + return true; +} + +void ADS1115::waitConversionFinished(bool& error) { + uint16_t conf_reg { 0 }; + // Wait for the conversion to complete, this requires bit 15 to change from 0->1 + int nloops = 0; + while ((conf_reg & 0x8000) == 0 && nloops * fReadWaitDelay / 1000 < 1000) // readBuf[0] contains 8 MSBs of config register, AND with 10000000 to select bit 15 + { + std::this_thread::sleep_for( std::chrono::microseconds( fReadWaitDelay) ); + if ( !readWord(static_cast(REG::CONFIG), &conf_reg) ) + { + error = true; + return; + } + nloops++; + } + if (nloops * fReadWaitDelay / 1000 >= 1000) { + if (fDebugLevel > 1) + printf("timeout!\n"); + { + error = true; + return; + } + } + if (fDebugLevel > 2) + printf(" nr of busy adc loops: %d \n", nloops); + if (nloops > 1) { + fReadWaitDelay += (nloops - 1) * fReadWaitDelay / 10; + if (fDebugLevel > 1) { + printf(" read wait delay: %6.2f ms\n", fReadWaitDelay / 1000.); + } + } + error = false; +} + +bool ADS1115::readConversionResult( int16_t& dataword ) +{ + uint16_t data { 0 }; + // Read the contents of the conversion register into readBuf + if ( !readWord(static_cast(REG::CONVERSION), &data) ) return false; + + dataword = static_cast(data); + + return true; +} + +ADS1115::Sample ADS1115::getSample( unsigned int channel ) +{ + //if ( fConvMode != CONV_MODE::SINGLE ) return InvalidSample; + std::lock_guard lock(fMutex); + int16_t conv_result; // Stores the 16 bit value of our ADC conversion + + fConvMode = CONV_MODE::SINGLE; + fSelectedChannel = channel; + + startTimer(); + + // Write the current config to the ADS1115 + // and begin a single conversion + if ( !writeConfig( true ) ) { + return InvalidSample; + } + + bool err { false }; + waitConversionFinished(err); + if ( err ) { + return InvalidSample; + } + + if ( !readConversionResult( conv_result ) ) { + return InvalidSample; + } + + stopTimer(); + fLastConvTime = fLastTimeInterval; + + Sample sample + { + std::chrono::steady_clock::now(), + conv_result, + adcToVoltage( conv_result, fPga[fCurrentChannel] ), + lsb_voltage( fPga[fCurrentChannel] ), + fCurrentChannel + }; + if ( fConvReadyFn && sample != InvalidSample ) fConvReadyFn( sample ); + + if ( fAGC[fCurrentChannel] ) { + int eadc = std::abs(conv_result); + if ( eadc > HI_RANGE_LIMIT && fPga[fCurrentChannel] > PGA6V ) { + fPga[fCurrentChannel] = CFG_PGA(fPga[fCurrentChannel] - 1); + //if (fDebugLevel > 1) printf("ADC input high...setting PGA to level %d\n", fPga[fCurrentChannel]); + } else if ( eadc < LO_RANGE_LIMIT && fPga[fCurrentChannel] < PGA256MV ) { + fPga[fCurrentChannel] = CFG_PGA(fPga[fCurrentChannel] + 1); + //if (fDebugLevel > 1) printf("ADC input low...setting PGA to level %d\n", fPga[fCurrentChannel]); + } + } + fLastSample[fCurrentChannel] = sample; + return sample; +} + +bool ADS1115::triggerConversion( unsigned int channel ) +{ + // triggering a conversion makes only sense in single shot mode + if ( fConvMode == CONV_MODE::SINGLE ) { + try { + std::thread sampler( &ADS1115::getSample, this, channel ); + sampler.detach(); + return true; + } catch (...) { } + } + return false; +} + +ADS1115::Sample ADS1115::conversionFinished() +{ + std::lock_guard lock(fMutex); + int16_t conv_result; // Stores the 16 bit value of our ADC conversion + + if ( !readConversionResult( conv_result ) ) { + return InvalidSample; + } + + stopTimer(); + fLastConvTime = fLastTimeInterval; + startTimer(); + + Sample sample + { + std::chrono::steady_clock::now(), + conv_result, + adcToVoltage( conv_result, fPga[fCurrentChannel] ), + lsb_voltage( fPga[fCurrentChannel] ), + fCurrentChannel + }; + if ( fConvReadyFn && sample != InvalidSample ) fConvReadyFn( sample ); + + if ( fAGC[fCurrentChannel] ) { + int eadc = std::abs(conv_result); + if ( eadc > HI_RANGE_LIMIT && fPga[fCurrentChannel] > PGA6V ) { + fPga[fCurrentChannel] = CFG_PGA(fPga[fCurrentChannel] - 1); + //if (fDebugLevel > 1) printf("ADC input high...setting PGA to level %d\n", fPga[fCurrentChannel]); + } else if ( eadc < LO_RANGE_LIMIT && fPga[fCurrentChannel] < PGA256MV ) { + fPga[fCurrentChannel] = CFG_PGA(fPga[fCurrentChannel] + 1); + //if (fDebugLevel > 1) printf("ADC input low...setting PGA to level %d\n", fPga[fCurrentChannel]); + } + } + fLastSample[fCurrentChannel] = sample; + return sample; +} + +int16_t ADS1115::readADC(unsigned int channel) +{ + try { + std::future sample_future = std::async(&ADS1115::getSample, this, channel); + sample_future.wait(); + if ( sample_future.valid() ) { + Sample sample { sample_future.get() }; + if ( sample != InvalidSample ) return sample.value; + } + } catch (...) { } + return INT16_MIN; +} + +bool ADS1115::setLowThreshold(int16_t thr) +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device + startTimer(); + + // These three bytes are written to the ADS1115 to set the Lo_thresh register + writeBuf[0] = static_cast(REG::LO_THRESH); // This sets the pointer register to Lo_thresh register + writeBuf[1] = (thr & 0xff00) >> 8; + writeBuf[2] |= (thr & 0x00ff); + + // Initialize the buffer used to read data from the ADS1115 to 0 + readBuf[0] = 0; + readBuf[1] = 0; + + // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, + // this sets the Lo_thresh register + int n = write(writeBuf, 3); + if (n != 3) + return false; + n = read(readBuf, 2); // Read the same register into readBuf for verification + if (n != 2) + return false; + + if ((readBuf[0] != writeBuf[1]) || (readBuf[1] != writeBuf[2])) + return false; + stopTimer(); + return true; +} + +bool ADS1115::setHighThreshold(int16_t thr) +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device + startTimer(); + + // These three bytes are written to the ADS1115 to set the Hi_thresh register + writeBuf[0] = static_cast(REG::HI_THRESH); // This sets the pointer register to Hi_thresh register + writeBuf[1] = (thr & 0xff00) >> 8; + writeBuf[2] |= (thr & 0x00ff); + + // Initialize the buffer used to read data from the ADS1115 to 0 + readBuf[0] = 0; + readBuf[1] = 0; + + // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, + // this sets the Hi_thresh register + int n = write(writeBuf, 3); + if (n != 3) + return false; + + n = read(readBuf, 2); // Read the same register into readBuf for verification + if (n != 2) + return false; + + if ((readBuf[0] != writeBuf[1]) || (readBuf[1] != writeBuf[2])) + return false; + stopTimer(); + return true; +} + +bool ADS1115::setDataReadyPinMode() +{ + // c.f. datasheet, par. 9.3.8, p. 19 + // set MSB of Lo_thresh reg to 0 + // set MSB of Hi_thresh reg to 1 + // set COMP_QUE[1:0] to any value other than '11' (default value) + bool ok = setLowThreshold(static_cast(0b0000000000000000)); + ok = ok && setHighThreshold(static_cast(0b1111111111111111)); + ok = ok && setCompQueue( 0x00 ); + return ok; +} + +bool ADS1115::setCompQueue( uint8_t bitpattern ) +{ + uint8_t buf[2] { 0, 0 }; // 2 byte buffer to store the data read from the I2C device + if ( readReg(static_cast(REG::CONFIG), buf, 2) != 2 ) return false; + buf[1] &= 0b11111100; + buf[1] |= bitpattern & 0b00000011; + if ( writeReg(static_cast(REG::CONFIG), buf, 2) != 2 ) return false; + return true; +} + +/* +bool ADS1115::devicePresent() +{ + uint8_t buf[2]; + return (read(buf, 2) == 2); // Read the currently selected register into readBuf +} +*/ + +bool ADS1115::identify() +{ +// startTimer(); + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + + uint16_t dataword { 0 }; + if ( !readWord(static_cast(REG::CONFIG), &dataword) ) return false; + if ( ( (dataword & 0x8000) == 0 ) && (dataword & 0x0100) ) return false; + uint16_t dataword2 { 0 }; + // try to read at addr conf_reg+4 and compare with the previously read config register + // both should be identical since only the 2 LSBs of the pointer register are evaluated by the ADS1115 + if ( !readWord(static_cast(REG::CONFIG) | 0x04, &dataword2) ) return false; + if ( dataword != dataword2 ) return false; + + return true; +} + +double ADS1115::getVoltage(unsigned int channel) +{ + double voltage = 0.; + getVoltage(channel, voltage); + return voltage; +} + +void ADS1115::getVoltage(unsigned int channel, double& voltage) +{ + int16_t adc = 0; + getVoltage(channel, adc, voltage); +} + +void ADS1115::getVoltage(unsigned int channel, int16_t& adc, double& voltage) +{ + Sample sample = getSample(channel); + adc = sample.value; + voltage = sample.voltage; +} + +void ADS1115::setAGC(bool state) +{ + fAGC[0] = fAGC[1] = fAGC[2] = fAGC[3] = state; +} + +void ADS1115::setAGC(uint8_t channel, bool state) +{ + if ( channel > 3 ) return; + fAGC[channel] = state; +} + +bool ADS1115::getAGC(uint8_t channel) const +{ + return fAGC[channel & 0x03]; +} diff --git a/daemon/src/hardware/i2c/bme280.cpp b/daemon/src/hardware/i2c/bme280.cpp new file mode 100644 index 00000000..ac89d54a --- /dev/null +++ b/daemon/src/hardware/i2c/bme280.cpp @@ -0,0 +1,537 @@ +#include "hardware/i2c/bme280.h" +#include +#include +#include +/* +*BME280 HumidityTemperaturePressuresensor +* +*/ +bool BME280::init() +{ + fTitle = "BME280"; + + uint8_t val = 0; + fCalibrationValid = false; + + // chip id reg + int n = readReg(0xd0, &val, 1); // Read the id register into readBuf + // printf( "%d bytes read\n",n); + + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("chip id: 0x%x \n", val); + } + + if (val == 0x60) + readCalibParameters(); + return (val == 0x60); +} + +bool BME280::status() +{ + uint8_t status = 0; + int n = readReg(0xf3, &status, 1); + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + } + status &= 0b1001; + return (status == 0 && n == 1); +} + +uint8_t BME280::readConfig() +{ + uint8_t config[1]; + config[0] = 0; + int n = readReg(0xf5, config, 1); + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + return (unsigned int)config[0]; +} + +uint8_t BME280::read_CtrlMeasReg() +{ + uint8_t ctrl_meas[1]; + ctrl_meas[0] = 0; + int n = readReg(0xf4, ctrl_meas, 1); + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + return (uint8_t)ctrl_meas[0]; +} + +bool BME280::writeConfig(uint8_t config) +{ + uint8_t buf[1]; + // check for bit 1 because datasheet says: "do not change" + int n = readReg(0xf5, buf, 1); + buf[0] = buf[0] & 0b10; + config = config & 0b11111101; + buf[0] = buf[0] | config; + n += writeReg(0xf5, buf, 1); + if (fDebugLevel > 1) + printf("%d bytes written\n", n); + return (n == 2); +} + +bool BME280::write_CtrlMeasReg(uint8_t config) +{ + uint8_t buf[1]; + buf[0] = config; + int n = writeReg(0xf4, buf, 1); + if (fDebugLevel > 1) + printf("%d bytes written\n", n); + return (n == 1); +} + +bool BME280::setMode(uint8_t mode) +{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 + if (mode > 0b11) { + if (fDebugLevel > 1) + printf("mode > 3 error\n"); + return false; + } + uint8_t buf[1]; + int n = readReg(0xf4, buf, 1); + uint8_t ctrl_meas = buf[0]; + ctrl_meas = ctrl_meas & 0xfc; + ctrl_meas = ctrl_meas | mode; + buf[0] = ctrl_meas; + n += writeReg(0xf4, buf, 1); + return (n == 2); +} + +bool BME280::setTSamplingMode(uint8_t mode) +{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 + if (mode > 0b111) { + if (fDebugLevel > 1) + printf("mode > 3 error\n"); + return false; + } + uint8_t buf[1]; + int n = readReg(0xf4, buf, 1); + uint8_t ctrl_meas = buf[0]; + ctrl_meas = ctrl_meas & 0b00011111; + mode = mode << 5; + ctrl_meas = ctrl_meas | mode; + buf[0] = ctrl_meas; + n += writeReg(0xf4, buf, 1); + return (n == 2); +} + +bool BME280::setPSamplingMode(uint8_t mode) +{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 + if (mode > 0b111) { + if (fDebugLevel > 1) + printf("mode > 3 error\n"); + return false; + } + uint8_t buf[1]; + int n = readReg(0xf4, buf, 1); + uint8_t ctrl_meas = buf[0]; + ctrl_meas = ctrl_meas & 0b11100011; + mode = mode << 2; + ctrl_meas = ctrl_meas | mode; + buf[0] = ctrl_meas; + n += writeReg(0xf4, buf, 1); + return (n == 2); +} + +bool BME280::setHSamplingMode(uint8_t mode) +{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 + if (mode > 0b111) { + if (fDebugLevel > 1) + printf("mode > 3 error\n"); + return false; + } + uint8_t buf[1]; + int n = readReg(0xf2, buf, 1); + uint8_t ctrl_meas = buf[0]; + ctrl_meas = ctrl_meas & 0b11111000; + ctrl_meas = ctrl_meas | mode; + buf[0] = ctrl_meas; + n += writeReg(0xf2, buf, 1); + n += readReg(0xf4, buf, 1); + writeReg(0xf4, buf, 1); + return (n == 2); +} + +bool BME280::setDefaultSettings() +{ + uint8_t buf[1]; + readReg(0xf2, buf, 1); + buf[0] &= 0b11111000; + buf[0] |= 0b010; + writeReg(0xf2, buf, 1); // enabling humidity measurement (oversampling x2) + write_CtrlMeasReg(0b01001000); // enabling temperature and pressure measurement (oversampling x2), set sleep mode + return true; +} + +bool BME280::measure() +{ + // calculate t_max [ms] from settings: + uint8_t readBuf[1]; + double t_max = 1.25; + readReg(0xf2, readBuf, 1); + unsigned int val = readBuf[0] & 0b111; + if (fDebugLevel > 1) + printf("osrs_h: %u\n", val); + if (val > 5) + val = 5; + unsigned int add = 1; + if (val != 0) { + add = add << (val - 1); + t_max += 2.3 * (double)add + 0.575; + } + + readBuf[0] = 0; + add = 1; + readReg(0xf4, readBuf, 1); + val = readBuf[0] & 0b00011100; + val = val >> 2; + if (fDebugLevel > 1) + printf("osrs_p: %u\n", val); + if (val > 5) + val = 5; + if (val != 0) { + add = add << (val - 1); + t_max += 2.3 * (double)add + 0.575; + } + + add = 1; + val = readBuf[0] & 0b11100000; + val = val >> 5; + if (fDebugLevel > 1) + printf("osrs_t: %u\n", val); + if (val > 5) + val = 5; + if (val != 0) { + add = add << (val - 1); + t_max += 2.3 * (double)add; + } + // t_max corresponds to the maximum time that a measurement can take with given + // settings read out from registers f2 and f4 + + // wait while status not ready: + for (int i = 0; i < 10; i++) { + usleep(5000); + } + setMode(0x2); // set mode to "forced measurement" (single-shot) + // it will now perform a measurement as configured in 0xf4, 0xf2 and 0xf5 registers + + // wait at least 112.8 ms for a full accuracy measurement of all 3 values + // or ask for status to be 0 + usleep((int)(t_max * 1000 + 0.5) + 200); + if (fDebugLevel > 1) + printf("measurement took about %.1f ms\n", t_max + 0.2); + for (int i = 0; i < 10; i++) { + if (status()) { + break; + } + usleep(5000); + if (i == 9) { + return false; + } + } + return true; +} + +int32_t BME280::readUT() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + uint32_t val; // Stores the 20 bit value of our ADC conversion + + if (!measure()) { + std::cerr << "error: measurement invalid"; + return INT32_MIN; + } + + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + + // adc reg + int n = readReg(0xfa, readBuf, 3); // Read the config register into readBuf + if (fDebugLevel > 1) + printf("%d bytes read: 0x%02x 0x%02x 0x%02x\n", n, readBuf[0], readBuf[1], readBuf[2]); + + val = ((uint32_t)readBuf[0]) << 12; // <-------///// should the lower 4 bits or the higher 4 bits of the 24 bits of registers be left 0 ??? + val |= ((uint32_t)readBuf[1]) << 4; // (look datasheet page 25) + val |= ((uint32_t)readBuf[2]) >> 4; + + return (int32_t)val; +} + +int32_t BME280::readUP() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + uint32_t val; // Stores the 20 bit value of our ADC conversion + + if (!measure()) { + std::cerr << "error: measurement invalid"; + return INT32_MIN; + } + + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + + // adc reg + int n = readReg(0xf7, readBuf, 3); // Read the config register into readBuf + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + + val = ((uint32_t)readBuf[0]) << 12; + val |= ((uint32_t)readBuf[1]) << 4; + val |= ((uint32_t)readBuf[2]) >> 4; + + return (int32_t)val; +} + +int32_t BME280::readUH() +{ + uint8_t readBuf[2]; + uint16_t val; + + if (!measure()) { + std::cerr << "error: measurement invalid"; + return INT32_MIN; + } + + readBuf[0] = 0; + readBuf[1] = 0; + + // adc reg + int n = readReg(0xfd, readBuf, 2); // Read the config register into readBuf + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + + val = ((uint32_t)readBuf[0]) << 8; + val |= ((uint32_t)readBuf[1]); // (look datasheet page 25) + + return (int32_t)val; +} + +TPH BME280::readTPCU() +{ + uint8_t readBuf[8]; + for (int i = 0; i < 8; i++) { + readBuf[i] = 0; + } + + TPH val; + if (!measure()) { + std::cerr << "error: measurement invalid"; + val.adc_P = INT32_MIN; + val.adc_T = INT32_MIN; + val.adc_H = INT32_MIN; + return val; + } + + int n = readReg(0xf7, readBuf, 8); // read T, P and H registers; + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + uint32_t adc_P = ((uint32_t)readBuf[0]) << 12; + adc_P |= ((uint32_t)readBuf[1]) << 4; + adc_P |= ((uint32_t)readBuf[2]) >> 4; + uint32_t adc_T = ((uint32_t)readBuf[3]) << 12; + adc_T |= ((uint32_t)readBuf[4]) << 4; + adc_T |= ((uint32_t)readBuf[5]) >> 4; + uint32_t adc_H = ((uint32_t)readBuf[6]) << 8; + adc_H |= ((uint32_t)readBuf[7]); // (look datasheet page 25) + + val.adc_P = (int32_t)adc_P; + val.adc_T = (int32_t)adc_T; + val.adc_H = (int32_t)adc_H; + return val; +} + +bool BME280::softReset() +{ + uint8_t resetWord[1]; + resetWord[0] = 0xb6; + int val = writeReg(0xe0, resetWord, 1); + return (val == 1); +} + +uint16_t BME280::getCalibParameter(unsigned int param) const +{ + if (param < 18) + return fCalibParameters[param]; + return 0xffff; +} + +void BME280::readCalibParameters() +{ + uint8_t readBuf[32]; + uint8_t readBufPart1[26]; + uint8_t readBufPart2[7]; + // register address first byte eeprom + int n = readReg(0x88, readBufPart1, 26); // Read the 26 eeprom word values into readBuf + n = n + readReg(0xe1, readBufPart2, 7); // from two different locations + + for (int i = 0; i < 24; i++) { + readBuf[i] = readBufPart1[i]; + } + readBuf[24] = readBufPart1[25]; + for (int i = 0; i < 7; i++) { + readBuf[i + 25] = readBufPart2[i]; + } + for (int i = 0; i < 32; i++) { + if (fDebugLevel > 1) { + printf("readBuf %d\n", n); + } + } + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + } + if (fDebugLevel > 1) { + printf("BME280 eeprom calib data:\n"); + } + + bool ok = true; + for (int i = 0; i < 12; i++) { + fCalibParameters[i] = ((uint16_t)readBuf[2 * i]) | (((uint16_t)readBuf[2 * i + 1]) << 8); // 2x 8-Bit ergibt 16-Bit Wort + if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) + ok = false; + if (fDebugLevel > 1) + printf("calib%d: %d \n", i, fCalibParameters[i]); + } + fCalibParameters[12] = (uint16_t)readBuf[24]; + if (fDebugLevel > 1) + printf("calib%d: %d \n", 12, fCalibParameters[12]); + fCalibParameters[13] = ((uint16_t)readBuf[25]) | (((uint16_t)readBuf[26]) << 8); + if (fDebugLevel > 1) + printf("calib%d: %d \n", 13, fCalibParameters[13]); + fCalibParameters[14] = (uint16_t)readBuf[27]; + if (fDebugLevel > 1) + printf("calib%d: %d \n", 14, fCalibParameters[14]); + fCalibParameters[15] = (((uint16_t)readBuf[28]) << 4) | (((uint16_t)readBuf[29]) & 0b1111); + if (fDebugLevel > 1) + printf("calib%d: %d \n", 15, fCalibParameters[15]); + fCalibParameters[16] = (((uint16_t)readBuf[29] & 0xf0) >> 4) | (((uint16_t)readBuf[30]) << 4); + if (fDebugLevel > 1) + printf("calib%d: %d \n", 16, fCalibParameters[16]); + fCalibParameters[17] = (uint16_t)readBuf[31]; + if (fDebugLevel > 1) + printf("calib%d: %d \n", 17, fCalibParameters[17]); + + if (fDebugLevel > 1) { + if (ok) { + printf("calib data is valid.\n"); + } else { + printf("calib data NOT valid!\n"); + } + } + fCalibrationValid = ok; + setDefaultSettings(); +} + +TPH BME280::getTPHValues() +{ + TPH vals = readTPCU(); + vals.T = getTemperature(vals.adc_T); + vals.P = getPressure(vals.adc_P); + vals.H = getHumidity(vals.adc_H); + return vals; +} + +double BME280::getTemperature(int32_t adc_T) +{ + if (!fCalibrationValid) + return -999.; + int32_t dig_T1 = (int32_t)fCalibParameters[0]; + int32_t dig_T2 = (int32_t)((int16_t)fCalibParameters[1]); + int32_t dig_T3 = (int32_t)((int16_t)fCalibParameters[2]); + int32_t X1 = (((adc_T >> 3) - (dig_T1 << 1)) * dig_T2) >> 11; + int32_t X2 = (((((adc_T >> 4) - dig_T1) * ((adc_T >> 4) - dig_T1)) >> 12) * dig_T3) >> 14; + fT_fine = X1 + X2; + int32_t t = (fT_fine * 5 + 128) >> 8; + double T = t / 100.0; + if (fDebugLevel > 1) { + printf("adc_T=%d\n", adc_T); + printf("X1=%d\n", X1); + printf("X2=%d\n", X2); + printf("t_fine=%d\n", fT_fine); + printf("temp=%d\n", t); + } + return T; +} + +double BME280::getHumidity(int32_t adc_H) +{ // please only do this if "getTemperature()" has been executed before + return getHumidity(adc_H, fT_fine); +} +double BME280::getHumidity(int32_t adc_H, int32_t t_fine) +{ + if (!fCalibrationValid) + return -999.; + if (t_fine == 0) + return -999.; + int32_t dig_H1 = (int32_t)fCalibParameters[12]; + int32_t dig_H2 = (int32_t)((int16_t)fCalibParameters[13]); + int32_t dig_H3 = (int32_t)fCalibParameters[14]; + int32_t dig_H4 = (int32_t)((int16_t)fCalibParameters[15]); + int32_t dig_H5 = (int32_t)((int16_t)fCalibParameters[16]); + int32_t dig_H6 = (int32_t)((int8_t)((uint8_t)fCalibParameters[17])); + int32_t X1 = 0; + X1 = (t_fine - ((int32_t)76800)); + X1 = (((((adc_H << 14) - (dig_H4 << 20) - (dig_H5 * X1)) + ((int32_t)16384)) >> 15) * (((((((X1 * dig_H6) >> 10) * (((X1 * dig_H3) >> 11) + ((int32_t)32768))) >> 10) + ((int32_t)2097152)) * dig_H2 + 8192) >> 14)); + X1 = (X1 - (((((X1 >> 15) * (X1 >> 15)) >> 7) * dig_H1) >> 4)); + X1 = (X1 < 0 ? 0 : X1); + X1 = (X1 > 419430400 ? 419430400 : X1); + uint32_t h = (uint32_t)(X1 >> 12); + double H = h / 1024.0; + if (fDebugLevel > 1) { + printf("adc_H=%d\n", adc_H); + printf("X1=%d\n", X1); + printf("t_fine=%d\n", t_fine); + printf("Humidity=%u\n", h); + } + return H; +} + +double BME280::getPressure(signed int adc_P) +{ + return getPressure(adc_P, fT_fine); +} +double BME280::getPressure(signed int adc_P, signed int t_fine) +{ + if (!fCalibrationValid) + return -999.0; + if (fT_fine == 0) + return -999.0; + uint16_t dig_P1 = fCalibParameters[3]; + int16_t dig_P2 = (int16_t)fCalibParameters[4]; + int16_t dig_P3 = (int16_t)fCalibParameters[5]; + int16_t dig_P4 = (int16_t)fCalibParameters[6]; + int16_t dig_P5 = (int16_t)fCalibParameters[7]; + int16_t dig_P6 = (int16_t)fCalibParameters[8]; + int16_t dig_P7 = (int16_t)fCalibParameters[9]; + int16_t dig_P8 = (int16_t)fCalibParameters[10]; + int16_t dig_P9 = (int16_t)fCalibParameters[11]; + + int64_t X1, X2, p; + X1 = ((int64_t)t_fine) - 128000; + X2 = X1 * X1 * (int64_t)dig_P6; + X2 = X2 + ((X1 * (int64_t)dig_P5) << 17); + X2 = X2 + (((int64_t)dig_P4) << 35); + X1 = ((X1 * X1 * (int64_t)dig_P3) >> 8) + ((X1 * (int64_t)dig_P2) << 12); + X1 = (((((int64_t)1) << 47) + X1)) * ((int64_t)dig_P1) >> 33; + if (X1 == 0) { + return 0; // avoid exception caused by division by zero + } + p = 1048576 - adc_P; + p = (((p << 31) - X2) * 3125) / X1; + X1 = (((int64_t)dig_P9) * (p >> 13) * (p >> 13)) >> 25; + X2 = (((int64_t)dig_P8) * p) >> 19; + p = ((p + X1 + X2) >> 8) + (((int64_t)dig_P7) << 4); + + double P = ((uint32_t)p) / 256.; + if (fDebugLevel > 1) { + printf("adc_P=%d\n", adc_P); + printf("X1=%lld\n", X1); + printf("X2=%lld\n", X2); + printf("p=%lld\n", p); + printf("P=%.3f\n", P); + } + return P; +} diff --git a/daemon/src/hardware/i2c/bmp180.cpp b/daemon/src/hardware/i2c/bmp180.cpp new file mode 100644 index 00000000..a3e00c58 --- /dev/null +++ b/daemon/src/hardware/i2c/bmp180.cpp @@ -0,0 +1,207 @@ +#include "hardware/i2c/bmp180.h" +#include +#include + +/* +* BMP180 Pressure Sensor +*/ + +bool BMP180::init() +{ + uint8_t val = 0; + + fCalibrationValid = false; + + // chip id reg + int n = readReg(0xd0, &val, 1); // Read the id register into readBuf + + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("chip id: 0x%x \n", val); + } + if (val == 0x55) + readCalibParameters(); + return (val == 0x55); +} + +unsigned int BMP180::readUT() +{ + uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device + unsigned int val; // Stores the 16 bit value of our ADC conversion + + // start temp measurement: CR -> 0x2e + uint8_t cr_val = 0x2e; + // register address control reg + int n = writeReg(0xf4, &cr_val, 1); + + // wait at least 4.5 ms + usleep(4500); + + readBuf[0] = 0; + readBuf[1] = 0; + + // adc reg + n = readReg(0xf6, readBuf, 2); // Read the config register into readBuf + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + + val = (readBuf[0]) << 8 | readBuf[1]; + + return val; +} + +unsigned int BMP180::readUP(uint8_t oss) +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + unsigned int val; // Stores the 16 bit value of our ADC conversion + static const int delay[4] = { 4500, 7500, 13500, 25500 }; + + // start pressure measurement: CR -> 0x34 | oss<<6 + uint8_t cr_val = 0x34 | (oss & 0x03) << 6; + // register address control reg + int n = writeReg(0xf4, &cr_val, 1); + usleep(delay[oss & 0x03]); + + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + + // adc reg + n = readReg(0xf6, readBuf, 3); // Read the conversion result into readBuf + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + + val = (readBuf[0] << 16 | readBuf[1] << 8 | readBuf[2]) >> (8 - (oss & 0x03)); + + return val; +} + +signed int BMP180::getCalibParameter(unsigned int param) const +{ + if (param < 11) + return fCalibParameters[param]; + return 0xffff; +} + +void BMP180::readCalibParameters() +{ + uint8_t readBuf[22]; + // register address first byte eeprom + int n = readReg(0xaa, readBuf, 22); // Read the 11 eeprom word values into readBuf + if (fDebugLevel > 1) + printf("%d bytes read\n", n); + + if (fDebugLevel > 1) + printf("BMP180 eeprom calib data:\n"); + + bool ok = true; + for (int i = 0; i < 11; i++) { + if (i > 2 && i < 6) + fCalibParameters[i] = (uint16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); + else + fCalibParameters[i] = (int16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); + if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) + ok = false; + if (fDebugLevel > 1) + printf("calib%d: %d \n", i, fCalibParameters[i]); + } + if (fDebugLevel > 1) { + if (ok) + printf("calib data is valid.\n"); + else + printf("calib data NOT valid!\n"); + } + + fCalibrationValid = ok; +} + +double BMP180::getTemperature() +{ + if (!fCalibrationValid) + return -999.; + signed int UT = readUT(); + signed int X1 = ((UT - fCalibParameters[5]) * fCalibParameters[4]) >> 15; + signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); + signed int B5 = X1 + X2; + double T = (B5 + 8) / 160.; + if (fDebugLevel > 1) { + printf("UT=%d\n", UT); + printf("X1=%d\n", X1); + printf("X2=%d\n", X2); + printf("B5=%d\n", B5); + printf("Temp=%f\n", T); + } + return T; +} + +double BMP180::getPressure(uint8_t oss) +{ + if (!fCalibrationValid) + return 0.; + signed int UT = readUT(); + if (fDebugLevel > 1) + printf("UT=%d\n", UT); + signed int UP = readUP(oss); + if (fDebugLevel > 1) + printf("UP=%d\n", UP); + signed int X1 = ((UT - fCalibParameters[5]) * fCalibParameters[4]) >> 15; + signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); + signed int B5 = X1 + X2; + signed int B6 = B5 - 4000; + if (fDebugLevel > 1) + printf("B6=%d\n", B6); + X1 = (fCalibParameters[7] * ((B6 * B6) >> 12)) >> 11; + if (fDebugLevel > 1) + printf("X1=%d\n", X1); + X2 = (fCalibParameters[1] * B6) >> 11; + if (fDebugLevel > 1) + printf("X2=%d\n", X2); + signed int X3 = X1 + X2; + signed int B3 = ((fCalibParameters[0] * 4 + X3) << (oss & 0x03)) + 2; + B3 = B3 / 4; + if (fDebugLevel > 1) + printf("B3=%d\n", B3); + X1 = (fCalibParameters[2] * B6) >> 13; + if (fDebugLevel > 1) + printf("X1=%d\n", X1); + X2 = (fCalibParameters[6] * (B6 * B6) / 4096); + X2 = X2 >> 16; + if (fDebugLevel > 1) + printf("X2=%d\n", X2); + X3 = (X1 + X2 + 2) / 4; + if (fDebugLevel > 1) + printf("X3=%d\n", X3); + unsigned long B4 = (fCalibParameters[3] * (unsigned long)(X3 + 32768)) >> 15; + if (fDebugLevel > 1) + printf("B4=%ld\n", B4); + unsigned long B7 = ((unsigned long)UP - B3) * (50000 >> (oss & 0x03)); + if (fDebugLevel > 1) + printf("B7=%ld\n", B7); + int p = 0; + if (B7 < 0x80000000) + p = (B7 * 2) / B4; + else + p = (B7 / B4) * 2; + if (fDebugLevel > 1) + printf("p=%d\n", p); + + X1 = p >> 8; + if (fDebugLevel > 1) + printf("X1=%d\n", X1); + X1 = X1 * X1; + if (fDebugLevel > 1) + printf("X1=%d\n", X1); + X1 = (X1 * 3038) >> 16; + if (fDebugLevel > 1) + printf("X1=%d\n", X1); + X2 = (-7357 * p) >> 16; + if (fDebugLevel > 1) + printf("X2=%d\n", X2); + p = 16 * p + (X1 + X2 + 3791); + double press = p / 16.; + + if (fDebugLevel > 1) { + printf("pressure=%f\n", press); + } + return press; +} diff --git a/daemon/src/hardware/i2c/eeprom24aa02.cpp b/daemon/src/hardware/i2c/eeprom24aa02.cpp new file mode 100644 index 00000000..10534f48 --- /dev/null +++ b/daemon/src/hardware/i2c/eeprom24aa02.cpp @@ -0,0 +1,104 @@ +#include "hardware/i2c/eeprom24aa02.h" +#include +#include +#include +#include + +/* +* 24AA02 EEPROM +*/ + +uint8_t EEPROM24AA02::readByte(uint8_t addr) +{ + uint8_t val = 0; + startTimer(); + readReg(addr, &val, 1); // Read the data at address location + stopTimer(); + return val; +} + +bool EEPROM24AA02::readByte(uint8_t addr, uint8_t* value) +{ + startTimer(); + int n = readReg(addr, value, 1); // Read the data at address location + stopTimer(); + return (n == 1); +} + +void EEPROM24AA02::writeByte(uint8_t addr, uint8_t data) +{ + uint8_t writeBuf[2]; // Buffer to store the 2 bytes that we write to the I2C device + + writeBuf[0] = addr; // address of data byte + writeBuf[1] = data; // data byte + + startTimer(); + + // Write address first + write(writeBuf, 2); + + usleep(5000); + stopTimer(); +} + +bool EEPROM24AA02::writeBytes(uint8_t addr, uint16_t length, uint8_t* data) +{ + static const uint8_t PAGESIZE = 8; + bool success = true; + startTimer(); + for (uint16_t i = 0; i < length;) { + uint8_t currAddr = addr + i; + // determine, how many bytes left on current page + uint8_t pageRemainder = PAGESIZE - currAddr % PAGESIZE; + if (currAddr + pageRemainder >= length) + pageRemainder = length - currAddr; + int n = writeReg(currAddr, &data[i], pageRemainder); + std::this_thread::sleep_for( std::chrono::microseconds( 5000 ) ); + i += pageRemainder; + success = success && (n == pageRemainder); + } + stopTimer(); + return success; +} + +int16_t EEPROM24AA02::readBytes(uint8_t regAddr, uint16_t length, uint8_t* data) +{ + return i2cDevice::readBytes( regAddr, length, data ); +} + +bool EEPROM24AA02::identify() +{ + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + + const unsigned int N { 256 }; + uint8_t buf[N+1]; +// std::cout << " attempt 1: offs=0, len="< +#include +#include + +/* +* HMC5883 3 axis magnetic field sensor (Honeywell) +*/ + +const double HMC5883::GAIN[8] = { 0.73, 0.92, 1.22, 1.52, 2.27, 2.56, 3.03, 4.35 }; + +bool HMC5883::init() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + + // init value 0 for gain + fGain = 0; + + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + + int n = readReg(0x0a, readBuf, 3); // Read the id registers into readBuf + + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("id reg A: 0x%x \n", readBuf[0]); + printf("id reg B: 0x%x \n", readBuf[1]); + printf("id reg C: 0x%x \n", readBuf[2]); + } + + if (readBuf[0] != 0x48) + return false; + + // addr config reg A (CRA) + // 8 average, 15 Hz, single measurement: 0x70 + uint8_t cmd = 0x70; + n = writeReg(0x00, &cmd, 1); + + setGain(fGain); + return true; +} + +void HMC5883::setGain(uint8_t gain) +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + + // set CRB + writeBuf[0] = 0x01; // addr config reg B (CRB) + writeBuf[1] = (gain & 0x07) << 5; // gain=xx + write(writeBuf, 2); + fGain = gain & 0x07; +} + +uint8_t HMC5883::readGain() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + + int n = readReg(0x01, readBuf, 1); // Read the config register into readBuf + + if (n != 1) + return 0; + uint8_t gain = readBuf[0] >> 5; + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("gain (read from device): 0x%x\n", gain); + } + return gain; +} + +bool HMC5883::readRDYBit() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + + // addr status reg (SR) + int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf + + if (n != 1) + return 0; + uint8_t sr = readBuf[0]; + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("status (read from device): 0x%x\n", sr); + } + if ((sr & 0x01) == 0x01) + return true; + return false; +} + +bool HMC5883::readLockBit() +{ + uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device + + // addr status reg (SR) + int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf + + if (n != 1) + return 0; + uint8_t sr = readBuf[0]; + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("status (read from device): 0x%x\n", sr); + } + if ((sr & 0x02) == 0x02) + return true; + return false; +} + +bool HMC5883::getXYZRawValues(int& x, int& y, int& z) +{ + uint8_t readBuf[6]; + + uint8_t cmd = 0x01; // start single measurement + int n = writeReg(0x02, &cmd, 1); // addr mode reg (MR) + usleep(6000); + + // Read the 3 data registers into readBuf starting from addr 0x03 + n = readReg(0x03, readBuf, 6); + int16_t xreg = (int16_t)(readBuf[0] << 8 | readBuf[1]); + int16_t yreg = (int16_t)(readBuf[2] << 8 | readBuf[3]); + int16_t zreg = (int16_t)(readBuf[4] << 8 | readBuf[5]); + + if (fDebugLevel > 1) { + printf("%d bytes read\n", n); + printf("xreg: %d\n", xreg); + printf("yreg: %d\n", yreg); + printf("zreg: %d\n", zreg); + } + + x = xreg; + y = yreg; + z = zreg; + + if (xreg >= -2048 && xreg < 2048 && yreg >= -2048 && yreg < 2048 && zreg >= -2048 && zreg < 2048) + return true; + + return false; +} + +bool HMC5883::getXYZMagneticFields(double& x, double& y, double& z) +{ + int xreg, yreg, zreg; + bool ok = getXYZRawValues(xreg, yreg, zreg); + double lsbgain = GAIN[fGain]; + x = lsbgain * xreg / 1000.; + y = lsbgain * yreg / 1000.; + z = lsbgain * zreg / 1000.; + + if (fDebugLevel > 1) { + printf("x field: %f G\n", x); + printf("y field: %f G\n", y); + printf("z field: %f G\n", z); + } + + return ok; +} + +bool HMC5883::calibrate(int& x, int& y, int& z) +{ + + // addr config reg A (CRA) + // 8 average, 15 Hz, positive self test measurement: 0x71 + uint8_t cmd = 0x71; + /*int n=*/writeReg(0x00, &cmd, 1); + + uint8_t oldGain = fGain; + setGain(5); + + int xr, yr, zr; + // one dummy measurement + getXYZRawValues(xr, yr, zr); + // measurement + getXYZRawValues(xr, yr, zr); + + x = xr; + y = yr; + z = zr; + + setGain(oldGain); + // one dummy measurement + getXYZRawValues(xr, yr, zr); + + // set normal measurement mode in CRA again + cmd = 0x70; + /*n=*/writeReg(0x00, &cmd, 1); + return true; +} diff --git a/daemon/src/hardware/i2c/i2cdevice.cpp b/daemon/src/hardware/i2c/i2cdevice.cpp new file mode 100644 index 00000000..5a5acfd7 --- /dev/null +++ b/daemon/src/hardware/i2c/i2cdevice.cpp @@ -0,0 +1,463 @@ +#include "hardware/i2c/i2cdevice.h" +#include +#include +#include // open +#include +#include // I2C bus definitions for linux like systems + +using namespace std; + +unsigned int i2cDevice::fNrDevices = 0; +unsigned long int i2cDevice::fGlobalNrBytesRead = 0; +unsigned long int i2cDevice::fGlobalNrBytesWritten = 0; +std::vector i2cDevice::fGlobalDeviceList; + +i2cDevice::i2cDevice() +{ + //opening the devicefile from the i2c driversection (open the device i2c) + //"/dev/i2c-0" or "../i2c-1" for linux system. In our case + fNrBytesRead = 0; + fNrBytesWritten = 0; + fAddress = 0; + fDebugLevel = DEFAULT_DEBUG_LEVEL; + fHandle = open("/dev/i2c-1", O_RDWR); + if (fHandle > 0) { + fNrDevices++; + fGlobalDeviceList.push_back(this); + } else + fMode = MODE_FAILED; +} + +i2cDevice::i2cDevice(const char* busAddress) +{ + fNrBytesRead = 0; + fNrBytesWritten = 0; + fDebugLevel = DEFAULT_DEBUG_LEVEL; + //opening the devicefile from the i2c driversection (open the device i2c) + //"/dev/i2c-0" or "../i2c-1" for linux system. In our case + fHandle = open(busAddress, O_RDWR); + if (fHandle > 0) { + fNrDevices++; + fGlobalDeviceList.push_back(this); + } else + fMode = MODE_FAILED; +} + +i2cDevice::i2cDevice(uint8_t slaveAddress) + : fAddress(slaveAddress) +{ + fNrBytesRead = 0; + fNrBytesWritten = 0; + fDebugLevel = DEFAULT_DEBUG_LEVEL; + //opening the devicefile from the i2c driversection (open the device i2c) + //"/dev/i2c-0" or "../i2c-1" for linux system. In our case + fHandle = open("/dev/i2c-1", O_RDWR); + if (fHandle > 0) { + //ioctl(fHandle, I2C_SLAVE, fAddress); + setAddress(slaveAddress); + fNrDevices++; + fGlobalDeviceList.push_back(this); + } else + fMode = MODE_FAILED; +} + +i2cDevice::i2cDevice(const char* busAddress, uint8_t slaveAddress) + : fAddress(slaveAddress) +{ + fNrBytesRead = 0; + fNrBytesWritten = 0; + fDebugLevel = DEFAULT_DEBUG_LEVEL; + //opening the devicefile from the i2c driversection (open the device i2c) + //"/dev/i2c-0" or "../i2c-1" for linux system. In our case + fHandle = open(busAddress, O_RDWR); + if (fHandle > 0) { + setAddress(slaveAddress); + fNrDevices++; + fGlobalDeviceList.push_back(this); + } else + fMode = MODE_FAILED; +} + +i2cDevice::~i2cDevice() +{ + //destructor of the opening part from above + if (fHandle > 0) { + fNrDevices--; + close(fHandle); + } + std::vector::iterator it; + it = std::find(fGlobalDeviceList.begin(), fGlobalDeviceList.end(), this); + if (it != fGlobalDeviceList.end()) + fGlobalDeviceList.erase(it); +} + +void i2cDevice::getCapabilities() +{ + unsigned long funcs; + int res = ioctl(fHandle, I2C_FUNCS, &funcs); + if (res < 0) + cerr << "error retrieving function capabilities from I2C interface." << endl; + else { + cout << "I2C adapter capabilities: 0x" << hex << funcs << dec << endl; + } +} + +bool i2cDevice::devicePresent() +{ + uint8_t dummy { 0 }; + return (read(&dummy, 1) == 1); +} + +void i2cDevice::setAddress(uint8_t address) +{ //pointer to our device on the i2c-bus + fAddress = address; + int res = ioctl(fHandle, I2C_SLAVE, fAddress); //i.g. Specify the address of the I2C Slave to communicate with + if (res < 0) { + res = ioctl(fHandle, I2C_SLAVE_FORCE, fAddress); + if (res < 0) { + fMode = MODE_FAILED; + fIOErrors++; + } else + fMode = MODE_FORCE; + } else { + fMode = MODE_NORMAL; + } +} + +void i2cDevice::lock( bool locked ) +{ + if (locked) + fMode |= MODE_LOCKED; + else + fMode &= ~MODE_LOCKED; +} + +bool i2cDevice::identify() +{ + // this function should be reimplemented in derived classes + // if it is not reimplemented it returns false, i.e. the abstract i2cDevice can never be identified positively + // reimplement this method for specific devices and use whatever is needed to get an unanimous identification + // return true if device is identified correctly + return false; +} + +int i2cDevice::read(uint8_t* buf, int nBytes) +{ //defines a function with a pointer buf as buffer and the number of bytes which + //we want to read. + if (fHandle <= 0 || (fMode & MODE_LOCKED)) + return 0; + //std::lock_guard lock(fMutex); + int nread = ::read(fHandle, buf, nBytes); //"::" declares that the functions does not call itself again, but instead uses the system call + if (nread > 0) { + fNrBytesRead += nread; + fGlobalNrBytesRead += nread; + fMode &= ~((uint8_t)MODE_UNREACHABLE); + } else if (nread <= 0) { + fIOErrors++; + fMode |= MODE_UNREACHABLE; + } + return nread; +} + +int i2cDevice::write(uint8_t* buf, int nBytes) +{ + if (fHandle <= 0 || (fMode & MODE_LOCKED)) + return 0; + //std::lock_guard lock(fMutex); + int nwritten = ::write(fHandle, buf, nBytes); + if (nwritten > 0) { + fNrBytesWritten += nwritten; + fGlobalNrBytesWritten += nwritten; + fMode &= ~((uint8_t)MODE_UNREACHABLE); + } else if (nwritten <= 0) { + fIOErrors++; + fMode |= MODE_UNREACHABLE; + } + return nwritten; +} + +int i2cDevice::writeReg(uint8_t reg, uint8_t* buf, int nBytes) +{ + // the i2c_smbus_*_i2c_block_data functions are better but allow + // block sizes of up to 32 bytes only + //i2c_smbus_write_i2c_block_data(int file, reg, nBytes, buf); + + uint8_t writeBuf[nBytes + 1]; + + writeBuf[0] = reg; // first byte is register address + for (int i = 0; i < nBytes; i++) + writeBuf[i + 1] = buf[i]; + int n = write(writeBuf, nBytes + 1); + return n - 1; +} + +int i2cDevice::readReg(uint8_t reg, uint8_t* buf, int nBytes) +{ + std::lock_guard lock(fMutex); + int n = write(®, 1); + if (n != 1) + return -1; + n = read(buf, nBytes); + return n; +} + +/** Read a single bit from an 8-bit device register. +* @param regAddr Register regAddr to read from +* @param bitNum Bit position to read (0-7) +* @param data Container for single bit value +* @return Status of read operation (true = success) +*/ +int8_t i2cDevice::readBit(uint8_t regAddr, uint8_t bitNum, uint8_t* data) +{ + uint8_t b; + uint8_t count = readReg(regAddr, &b, 1); + *data = b & (1 << bitNum); + return count; +} + +/** Read multiple bits from an 8-bit device register. +* @param regAddr Register regAddr to read from +* @param bitStart First bit position to read (0-7) +* @param length Number of bits to read (not more than 8) +* @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) +* @return Status of read operation (true = success) +*/ +int8_t i2cDevice::readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t* data) +{ + // 01101001 read byte + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 010 masked + // -> 010 shifted + uint8_t count, b; + if ((count = readReg(regAddr, &b, 1)) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + b &= mask; + b >>= (bitStart - length + 1); + *data = b; + } + return count; +} + +/** Read single byte from an 8-bit device register. +* @param regAddr Register regAddr to read from +* @param data Container for byte value read from device +* @return Status of read operation (true = success) +*/ +bool i2cDevice::readByte(uint8_t regAddr, uint8_t* data) +{ + return (readBytes(regAddr, 1, data) == 1); +} + +/** Read multiple bytes from an 8-bit device register. +* @param regAddr First register regAddr to read from +* @param length Number of bytes to read +* @param data Buffer to store read data in +* @return Number of bytes read (-1 indicates failure) +*/ +int16_t i2cDevice::readBytes(uint8_t regAddr, uint16_t length, uint8_t* data) +{ + return readReg(regAddr, data, length); +} + +/** write a single bit in an 8-bit device register. +* @param regAddr Register regAddr to write to +* @param bitNum Bit position to write (0-7) +* @param data New bit value to write +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data) +{ + uint8_t b; + std::lock_guard lock(fMutex); + int n = readByte(regAddr, &b); + if (n != 1) + return false; + b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); + return writeByte(regAddr, b); +} + +/** Write multiple bits in an 8-bit device register. +* @param regAddr Register regAddr to write to +* @param bitStart First bit position to write (0-7) +* @param length Number of bits to write (not more than 8) +* @param data Right-aligned value to write +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) +{ + // 010 value to write + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 00011100 mask byte + // 10101111 original value (sample) + // 10100011 original & ~mask + // 10101011 masked | value + uint8_t b; + std::lock_guard lock(fMutex); + if (readByte(regAddr, &b) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + data <<= (bitStart - length + 1); // shift data into correct position + data &= mask; // zero all non-important bits in data + b &= ~(mask); // zero all important bits in existing byte + b |= data; // combine data with existing byte + return writeByte(regAddr, b); + } else { + return false; + } +} + +/** Write single byte to an 8-bit device register. +* @param regAddr Register address to write to +* @param data New byte value to write +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeByte(uint8_t regAddr, uint8_t data) +{ + return writeBytes(regAddr, 1, &data); +} + +/** Write multiple bytes to an 8-bit device register. +* @param devAddr I2C slave device address +* @param regAddr First register address to write to +* @param length Number of bytes to write +* @param data Buffer to copy new data from +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data) +{ + + int n = writeReg(regAddr, data, length); + return (n == length); +} + +/** Write multiple words to a 16-bit device register. +* @param regAddr First register address to write to +* @param length Number of words to write +* @param data Buffer to copy new data from +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeWords(uint8_t regAddr, uint16_t length, uint16_t* data) +{ + int8_t count = 0; + uint8_t buf[512]; + + // Should do potential byteswap and call writeBytes() really, but that + // messes with the callers buffer + + for (int i = 0; i < length; i++) { + buf[i * 2] = data[i] >> 8; + buf[i * 2 + 1] = data[i]; + } + + count = writeReg(regAddr, buf, length * 2); + if (count < 0) { + fprintf(stderr, "Failed to write device(%d): %s\n", count, ::strerror(errno)); + return (false); + } else if (count != length * 2) { + fprintf(stderr, "Short write to device, expected %d, got %d\n", length + 1, count); + return (false); + } + return true; +} + +/** Write single word to a 16-bit device register. +* @param regAddr Register address to write to +* @param data New word value to write +* @return Status of operation (true = success) +*/ +bool i2cDevice::writeWord(uint8_t regAddr, uint16_t data) +{ + return writeWords(regAddr, 1, &data); +} + +/** Read single word from a 16-bit device register. +* @param regAddr Register regAddr to read from +* @param data Container for word value read from device +* @return Status of read operation (true = success) +*/ +bool i2cDevice::readWord(uint8_t regAddr, uint16_t* data) +{ + return (readWords(regAddr, 1, data) == 1); +} + +/** Read single word. +* @param data Container for word value read from device +* @return Status of read operation (true = success) +*/ +bool i2cDevice::readWord(uint16_t* data) +{ + return (readWords(1, data) == 1); +} + +/** Read multiple words from a 16-bit device register. +* @param regAddr First register regAddr to read from +* @param length Number of words to read +* @param data Buffer to store read data in +* @return Number of words read (-1 indicates failure) +*/ +int16_t i2cDevice::readWords(uint8_t regAddr, uint16_t length, uint16_t* data) +{ + int16_t count = 0; + uint8_t buf[512]; + + count = readReg(regAddr, buf, length * 2); + if (count < 0) { + fprintf(stderr, "Failed to read device(%d): %s\n", count, ::strerror(errno)); + return -1; + } else if (count != length * 2) { + fprintf(stderr, "Short read from device, expected %d, got %d\n", length * 2, count); + return count/2; + } + + for (int i = 0; i < length; i++) { + data[i] = buf[i * 2] << 8; + data[i] |= buf[i * 2 + 1]; + } + + return count/2; +} + +/** Read multiple words. +* @param length Number of words to read +* @param data Buffer to store read data in +* @return Number of words read (-1 indicates failure) +*/ +int16_t i2cDevice::readWords(uint16_t length, uint16_t* data) +{ + int16_t count = 0; + uint8_t buf[512]; + + count = read(buf, length * 2); + if (count < 0) { + fprintf(stderr, "Failed to read device(%d): %s\n", count, ::strerror(errno)); + return -1; + } else if (count != length * 2) { + fprintf(stderr, "Short read from device, expected %d, got %d\n", length * 2, count); + return count/2; + } + + for (int i = 0; i < length; i++) { + data[i] = buf[i * 2] << 8; + data[i] |= buf[i * 2 + 1]; + } + + return count/2; +} + + +void i2cDevice::startTimer() +{ + gettimeofday(&fT1, NULL); +} + +void i2cDevice::stopTimer() +{ + gettimeofday(&fT2, NULL); + // compute and print the elapsed time in millisec + double elapsedTime = (fT2.tv_sec - fT1.tv_sec) * 1000.0; // sec to ms + elapsedTime += (fT2.tv_usec - fT1.tv_usec) / 1000.0; // us to ms + fLastTimeInterval = elapsedTime; + if (fDebugLevel > 1) + printf(" last transaction took: %6.2f ms\n", fLastTimeInterval); +} diff --git a/daemon/src/hardware/i2c/i2cutil.cpp b/daemon/src/hardware/i2c/i2cutil.cpp new file mode 100644 index 00000000..bd8d126d --- /dev/null +++ b/daemon/src/hardware/i2c/i2cutil.cpp @@ -0,0 +1,36 @@ +#include "hardware/i2c/i2cutil.h" +#include +#include + +I2cGeneralCall::I2cGeneralCall() +: i2cDevice( static_cast( 0x00 ) ) +{ + fTitle = "GeneralCall"; +} + +I2cGeneralCall::I2cGeneralCall(const char* busAddress) +: i2cDevice( busAddress, static_cast( 0x00 ) ) +{ + fTitle = "GeneralCall"; +} + +void I2cGeneralCall::resetDevices() +{ + I2cGeneralCall gc; + uint8_t data { 0x06 }; + gc.write( &data, 1 ); +} + +void I2cGeneralCall::wakeUp() +{ + I2cGeneralCall gc; + uint8_t data { 0x09 }; + gc.write( &data, 1 ); +} + +void I2cGeneralCall::softwareUpdate() +{ + I2cGeneralCall gc; + uint8_t data { 0x08 }; + gc.write( &data, 1 ); +} diff --git a/daemon/src/hardware/i2c/lm75.cpp b/daemon/src/hardware/i2c/lm75.cpp new file mode 100644 index 00000000..b28dc4b4 --- /dev/null +++ b/daemon/src/hardware/i2c/lm75.cpp @@ -0,0 +1,100 @@ +#include "hardware/i2c/lm75.h" +#include +#include +#include +/* +* LM75 Temperature Sensor +*/ +LM75::LM75() + : i2cDevice(0x4f) +{ + fTitle = fName = "LM75"; +} + +LM75::LM75(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) +{ + fTitle = fName = "LM75"; +} + +LM75::LM75(uint8_t slaveAddress) + : i2cDevice(slaveAddress) +{ + fTitle = fName = "LM75"; +} + +LM75::~LM75() +{ + +} + +int16_t LM75::readRaw() +{ + startTimer(); + + uint16_t dataword { 0 }; + // Read the temp register + if ( !readWord( static_cast(REG::TEMP), &dataword ) ) { + // there was an error + return INT16_MIN; + } + + int16_t val = static_cast( dataword ); +// val = ((int16_t)readBuf[0] << 8) | readBuf[1]; + fLastRawValue = val; + + stopTimer(); + + return val; +} + +float LM75::getTemperature() +{ + int16_t dataword = readRaw(); + float temp = static_cast( dataword >> 8 ); + temp += static_cast(dataword & 0xff)/256.; + fLastTemp = temp; + return temp; +} + +bool LM75::identify() +{ + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + uint16_t dataword { 0 }; + uint8_t conf_reg { 0 }; + // Read the config register + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) { + // there was an error + return false; + } + // datasheet: 3 MSBs of conf register "should be kept as zeroes" + if ( ( conf_reg >> 5 ) != 0 ) return false; + + // read temp register + if ( !readWord( static_cast(REG::TEMP), &dataword ) ) { + // there was an error + return false; + } + // the 5 LSBs should always read zero + if ( (dataword & 0x1f) != 0 ) return false; +// if ( ( (dataword & 0x1f) != 0 ) && ( dataword >> 5 ) == 0 ) return false; + + // read Thyst register + if ( !readWord( static_cast(REG::THYST), &dataword ) ) { + // there was an error + return false; + } + // the 7 MSBs should always read zero + if ( (dataword & 0x7f) != 0 ) return false; + + // read Tos register + if ( !readWord( static_cast(REG::TOS), &dataword ) ) { + // there was an error + return false; + } + // the 7 MSBs should always read zero + if ( (dataword & 0x7f) != 0 ) return false; + + return true; +} diff --git a/daemon/src/hardware/i2c/mcp4728.cpp b/daemon/src/hardware/i2c/mcp4728.cpp new file mode 100644 index 00000000..3fd30b57 --- /dev/null +++ b/daemon/src/hardware/i2c/mcp4728.cpp @@ -0,0 +1,304 @@ +#include "hardware/i2c/mcp4728.h" +#include +#include +#include +#include +#include + +/* +* MCP4728 4 ch 12 bit DAC +*/ +constexpr auto DataValidityTimeout { std::chrono::milliseconds( 100 ) }; + +bool MCP4728::setVoltage(unsigned int channel, float voltage) +{ + if ( voltage < 0 || channel > 3 ) { + return false; + } + return setVoltage( channel, voltage, false ); +} + +bool MCP4728::setVoltage(uint8_t channel, float voltage, bool toEEPROM) +{ + if ( voltage < 0 || channel > 3 ) { + return false; + } + CFG_GAIN gain = GAIN1; + // Vref=internal: Vout = (2.048V * Dn) / 4096 * Gx + // Vref=Vdd: Vout = (Vdd * Dn) / 4096 + uint16_t value { 0x0000 }; + if ( fChannelSetting[channel].vref == VREF_2V ) { + value = std::lround( voltage * 2000 ); + if ( value > 0xfff ) { + value = value >> 1; + gain = GAIN2; + } + } else { + value = std::lround( voltage * 4096 / fVddRefVoltage ); + } + + if (value > 0xfff) { + // error: desired voltage is out of range + return false; + } + return setValue(channel, value, gain, toEEPROM); +} + +bool MCP4728::setValue(uint8_t channel, uint16_t value, CFG_GAIN gain, bool toEEPROM) +{ + if (value > 0xfff) { + value = 0xfff; + // error: number of bits exceeding 12 + return false; + } + DacChannel dacChannel { fChannelSetting[channel] }; + if ( toEEPROM ) { + dacChannel = fChannelSettingEep[channel]; + dacChannel.eeprom = true; + } + dacChannel.value = value; + dacChannel.gain = gain; + + return writeChannel( channel, dacChannel ); +} + +bool MCP4728::writeChannel(uint8_t channel, const DacChannel& channelData) +{ + if (channelData.value > 0xfff) { + // error number of bits exceeding 12 + return false; + } + startTimer(); + if ( !waitEepReady() ) return false; + + channel = channel & 0x03; + uint8_t buf[3]; + if (channelData.eeprom) { + buf[0] = COMMAND::DAC_EEP_SINGLE_WRITE << 3; + //buf[0] = 0b01011001; + } else { + buf[0] = COMMAND::DAC_MULTI_WRITE << 3; + //buf[0] = 0b01000001; + } + // buf[0] |= 0x01; set UDAC bit + buf[0] |= (channel << 1); // 01000/01011 (multiwrite/singlewrite command) DAC1 DAC0 (channel) UDAC bit = 1 + buf[1] = ((uint8_t)channelData.vref) << 7; // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 + buf[1] |= (channelData.pd & 0x03) << 5; + buf[1] |= (uint8_t)((channelData.value & 0xf00) >> 8); + buf[1] |= (uint8_t)(channelData.gain & 0x01) << 4; + buf[2] = (uint8_t)(channelData.value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 + if ( write(buf, 3) != 3 ) { + // somehow did not write exact same amount of bytes as it should + return false; + } + stopTimer(); + fLastConvTime = fLastTimeInterval; + if ( channelData.eeprom ) { + fChannelSettingEep[channel] = channelData; + } else { + fChannelSetting[channel] = channelData; + } + // force a register update next time anything is read + fLastRegisterUpdate = { }; + return true; +} + +bool MCP4728::storeSettings() +{ + startTimer(); + const uint8_t startchannel { 0 }; + uint8_t buf[9]; + + if ( !waitEepReady() ) return false; + + buf[0] = COMMAND::DAC_EEP_SEQ_WRITE << 3; + //buf[0] |= 0x01; // set UDAC bit + buf[0] |= ( startchannel << 1 ); // command DAC1 DAC0 UDAC + for ( uint8_t channel = 0; channel < 4; channel++) { + buf[ channel*2+1 ] = ((uint8_t)fChannelSetting[channel].vref) << 7; // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 + buf[ channel*2+1 ] |= (fChannelSetting[channel].pd & 0x03) << 5; + buf[ channel*2+1 ] |= (uint8_t)((fChannelSetting[channel].value & 0xf00) >> 8); + buf[ channel*2+1 ] |= (uint8_t)(fChannelSetting[channel].gain & 0x01) << 4; + buf[ channel*2+2 ] = (uint8_t)(fChannelSetting[channel].value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 + } + + if ( write(buf, 9) != 9 ) { + // somehow did not write exact same amount of bytes as it should + return false; + } + stopTimer(); + fLastConvTime = fLastTimeInterval; + // force a register update next time anything is read + fLastRegisterUpdate = { }; + + return true; +} + +bool MCP4728::devicePresent() +{ + return readRegisters(); +} + +bool MCP4728::waitEepReady() +{ +// if ( !fBusy ) return false; + if ( !readRegisters() ) return false; + int timeout_ctr { 100 }; + while ( fBusy && timeout_ctr-- > 0 ) { + fLastRegisterUpdate = {}; + if ( !readRegisters() ) return false; + } +// std::cout<<"debug: MCP4728::waitEepReady(): timout_ctr="< 0 ) return true; + return false; +} + +bool MCP4728::readRegisters() +{ + uint8_t buf[24]; + startTimer(); + // perform a register update only if the buffered content is too old + if ( ( std::chrono::steady_clock::now() - fLastRegisterUpdate ) < DataValidityTimeout ) { +// std::cout< 3) { + // error: channel index exceeding 3 + return false; + } + + if ( !readRegisters() ) return false; + if ( channelData.eeprom ) { + channelData = fChannelSettingEep[channel]; + } else { + channelData = fChannelSetting[channel]; + } + + return true; +} + +float MCP4728::code2voltage(const DacChannel& channelData) +{ + float vref = (channelData.vref == VREF_2V) ? 2.048 : fVddRefVoltage; + float voltage = vref * channelData.value / 4096.; + if (channelData.gain == GAIN2 && channelData.vref != VREF_VDD) + voltage *= 2.; + return voltage; +} + +bool MCP4728::identify() { + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + uint8_t buf[24]; + if (read(buf, 24) != 24) return false; + + if ( ( ( buf[0] & 0xf0 ) == 0xc0 ) && + ( ( buf[6] & 0xf0 ) == 0xd0 ) && + ( ( buf[12] & 0xf0 ) == 0xe0 ) && + ( ( buf[18] & 0xf0 ) == 0xf0 ) ) + { + return true; + } + + return false; +} + +bool MCP4728::setVRef( unsigned int channel, CFG_VREF vref_setting ) +{ + startTimer(); + if ( !waitEepReady() ) return false; + + channel = channel & 0x03; + uint8_t databyte { 0 }; + databyte = COMMAND::VREF_WRITE >> 1; + for ( unsigned int ch = 0; ch < 4; ch++ ) { + if ( ch == channel ) { + databyte |= vref_setting; + } else { + databyte |= fChannelSetting[ch].vref; + } + databyte = (databyte << 1); + } + + if ( write( &databyte, 1 ) != 1 ) { + // somehow did not write exact same amount of bytes as it should + return false; + } + stopTimer(); + fLastConvTime = fLastTimeInterval; + + fChannelSetting[channel].vref = vref_setting; + return true; +} + +bool MCP4728::setVRef( CFG_VREF vref_setting ) +{ + startTimer(); + if ( !waitEepReady() ) return false; + uint8_t databyte { 0 }; + databyte = COMMAND::VREF_WRITE >> 1; + for ( unsigned int ch = 0; ch < 4; ch++ ) { + databyte |= vref_setting; + databyte = (databyte << 1); + } + + if ( write( &databyte, 1 ) != 1 ) { + // somehow did not write exact same amount of bytes as it should + return false; + } + stopTimer(); + fLastConvTime = fLastTimeInterval; + + fChannelSetting[0].vref = fChannelSetting[1].vref = fChannelSetting[2].vref = fChannelSetting[3].vref = vref_setting; + return true; +} + + +void MCP4728::parseChannelData( uint8_t* buf ) +{ + for ( unsigned int channel = 0; channel < 4; channel++ ) { + // dac reg: offs = 1 + // eep: offs = 4 + fChannelSetting[channel].vref = (buf[channel * 6 + 1] & 0x80) ? VREF_2V : VREF_VDD; + fChannelSettingEep[channel].vref = (buf[channel * 6 + 4] & 0x80) ? VREF_2V : VREF_VDD; + + fChannelSetting[channel].pd = (buf[channel * 6 + 1] & 0x60) >> 5; + fChannelSettingEep[channel].pd = (buf[channel * 6 + 4] & 0x60) >> 5; + + fChannelSetting[channel].gain = (buf[channel * 6 + 1] & 0x10) ? GAIN2 : GAIN1; + fChannelSettingEep[channel].gain = (buf[channel * 6 + 4] & 0x10) ? GAIN2 : GAIN1; + + fChannelSetting[channel].value = (uint16_t)(buf[channel * 6 + 1] & 0x0f) << 8; + fChannelSetting[channel].value |= (uint16_t)(buf[channel * 6 + 1 + 1] & 0xff); + + fChannelSettingEep[channel].value = (uint16_t)(buf[channel * 6 + 4] & 0x0f) << 8; + fChannelSettingEep[channel].value |= (uint16_t)(buf[channel * 6 + 4 + 1] & 0xff); + + fBusy = ( buf[21] & 0x80 ) == 0; + + fChannelSettingEep[channel].eeprom = true; + } +} + +void MCP4728::dumpRegisters() { + uint8_t buf[24]; + if (read(buf, 24) != 24) { + // somehow did not read exact same amount of bytes as it should + return; + } + for ( int ch = 0; ch < 4; ch++ ) { + std::cout << "DAC"< +#include +#include +#include +#include +/* +* MIC184 Temperature Sensor +*/ +MIC184::MIC184() + : i2cDevice(0x4f) +{ + fTitle = fName = "MIC184"; +} + +MIC184::MIC184(const char* busAddress, uint8_t slaveAddress) + : i2cDevice(busAddress, slaveAddress) +{ + fTitle = fName = "MIC184"; +} + +MIC184::MIC184(uint8_t slaveAddress) + : i2cDevice(slaveAddress) +{ + fTitle = fName = "MIC184"; +} + +MIC184::~MIC184() +{ +} + +int16_t MIC184::readRaw() +{ + startTimer(); + + uint16_t dataword { 0 }; + // Read the temp register + if ( !readWord( static_cast(REG::TEMP), &dataword ) ) { + // there was an error + return INT16_MIN; + } + + int16_t val = static_cast( dataword ); + fLastRawValue = val; + + stopTimer(); + + return val; +} + +float MIC184::getTemperature() +{ + int16_t dataword = readRaw(); + float temp = static_cast( dataword >> 8 ); + temp += static_cast(dataword & 0xff)/256.; + fLastTemp = temp; + return temp; +} + +bool MIC184::identify() +{ + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + + uint8_t conf_reg_save { 0 }; + uint16_t dataword { 0 }; + uint16_t thyst_save { 0 }; + uint16_t tos_save { 0 }; + + // Read the config register + if ( !readByte( static_cast(REG::CONF), &conf_reg_save ) ) { + // there was an error + return false; + } + // datasheet: the interrupt mask bit in conf register should be zero when device is in init state + if ( ( conf_reg_save & 0b01000000 ) != 0 ) return false; + + // read temp register + if ( !readWord( static_cast(REG::TEMP), &dataword ) ) { + // there was an error + return false; + } + // the 5 LSBs should always read zero + if ( (dataword & 0x1f) != 0 ) return false; +// if ( ( (dataword & 0x1f) != 0 ) && ( dataword >> 5 ) == 0 ) return false; + + // read Thyst register + if ( !readWord( static_cast(REG::THYST), &thyst_save ) ) { + // there was an error + return false; + } + // the 7 MSBs should always read zero + if ( (thyst_save & 0x7f) != 0 ) return false; + + // read Tos register + if ( !readWord( static_cast(REG::TOS), &tos_save ) ) { + // there was an error + return false; + } + // the 7 MSBs should always read zero + if ( (tos_save & 0x7f) != 0 ) return false; +/* + std::cout << "MIC184::identify() : found LM75 base device at 0x"<(REG::CONF), conf_reg ) ) return false; + // write 0xc880 to Thyst and Tos regs. This corresponds to -55.5 degrees centigrade + dataword = 0xc880; + if ( !writeWord( static_cast(REG::THYST), dataword ) ) return false; + if ( !writeWord( static_cast(REG::TOS), dataword ) ) return false; + // wait at least one conversion cycle (>160ms) + std::this_thread::sleep_for( std::chrono::milliseconds( 160 ) ); + // Read the config register + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) return false; + // datasheet: MSB of conf reg should be set to one + // this is considered an indication for MIC184 + if ( !( conf_reg & 0x80 ) ) return false; + + // write 0x7f80 to Thyst and Tos regs. This corresponds to +127.5 degrees centigrade + dataword = 0x7f80; + if ( !writeWord( static_cast(REG::THYST), dataword ) ) return false; + if ( !writeWord( static_cast(REG::TOS), dataword ) ) return false; + // wait at least one conversion cycle (>160ms) + std::this_thread::sleep_for( std::chrono::milliseconds( 160 ) ); + // Read the config register again to clear pending interrupt request + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) return false; + + // at this point we know for sure that the device is an MIC184 + // set THyst and Tos regs back to previous settings + writeWord( static_cast(REG::THYST), thyst_save ); + writeWord( static_cast(REG::TOS), tos_save ); + // finally, set config reg into original state + if ( writeByte( static_cast(REG::CONF), conf_reg_save ) ) { + fExternal = ( conf_reg_save & 0x20 ); + return true; + } + return false; +} + +bool MIC184::setExternal( bool enable_external ) +{ + // Read and save the config register + uint8_t conf_reg { 0 }; + uint8_t conf_reg_save { 0 }; + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) return false; + conf_reg_save = conf_reg; + // disable interrupts, clear IM bit + conf_reg &= ~0x40; + if ( !writeByte( static_cast(REG::CONF), conf_reg ) ) return false; + // read back config reg to clear STS flag + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) return false; + if ( enable_external ) conf_reg_save |= 0x20; + else conf_reg_save &= ~0x20; + if ( !writeByte( static_cast(REG::CONF), conf_reg_save ) ) return false; + if ( !readByte( static_cast(REG::CONF), &conf_reg ) ) return false; + if ( (conf_reg & 0x20) != (conf_reg_save & 0x20) ) return false; + fExternal = enable_external; + // wait one cycle until a conversion in the new zone is ready + std::this_thread::sleep_for( std::chrono::milliseconds( 160 ) ); + // and wait twice as long if external zone enabled (datasheet: tconv=160ms (int) and 320ms (ext)) + if ( fExternal ) std::this_thread::sleep_for( std::chrono::milliseconds( 160 ) ); + return true; +} diff --git a/daemon/src/hardware/i2c/pca9536.cpp b/daemon/src/hardware/i2c/pca9536.cpp new file mode 100644 index 00000000..784a94d7 --- /dev/null +++ b/daemon/src/hardware/i2c/pca9536.cpp @@ -0,0 +1,83 @@ +#include "hardware/i2c/pca9536.h" +#include +#include +#include + +/* +* PCA9536 4 pin I/O expander +*/ + +bool PCA9536::setOutputPorts(uint8_t portMask) +{ + unsigned char data = ~portMask; + startTimer(); + if (1 != writeReg( REG::CONFIG, &data, 1)) { + return false; + } + stopTimer(); + return true; +} + +bool PCA9536::setOutputState(uint8_t portMask) +{ + startTimer(); + if (1 != writeReg( REG::OUTPUT, &portMask, 1)) { + return false; + } + stopTimer(); + return true; +} + +uint8_t PCA9536::getInputState() +{ + uint8_t inport = 0x00; + startTimer(); + readReg(REG::INPUT, &inport, 1); + stopTimer(); + return inport & 0x0f; +} + +bool PCA9536::devicePresent() +{ + uint8_t inport = 0x00; + // read input port + return (1 == readReg(REG::INPUT, &inport, 1)); +} + +bool PCA9536::identify() +{ + if ( fMode == MODE_FAILED ) return false; + if ( !devicePresent() ) return false; + uint8_t bytereg { 0 }; +/* + for (int i=0; i<256; i++) { + if ( !readByte( static_cast(i), &bytereg ) ) break; + std::cout << "reg 0x"<(REG::INPUT), &bytereg ) ) { + // there was an error + return false; + } + if ( ( bytereg & 0xf0 ) != 0xf0 ) return false; +/* + if ( !readByte( static_cast(REG::OUTPUT), &bytereg ) ) { + // there was an error + return false; + } + if ( ( bytereg & 0xf0 ) != 0xf0 ) return false; +*/ + if ( !readByte( static_cast(REG::POLARITY), &bytereg ) ) { + // there was an error + return false; + } + if ( ( bytereg & 0xf0 ) != 0x00 ) return false; + + if ( !readByte( static_cast(REG::CONFIG), &bytereg ) ) { + // there was an error + return false; + } + if ( ( bytereg & 0xf0 ) != 0xf0 ) return false; + if ( readByte( 0x04, &bytereg ) ) return false; + return true; +} diff --git a/daemon/src/hardware/i2c/sht21.cpp b/daemon/src/hardware/i2c/sht21.cpp new file mode 100644 index 00000000..78f26f73 --- /dev/null +++ b/daemon/src/hardware/i2c/sht21.cpp @@ -0,0 +1,156 @@ +#include "hardware/i2c/sht21.h" +#include +#include + +/* +* SHT21 Temperature&Humidity Sensor +* Prefered option is the no hold mastermode +*/ + +bool SHT21::checksumCorrect(uint8_t data[]) // expects data to be greater or equal 3 (expecting 3) +{ + const uint16_t Polynom = 0x131; + uint8_t crc = 0; + uint8_t byteCtr; + uint8_t bit; + try { + for (byteCtr = 0; byteCtr < 2; ++byteCtr) { + crc ^= (data[byteCtr]); + for (bit = 8; bit > 0; --bit) { + if (crc & 0x80) { + crc = (crc << 1) ^ Polynom; + } else { + crc = (crc << 1); + } + } + } + if (crc != data[2]) { + return false; + } else { + return true; + } + } catch (int i) { + printf("Error, Array too small in function: checksumCorrect\n"); + return false; + } +} + +float SHT21::getHumidity() +{ + uint16_t data_hum = readUH(); + float fhum; //end calculation -> Humidity + fhum = -6.0 + 125.0 * (((float)(data_hum)) / 65536.0); + return (fhum); +} + +float SHT21::getTemperature() +{ + uint16_t data_temp = readUT(); + float ftemp; //endl calculation -> Temperature + ftemp = -46.85 + 175.72 * (((float)(data_temp)) / 65536.0); + return (ftemp); +} + +uint16_t SHT21::readUT() // von unsigned int auf float geändert +{ + uint8_t writeBuf[1]; + uint8_t readBuf[3]; + uint16_t data_temp; + + writeBuf[0] = 0; + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + data_temp = 0; + + writeReg(0xF3, writeBuf, 0); + usleep(85000); + while (read(readBuf, 3) != 3) + ; + + if (fDebugLevel > 1) { + printf("Inhalt: (MSB Byte): %x\n", readBuf[0]); + printf("Inhalt: (LSB Byte): %x\n", readBuf[1]); + printf("Inhalt: (Checksum Byte): %x\n", readBuf[2]); + } + + data_temp = ((uint16_t)readBuf[0]) << 8; + data_temp |= readBuf[1]; + data_temp &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. + + if (!checksumCorrect(readBuf)) { + printf("checksum error\n"); + } + return data_temp; +} + +uint16_t SHT21::readUH() //Hold mode +{ + uint8_t writeBuf[1]; + uint8_t readBuf[3]; //what should be read later + uint16_t data_hum; + + writeBuf[0] = 0; + readBuf[0] = 0; + readBuf[1] = 0; + readBuf[2] = 0; + data_hum = 0; + + writeReg(0xF5, writeBuf, 0); + usleep(30000); + while (read(readBuf, 3) != 3) + ; + + if (fDebugLevel > 1) { + printf("Es wurden gelesen (MSB Bytes): %x\n", readBuf[0]); + printf("Es wurden gelesen (LSB Bytes): %x\n", readBuf[1]); + printf("Es wurden gelesen (Checksum Bytes): %x\n", readBuf[2]); + } + + data_hum = ((uint16_t)readBuf[0]) << 8; + data_hum |= readBuf[1]; + data_hum &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. + + if (!checksumCorrect(readBuf)) { + printf("checksum error\n"); + } + return data_hum; +} + +uint8_t SHT21::readResolutionSettings() +{ //reads the temperature and humidity resolution settings byte + uint8_t readBuf[1]; + + readBuf[0] = 0; //Initialization + + readReg(0xE7, readBuf, 1); + return readBuf[0]; +} + +void SHT21::setResolutionSettings(uint8_t settingsByte) +{ //sets the temperature and humidity resolution settings byte + uint8_t readBuf[1]; + readBuf[0] = 0; //Initialization + readReg(0xE7, readBuf, 1); + readBuf[0] &= 0b00111000; // mask, to not change reserved bits (Bit 3, 4 and 5 are reserved) + settingsByte &= 0b11000111; + uint8_t writeBuf[1]; + writeBuf[0] = settingsByte | readBuf[0]; + writeReg(0xE6, writeBuf, 1); +} + +bool SHT21::softReset() +{ + uint8_t writeBuf[1]; + writeBuf[0] = 0xFE; + + int n = 0; + n = writeReg(0xFE, writeBuf, 0); + usleep(15000); //wait for the SHT to reset; datasheet on page 9 + + if (n == 0) { + printf("soft_reset succesfull %i\n", n); + } + + return (n == 0); //Wenn n == 0, gibt die Funktion True zurück. Wenn nicht gibt sie False zurück. +} diff --git a/source/daemon/src/i2c/i2cdevices/sht31/sht31.cpp b/daemon/src/hardware/i2c/sht31.cpp similarity index 93% rename from source/daemon/src/i2c/i2cdevices/sht31/sht31.cpp rename to daemon/src/hardware/i2c/sht31.cpp index 9a013af4..8fe34e45 100644 --- a/source/daemon/src/i2c/i2cdevices/sht31/sht31.cpp +++ b/daemon/src/hardware/i2c/sht31.cpp @@ -1,4 +1,4 @@ -#include "sht31.h" +#include "hardware/i2c/sht31.h" #include #include @@ -55,7 +55,7 @@ bool SHT31::getValues(float &ftemp, float &fhum) { return true; } -bool SHT31::readRaw(uint16_t &UT, uint16_t &UH) // von unsigned int auf float geändert +bool SHT31::readRaw(uint16_t &UT, uint16_t &UH) // von unsigned int auf float geändert { uint8_t writeBuf[2]; uint8_t readBuf[6]; @@ -123,6 +123,7 @@ bool SHT31::breakCommand() { int n = 0; n = write(writeBuf, 2); usleep(15000); + return ( n != 2 ); } bool SHT31::softReset() @@ -140,5 +141,5 @@ bool SHT31::softReset() printf("soft_reset succesfull %i\n", n); } - return(n == 0); //Wenn n == 0, gibt die Funktion True zurück. Wenn nicht gibt sie False zurück. + return(n == 0); //Wenn n == 0, gibt die Funktion True zurück. Wenn nicht gibt sie False zurück. } diff --git a/source/daemon/src/i2c/i2cdevices/tca9546a/tca9546a.cpp b/daemon/src/hardware/i2c/tca9546a.cpp similarity index 85% rename from source/daemon/src/i2c/i2cdevices/tca9546a/tca9546a.cpp rename to daemon/src/hardware/i2c/tca9546a.cpp index a4dbfaf2..d5dabd7d 100644 --- a/source/daemon/src/i2c/i2cdevices/tca9546a/tca9546a.cpp +++ b/daemon/src/hardware/i2c/tca9546a.cpp @@ -1,4 +1,4 @@ -#include "tca9546a.h" +#include "hardware/i2c/tca9546a.h" #include #include #include diff --git a/daemon/src/hardware/i2c/ubloxi2c.cpp b/daemon/src/hardware/i2c/ubloxi2c.cpp new file mode 100644 index 00000000..a36a779d --- /dev/null +++ b/daemon/src/hardware/i2c/ubloxi2c.cpp @@ -0,0 +1,53 @@ +#include "hardware/i2c/ubloxi2c.h" +#include +#include +#include +#include + +/* Ublox GPS receiver, I2C interface */ + +bool UbloxI2c::devicePresent() +{ + uint8_t dummy; + return (1 == readReg(0xff, &dummy, 1)); +} + +std::string UbloxI2c::getData() +{ + uint16_t nrBytes = 0; + if (!getTxBufCount(nrBytes)) + return ""; + if (nrBytes == 0) + return ""; + uint8_t reg = 0xff; + int n = write(®, 1); + if (n != 1) + return ""; + uint8_t buf[128]; + if (nrBytes > 128) + nrBytes = 128; + n = read(buf, nrBytes); + if (n != nrBytes) + return ""; + std::string str(nrBytes, ' '); + std::transform(&buf[0], &buf[nrBytes], str.begin(), [](uint8_t c) { return (unsigned char)c; }); + return str; +} + +bool UbloxI2c::getTxBufCount(uint16_t& nrBytes) +{ + startTimer(); + uint8_t reg = 0xfd; + uint8_t buf[2]; + int n = write(®, 1); + if (n != 1) + return false; + n = read(buf, 2); // Read the data at TX buf counter location + stopTimer(); + if (n != 2) + return false; + uint16_t temp = buf[1]; + temp |= (uint16_t)buf[0] << 8; + nrBytes = temp; + return true; +} diff --git a/daemon/src/hardware/i2c/x9119.cpp b/daemon/src/hardware/i2c/x9119.cpp new file mode 100644 index 00000000..31b9e4d8 --- /dev/null +++ b/daemon/src/hardware/i2c/x9119.cpp @@ -0,0 +1,162 @@ +#include "hardware/i2c/x9119.h" +#include // I2C bus definitions for linux like systems +#include // I2C bus definitions for linux like systems +#include +#include + +/* +* X9119 +*/ + +unsigned int X9119::readWiperReg() +{ + + // just return the locally stored last value written to WCR + // since readback doesn't work without repeated start transaction + return fWiperReg; + + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device + int16_t val; // Stores the 16 bit value of our ADC conversion + + writeBuf[0] = 0x80; // op-code read WCR + + // Write writeBuf to the X9119 + // this sets the write address for WCR register and writes WCR + write(writeBuf, 1); + + readBuf[0] = 0; + readBuf[1] = 0; + + read(readBuf, 2); // Read the config register into readBuf + + val = (readBuf[0] & 0x03) << 8 | readBuf[1]; + + return val; +} + +unsigned int X9119::readDataReg(uint8_t reg) +{ + + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device + int16_t val; // Stores the 16 bit value of our ADC conversion + + writeBuf[0] = 0x80 | 0x20 | (reg & 0x03) << 2; // op-code read data reg + + // Write writeBuf to the X9119 + // this sets the write address for WCR register and writes WCR + write(writeBuf, 1); + + readBuf[0] = 0; + readBuf[1] = 0; + + read(readBuf, 2); // Read the config register into readBuf + + val = (readBuf[0] & 0x03) << 8 | readBuf[1]; + + return val; +} + +unsigned int X9119::readWiperReg2() +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device + int16_t val; // Stores the 16 bit value of our ADC conversion + + writeBuf[0] = 0x80; // op-code read WCR + + struct i2c_msg rdwr_msgs[2]; + + rdwr_msgs[0].addr = fAddress; + rdwr_msgs[0].flags = 0; + rdwr_msgs[0].len = 1; + rdwr_msgs[0].buf = writeBuf; + + rdwr_msgs[1].addr = fAddress; + rdwr_msgs[1].flags = I2C_M_RD; + rdwr_msgs[1].len = 2; + rdwr_msgs[1].buf = readBuf; + + struct i2c_rdwr_ioctl_data rdwr_data; + + rdwr_data.msgs = rdwr_msgs; + rdwr_data.nmsgs = 2; + + int result = ioctl(fHandle, I2C_RDWR, &rdwr_data); + + if (result < 0) { + printf("rdwr ioctl error: %d\n", errno); + perror("reason"); + } else { + printf("rdwr ioctl OK\n"); + } + + val = (readBuf[0] & 0x03) << 8 | readBuf[1]; + + return val; + + writeBuf[0] = 0x80; // op-code read WCR + + // Write writeBuf to the X9119 + // this sets the write address for WCR register and writes WCR + write(writeBuf, 1); + + readBuf[0] = 0; + readBuf[1] = 0; + + read(readBuf, 2); // Read the config register into readBuf + + val = (readBuf[0] & 0x03) << 8 | readBuf[1]; + + return val; +} + +unsigned int X9119::readWiperReg3() +{ + + union i2c_smbus_data data; + struct i2c_smbus_ioctl_data args; + + args.read_write = I2C_SMBUS_READ; + args.command = 0x80; + args.size = I2C_SMBUS_WORD_DATA; + args.data = &data; + int result = ioctl(fHandle, I2C_SMBUS, &args); + if (result < 0) { + printf("rdwr ioctl error: %d\n", errno); + perror("reason"); + return 0; + } else { + printf("rdwr ioctl OK\n"); + } + return 0x0FFFF & data.word; +} + +void X9119::writeWiperReg(unsigned int value) +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + + writeBuf[0] = 0x80 | 0x20; // op-code write WCR + writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR + writeBuf[2] = (value & 0xff); // LSB of WCR + + // Write writeBuf to the X9119 + // this sets the write address for WCR register and writes WCR + int n = write(writeBuf, 3); + if (n == 3) + fWiperReg = value; +} + +void X9119::writeDataReg(uint8_t reg, unsigned int value) +{ + uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device + + writeBuf[0] = 0x80 | 0x40 | (reg & 0x03) << 2; // op-code write data reg + writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR + writeBuf[2] = (value & 0xff); // LSB of WCR + + // Write writeBuf to the X9119 + // this sets the write address for data register and writes dr with value + write(writeBuf, 3); +} diff --git a/daemon/src/hardware/i2cdevices.cpp b/daemon/src/hardware/i2cdevices.cpp new file mode 100644 index 00000000..da1400d9 --- /dev/null +++ b/daemon/src/hardware/i2cdevices.cpp @@ -0,0 +1,54 @@ +#include "hardware/i2cdevices.h" +#include +#include + +i2cDevice* instantiateI2cDevice( uint8_t addr ) { + + i2cDevice* device { nullptr }; + for (uint8_t i = 0; i < i2cDevice::getGlobalDeviceList().size(); i++) { + if ( addr == i2cDevice::getGlobalDeviceList()[i]->getAddress() ) { + return device; + } + } + + bool ident { false }; + ident = MCP4728::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new MCP4728( addr ); + device->identify(); + return device; + } + ident = MIC184::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new MIC184( addr ); + device->identify(); + return device; + } + ident = LM75::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new LM75( addr ); + device->identify(); + return device; + } + ident = ADS1115::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new ADS1115( addr ); + device->identify(); + return device; + } + ident = EEPROM24AA02::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new EEPROM24AA02( addr ); + device->identify(); + return device; + } + ident = PCA9536::identifyDevice( static_cast(addr) ); + if ( ident ) { + device = new PCA9536( addr ); + device->identify(); + return device; + } + + device = new i2cDevice( addr ); + return device; +} diff --git a/daemon/src/hardware/spi/tdc7200.cpp b/daemon/src/hardware/spi/tdc7200.cpp new file mode 100644 index 00000000..cb424df1 --- /dev/null +++ b/daemon/src/hardware/spi/tdc7200.cpp @@ -0,0 +1,179 @@ +#include "hardware/spi/tdc7200.h" +#include + +TDC7200::TDC7200(unsigned int _INTB, QObject* parent) + : QObject(parent) +{ + INTB = (uint8_t)_INTB; +} + +void TDC7200::initialise() +{ + devicePresent = false; + writeReg(0x03, 0x07); + readReg(0x03); +} + +void TDC7200::onDataAvailable(uint8_t pin) +{ + // this means if the INTB is high and there are new measurement results + // should read all relevant TOF data and after that + if (pin != INTB) { + return; + } + uint8_t num_stop = config[1] & 0x07; + if (num_stop > 0b100) { + num_stop = 0; + } + + num_stop++; + + waitingForDataCounter = (int)((num_stop)*2 + 3); + readReg(0x1b); // calibration 1 + readReg(0x1c); // calibration 2 + for (int i = 0; i < num_stop * 2 + 1; i++) { + // TIME1 and as many TIMEx and CLOCK_COUNTx as num_stop + // for single num_stop there are TIME1, CLOCK_COUNT1, TIME2 + readReg(i + 0x10); + } +} + +void TDC7200::onStatusRequested() +{ + emit statusUpdated(devicePresent); +} + +void TDC7200::configRegisters() +{ + for (int i = sizeof(config) - 1; i > 0; i--) { + writeReg(i, config[i]); + } +} + +void TDC7200::startMeas() +{ + if (!devicePresent) { + initialise(); + return; + } + writeReg(0, config[0] | 0x01); // the least significant bit starts the measurement +} + +void TDC7200::onDataReceived(uint8_t reg, std::string data) +{ + if (devicePresent == false) { + if (reg == 0x03 && data.size() == 1 and data[0] == (char)0x07) { + devicePresent = true; // device is present, do configuration + emit statusUpdated(true); + configRegisters(); + return; + } else { + emit statusUpdated(false); + qDebug() << "TDC7200 not present"; + return; + } + } + if (reg < 10) { + if (data.size() != 1) { + qDebug() << "data size returned does not match the register size"; + return; + } + } else if (data.size() != 3) { + qDebug() << "data size returned does not match the register size"; + return; + } else if (reg > 0x1c) { + qDebug() << "returned register address out of scope"; + return; + } + uint32_t regContent = 0; + if (reg < 10) { + regContent = (uint32_t)data[0]; + regContent1[reg] = (uint8_t)data[0]; + } else { + regContent = data[0]; + regContent <<= 8; + regContent |= data[1]; + regContent <<= 8; + regContent |= data[2]; + regContent2[reg - 0x10] = regContent; + if (waitingForDataCounter != -1) { + waitingForDataCounter--; + } + } + emit regContentChanged(reg, regContent); + if (waitingForDataCounter == 0) { + waitingForDataCounter = -1; + processData(); + } +} + +void TDC7200::processData() +{ + uint8_t num_stop = config[1] & 0x07; + if (num_stop > 0b100) { + num_stop = 0; + } + num_stop += 1; + uint8_t meas_mode = (config[0] & 0x2) >> 1; + uint32_t CALIBRATION1 = regContent2[0x1b - 0x10]; + uint32_t CALIBRATION2 = regContent2[0x1c - 0x10]; + uint8_t cal2_periods_setting = (config[1] & 0b11000000) >> 6; + uint8_t CALIBRATION2_PERIODS = 0; + switch (cal2_periods_setting) { + case 0: + CALIBRATION2_PERIODS = 2; + break; + case 1: + CALIBRATION2_PERIODS = 10; + break; + case 2: + CALIBRATION2_PERIODS = 20; + break; + case 3: + CALIBRATION2_PERIODS = 40; + break; + default: + break; + } + + QVector timings; + double calCount = ((double)CALIBRATION2 - (double)CALIBRATION1) / ((double)CALIBRATION2_PERIODS - 1); + double normLSB = (double)CLOCKperiod / calCount; + double TIME1 = (double)regContent2[0]; + for (int i = 0; i < num_stop; i++) { + if (meas_mode == 0) { // mode 1 + double TIMEx = (double)regContent2[i * 2]; + double TOF = TIMEx / normLSB; + timings.push_back(TOF); + } + if (meas_mode == 1) { // mode 2 + double TIMEn1 = (double)regContent2[i * 2 + 2]; + double TOF = normLSB * (TIME1 - TIMEn1) + ((double)regContent2[i + 1]) * CLOCKperiod; + timings.push_back(TOF); + } + } + emit timeMeas(timings); + emit tdcEvent(timings.at(0) * 1e6); + startMeas(); +} + +void TDC7200::writeReg(uint8_t reg, uint8_t data) +{ + uint8_t command = reg & 0x3f; + command |= 0x40; // bit 6 is 1 => write and bit 7 is 0 for writing only one byte + std::string dataString; + dataString += (char)data; + emit writeData(command, dataString); +} + +void TDC7200::readReg(uint8_t reg) +{ + unsigned int bytesRead = 0; + if (reg < 10) { + bytesRead = 1; + } else { + bytesRead = 3; + } + uint8_t command = reg & 0x3f; + emit readData(command, bytesRead); +} diff --git a/daemon/src/logengine.cpp b/daemon/src/logengine.cpp new file mode 100644 index 00000000..81effa7b --- /dev/null +++ b/daemon/src/logengine.cpp @@ -0,0 +1,147 @@ +#include +#include +#include +#include +#include "logengine.h" +#include "logparameter.h" + +static QString dateStringNow() +{ + return QDateTime::currentDateTimeUtc().toString("yyyy-MM-dd_hh-mm-ss"); +} + +LogEngine::LogEngine(QObject* parent) + : QObject(parent) +{ + QTimer* logReminder = new QTimer(this); + logReminder->setInterval(60 * 1000 * MuonPi::Config::Log::interval); + logReminder->setSingleShot(false); + connect(logReminder, &QTimer::timeout, this, &LogEngine::onLogInterval); + logReminder->start(); +} + +LogEngine::~LogEngine() +{ +} + +void LogEngine::setHashLength(int hash_length) +{ + hashLength = hash_length; +} + +void LogEngine::onLogParameterReceived(const LogParameter& logpar) +{ + if (logpar.logType() == LogParameter::LOG_NEVER) { + return; + } + if (logpar.logType() == LogParameter::LOG_EVERY) { + // directly log to file since LOG_EVERY attribute is set + // no need to store in buffer, just return after logging + emit sendLogString(dateStringNow() + " " + QString(logpar.name() + " " + logpar.value())); + // reset already existing entries but preserve logType attribute + if (logData.find(logpar.name()) != logData.end()) { + int logType = logData[logpar.name()].front().logType(); + if (logType != LogParameter::LOG_AVERAGE) { + logData[logpar.name()].clear(); + } + logData[logpar.name()].push_back(LogParameter(logpar.name(), logpar.value(), logType)); + logData[logpar.name()].back().setUpdatedRecently(false); + } + return; + } else { + // save to buffer + if (logpar.logType() == LogParameter::LOG_ONCE) { + // don't save if a LOG_ONCE param with this name is already in buffer + } + logData[logpar.name()].push_back(logpar); + logData[logpar.name()].back().setUpdatedRecently(true); + } +} + +void LogEngine::onLogInterval() +{ + emit logIntervalSignal(); + // send log items which should always be sent + emit sendLogString(dateStringNow() + " maxGeohashLength " + QString::number(hashLength)); + emit sendLogString(dateStringNow() + " softwareVersionString " + QString::fromStdString(MuonPi::Version::software.string())); + emit sendLogString(dateStringNow() + " hardwareVersionString " + QString::fromStdString(MuonPi::Version::hardware.string())); + + // loop over the map with all accumulated parameters since last log reminder + // no increment here since we erase and invalidate iterators within the loop + for (auto it = logData.begin(); it != logData.end();) { + QString name = it.key(); + QVector parVector = it.value(); + // check if name string is set but no entry exists. This should not happen + if (parVector.isEmpty()) { + ++it; + continue; + } + + if (parVector.back().logType() == LogParameter::LOG_LATEST) { + // easy to write only the last value to file + emit sendLogString(dateStringNow() + " " + name + " " + parVector.back().value()); + it = logData.erase(it); + } else if (parVector.back().logType() == LogParameter::LOG_AVERAGE) { + // here we loop over all values in the vector for the current parameter and do the averaging + double sum = 0.; + bool ok = false; + // parse last field of value string + QString unitString = parVector.back().value().section(" ", -1, -1); + // compare with first field + if (unitString.compare(parVector.back().value().section(" ", 0, 0)) == 0) { + // unit and value are identical, so there is probably no unit suffix + // set unit to empty string + unitString = ""; + } + // do the averaging + for (int i = 0; i < parVector.size(); i++) { + QString valString = parVector[i].value(); + QString str = valString.section(" ", 0, 0); + // convert to double with error checking + double val = str.toDouble(&ok); + if (!ok) + break; + sum += val; + } + if (ok) { + sum /= parVector.size(); + emit sendLogString(dateStringNow() + " " + QString(name + " " + QString::number(sum, 'f', 7) + " " + unitString)); + } + it = logData.erase(it); + } else if (parVector.back().logType() == LogParameter::LOG_ONCE) { + // we want to log only one time per daemon lifetime || file change + if (onceLogFlag || parVector.front().updatedRecently()) { + emit sendLogString(dateStringNow() + " " + name + " " + parVector.back().value()); + } + while (parVector.size() > 2) { + parVector.pop_front(); + } + parVector.front().setUpdatedRecently(false); + logData[name] = parVector; + ++it; + } else if (parVector.back().logType() == LogParameter::LOG_ON_CHANGE) { + // we want to log only if one value differs from the first entry + // first entry is reference value + if (onceLogFlag || parVector.front().updatedRecently()) { + // log the first time anyway + emit sendLogString(dateStringNow() + " " + name + " " + parVector.back().value()); + } else { + for (int i = 1; i < parVector.size(); i++) { + if (parVector[i].value().compare(parVector.front().value()) != 0) { + // found difference -> log it + emit sendLogString(dateStringNow() + " " + name + " " + parVector[i].value()); + parVector.replace(0, parVector[i]); + } + } + } + while (parVector.size() > 1) { + parVector.pop_back(); + } + parVector.front().setUpdatedRecently(false); + logData[name] = parVector; + ++it; + } else + ++it; + } + onceLogFlag = false; +} diff --git a/daemon/src/main.cpp b/daemon/src/main.cpp new file mode 100644 index 00000000..7586b99f --- /dev/null +++ b/daemon/src/main.cpp @@ -0,0 +1,592 @@ +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "utility/custom_io_operators.h" +#include "daemon.h" +#include + +static const char* CONFIG_FILE = MuonPi::Config::file; +static int verbose = 0; + +[[nodiscard]] auto getch() -> int; +[[nodiscard]] auto getpass(const char* prompt, bool show_asterisk) -> std::string; + +auto getch() -> int +{ + int ch; + struct termios t_old, t_new; + + tcgetattr(STDIN_FILENO, &t_old); + t_new = t_old; + t_new.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &t_new); + + ch = getchar(); + + tcsetattr(STDIN_FILENO, TCSANOW, &t_old); + return ch; +} + +auto getpass(const char* prompt, bool show_asterisk) -> std::string +{ + const char BACKSPACE = 127; + const char RETURN = 10; + + std::string password; + unsigned char ch = 0; + ch = getch(); + std::cout << prompt << '\n' + << std::flush; + while ((ch = getch()) != RETURN) { + if (ch == BACKSPACE) { + if (password.length() != 0) { + if (show_asterisk) + std::cout << "\b \b"; + password.resize(password.length() - 1); + } + } else { + password += ch; + if (show_asterisk) + std::cout << '*'; + } + } + std::cout << '\n' + << std::flush; + return password; +} + +// The application's custom message handler +// All outputs to console should go through the QT message mechanism: +// i.e. qDebug(), qWarning(), qCritical(), qFatal() +void messageOutput(QtMsgType type, const QMessageLogContext& context, const QString& msg) +{ + QByteArray localMsg = msg.toLocal8Bit(); + const char* file = context.file ? context.file : ""; + const char* function = context.function ? context.function : ""; + switch (type) { + case QtDebugMsg: + if (verbose) { + fprintf(stdout, "Debug: %s (%s:%u, %s)\n", localMsg.constData(), file, context.line, function); + fflush(stdout); + } + break; + case QtInfoMsg: + fprintf(stdout, "Info: %s\n", localMsg.constData()); + fflush(stdout); + break; + case QtWarningMsg: + fprintf(stderr, "Warning: %s\n", localMsg.constData()); + fflush(stderr); + break; + case QtCriticalMsg: + fprintf(stderr, "Critical: %s\n", localMsg.constData()); + fflush(stderr); + break; + case QtFatalMsg: + fprintf(stderr, "Fatal: %s\n", localMsg.constData()); + fflush(stderr); + break; + } +} + +int main(int argc, char* argv[]) +{ + qRegisterMetaType("TcpMessage"); + qInstallMessageHandler(messageOutput); + QCoreApplication a(argc, argv); + QCoreApplication::setApplicationName("muondetector-daemon"); + QCoreApplication::setApplicationVersion(QString::fromStdString(MuonPi::Version::software.string())); + // config file handling + libconfig::Config cfg; + + qInfo() << "MuonPi Muondetector Daemon " + << "V"+QString::fromStdString(MuonPi::Version::software.string()) + << "(build "+ QString(__TIMESTAMP__) +")"; + + // Read the file. If there is an error, report it and exit. + try { + cfg.readFile(MuonPi::Config::file); + } catch (const libconfig::FileIOException& fioex) { + qWarning() << "Error while reading config file" << QString(CONFIG_FILE); + } catch (const libconfig::ParseException& pex) { + qFatal(qPrintable("Parse error at " + QString(pex.getFile()) + " : line " + QString(pex.getLine()) + " - " + QString(pex.getError()))); + return (EXIT_FAILURE); + } + + // command line input management + QCommandLineParser parser; + parser.setApplicationDescription("MuonPi cosmic shower muon detector control and configuration program (daemon)\n" + "with added tcp implementation for synchronisation of " + "data with a central server through MQTT protocol"); + parser.addHelpOption(); + parser.addVersionOption(); + + // add module path for example /dev/gps0 or /dev/ttyAMA0 + parser.addPositionalArgument("device", QCoreApplication::translate("main", "path to u-blox GNSS device\n" + "e.g. /dev/ttyAMA0")); + + // station ID (some name for individual stations if someone has multiple) + QCommandLineOption stationIdOption("id", + QCoreApplication::translate("main", "set station ID"), + QCoreApplication::translate("main", "ID")); + parser.addOption(stationIdOption); + + // verbosity option + QCommandLineOption verbosityOption(QStringList() << "e" + << "verbose", + QCoreApplication::translate("main", "set verbosity level\n" + "5 is max"), + QCoreApplication::translate("main", "verbosity")); + parser.addOption(verbosityOption); + + // dumpraw option + QCommandLineOption dumpRawOption("d", + QCoreApplication::translate("main", "dump raw gps device (NMEA) output to stdout")); + parser.addOption(dumpRawOption); + + // show GNSS configs + QCommandLineOption showGnssConfigOption("c", + QCoreApplication::translate("main", "configure standard ubx protocol messages at start")); + parser.addOption(showGnssConfigOption); + + // show outgoing ubx messages as hex + QCommandLineOption showoutOption(QStringList() << "showoutgoing" + << "showout", + QCoreApplication::translate("main", "show outgoing ubx messages as hex")); + parser.addOption(showoutOption); + + // show incoming ubx messages as hex + QCommandLineOption showinOption(QStringList() << "showincoming" + << "showin", + QCoreApplication::translate("main", "show incoming ubx messages as hex")); + parser.addOption(showinOption); + + // peerAddress option + QCommandLineOption peerIpOption(QStringList() << "peer" + << "peerAddress", + QCoreApplication::translate("main", "set file server ip address"), + QCoreApplication::translate("main", "peerAddress")); + parser.addOption(peerIpOption); + + // peerPort option + QCommandLineOption peerPortOption(QStringList() << "pp" + << "peerPort", + QCoreApplication::translate("main", "set file server port"), + QCoreApplication::translate("main", "peerPort")); + parser.addOption(peerPortOption); + + // daemonAddress option + QCommandLineOption daemonIpOption(QStringList() << "server" + << "daemonAddress", + QCoreApplication::translate("main", "set gui server ip address"), + QCoreApplication::translate("main", "daemonAddress")); + parser.addOption(daemonIpOption); + + // daemonPort option + QCommandLineOption daemonPortOption(QStringList() << "dp" + << "daemonPort", + QCoreApplication::translate("main", "set gui server port"), + QCoreApplication::translate("main", "daemonPort")); + parser.addOption(daemonPortOption); + + // baudrate option + QCommandLineOption baudrateOption("b", + QCoreApplication::translate("main", "set baudrate for serial connection"), + QCoreApplication::translate("main", "baudrate")); + parser.addOption(baudrateOption); + + // discriminator thresholds: + QCommandLineOption discr1Option(QStringList() << "discr1" + << "thresh1" + << "th1", + QCoreApplication::translate("main", + "set discriminator 1 threshold in Volts"), + QCoreApplication::translate("main", "threshold1")); + parser.addOption(discr1Option); + QCommandLineOption discr2Option(QStringList() << "discr2" + << "thresh2" + << "th2", + QCoreApplication::translate("main", + "set discriminator 2 threshold in Volts"), + QCoreApplication::translate("main", "threshold2")); + parser.addOption(discr2Option); + + // pcaPortMask to select signal to ublox + QCommandLineOption pcaPortMaskOption(QStringList() << "pca" + << "signal", + QCoreApplication::translate("main", "set input signal for ublox interrupt pin:" + "\n0 - coincidence (AND)" + "\n1 - anti-coincidence (XOR)" + "\n2 - discr 1" + "\n3 - discr 2" + "\n4 - vcc" + "\n5 - timepulse" + "\n6 - N/A" + "\n7 - ext signal"), + QCoreApplication::translate("main", "channel")); + parser.addOption(pcaPortMaskOption); + + // biasVoltage for SiPM + QCommandLineOption biasVoltageOption(QStringList() << "bias" + << "vout", + QCoreApplication::translate("main", "set bias voltage for SiPM"), + QCoreApplication::translate("main", "bias voltage")); + parser.addOption(biasVoltageOption); + + // biasVoltage on or off + QCommandLineOption biasPowerOnOff(QStringList() << "p", + QCoreApplication::translate("main", "bias voltage on or off")); + parser.addOption(biasPowerOnOff); + + // preamps on: + QCommandLineOption preamp1Option(QStringList() << "pre1" + << "preamp1", + QCoreApplication::translate("main", "preamplifier channel 1 on/off (0/1)")); + parser.addOption(preamp1Option); + QCommandLineOption preamp2Option(QStringList() << "pre2" + << "preamp2", + QCoreApplication::translate("main", "preamplifier channel 2 on/off (0/1)")); + parser.addOption(preamp2Option); + + // gain: + QCommandLineOption gainOption(QStringList() << "g" + << "gain", + QCoreApplication::translate("main", "peak detector high gain select")); + parser.addOption(gainOption); + + // event trigger for ADC + QCommandLineOption eventInputOption(QStringList() << "t" + << "trigger", + QCoreApplication::translate("main", "event (trigger) signal input:" + "\n0 - coincidence (AND)" + "\n1 - anti-coincidence (XOR)"), + QCoreApplication::translate("main", "trigger")); + parser.addOption(eventInputOption); + + // input polarity switch: + QCommandLineOption pol1Option(QStringList() << "pol1" + << "polarity1", + QCoreApplication::translate("main", "input polarity ch1 negative (0) or positive (1)")); + parser.addOption(pol1Option); + QCommandLineOption pol2Option(QStringList() << "pol2" + << "polarity2", + QCoreApplication::translate("main", "input polarity ch2 negative (0) or positive (1)")); + parser.addOption(pol2Option); + + // process the actual command line arguments given by the user + parser.process(a); + const QStringList args = parser.positionalArguments(); + if (args.size() > 1) { + qWarning() << "you set additional positional arguments but the program does not use them"; + } + + Daemon::configuration daemonConfig; + + bool ok; + if (parser.isSet(verbosityOption)) { + verbose = parser.value(verbosityOption).toInt(&ok); + if (!ok) { + verbose = 0; + qWarning() << "wrong verbosity level selection...setting to 0"; + } + } + daemonConfig.verbose = verbose; + + try { + daemonConfig.maxGeohashLength = cfg.lookup("max_geohash_length"); + } catch (const libconfig::SettingNotFoundException&) { + } + + try { + daemonConfig.storeLocal = cfg.lookup("store_local"); + } catch (const libconfig::SettingNotFoundException&) { + } + + // setup all variables for ublox module manager, then make the object run + if (!args.empty() && args.at(0) != "") { + daemonConfig.gpsdevname = args.at(0); + } else + try { + std::string gpsdevnameCfg = cfg.lookup("ublox_device"); + if (verbose > 2) + std::cout << "ublox device: " << gpsdevnameCfg << std::endl; + daemonConfig.gpsdevname = QString::fromStdString(gpsdevnameCfg); + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'ublox_device' setting in configuration file. Will guess..."; + QDir directory("/dev", "*", QDir::Name, QDir::System); + QStringList serialports = directory.entryList(QStringList({ "ttyS0", "ttyAMA0", "serial0" })); + if (!serialports.empty()) { + daemonConfig.gpsdevname = QString("/dev/" + serialports.last()); + qInfo() << "detected" << daemonConfig.gpsdevname << "as most probable candidate"; + } else { + qCritical() << "no device selected, will not connect to GNSS module" << endl; + } + } + + if (verbose > 4) { + qDebug() << "int main running in thread" + << QString("0x%1").arg(reinterpret_cast(QCoreApplication::instance()->thread())); + } + daemonConfig.dumpRaw = parser.isSet(dumpRawOption); + if (parser.isSet(baudrateOption)) { + daemonConfig.baudrate = parser.value(baudrateOption).toInt(&ok); + if (!ok || daemonConfig.baudrate < 0) { + daemonConfig.baudrate = 9600; + qWarning() << "wrong input for baudrate...using default:" << daemonConfig.baudrate; + } + } else + try { + int baudrateCfg = cfg.lookup("ublox_baud"); + if (verbose > 2) + qInfo() << "ublox baudrate:" << baudrateCfg; + daemonConfig.baudrate = baudrateCfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + if (verbose > 1) + qWarning() << "No 'ublox_baud' setting in configuration file. Assuming" << daemonConfig.baudrate; + } + + daemonConfig.configGnss = parser.isSet(showGnssConfigOption); + if (parser.isSet(peerPortOption)) { + daemonConfig.peerPort = parser.value(peerPortOption).toUInt(&ok); + if (!ok) { + daemonConfig.peerPort = 0; + qCritical() << "wrong input peerPort (maybe not an integer)"; + } + } + if (parser.isSet(peerIpOption)) { + daemonConfig.peerAddress = parser.value(peerIpOption); + if (!QHostAddress(daemonConfig.peerAddress).toIPv4Address()) { + if (daemonConfig.peerAddress != "localhost" && daemonConfig.peerAddress != "local") { + daemonConfig.peerAddress = ""; + qCritical() << "wrong input ipAddress, not an ipv4address"; + } + } + } + try { + int port = cfg.lookup("tcp_port"); + daemonConfig.serverPort = static_cast(port); + } catch (const libconfig::SettingNotFoundException&) { + } + if (parser.isSet(daemonPortOption)) { + daemonConfig.serverPort = parser.value(daemonPortOption).toUInt(&ok); + if (!ok) { + daemonConfig.peerPort = 0; + qCritical() << "wrong input peerPort (maybe not an integer)"; + } + } + if (parser.isSet(daemonIpOption)) { + daemonConfig.serverAddress = parser.value(daemonIpOption); + if (!QHostAddress(daemonConfig.serverAddress).toIPv4Address()) { + if (daemonConfig.serverAddress != "localhost" && daemonConfig.serverAddress != "local") { + daemonConfig.serverAddress = ""; + qCritical() << "wrong daemon ipAddress, not an ipv4address"; + } + } + } + + if (parser.isSet(pcaPortMaskOption)) { + daemonConfig.pcaPortMask = parser.value(pcaPortMaskOption).toUInt(&ok); + if (!ok) { + daemonConfig.pcaPortMask = 0; + qCritical() << "wrong input pcaPortMask (maybe not an unsigned integer)"; + } + } else + try { + int pcaPortMaskCfg = cfg.lookup("timing_input"); + if (verbose > 2) + qDebug() << "timing input: " << pcaPortMaskCfg << endl; + daemonConfig.pcaPortMask = pcaPortMaskCfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'timing_input' setting in configuration file. Assuming" << (int)daemonConfig.pcaPortMask; + } + + daemonConfig.showout = parser.isSet(showoutOption); + daemonConfig.showin = parser.isSet(showinOption); + + if (parser.isSet(discr1Option)) { + daemonConfig.dacThresh[0] = parser.value(discr1Option).toFloat(&ok); + if (!ok) { + daemonConfig.dacThresh[0] = -1.; + qCritical() << "error in value for discr1 (maybe not a float)"; + } + } + if (parser.isSet(discr2Option)) { + daemonConfig.dacThresh[1] = parser.value(discr2Option).toFloat(&ok); + if (!ok) { + daemonConfig.dacThresh[1] = -1.; + qCritical() << "error in value for discr2 (maybe not a float)"; + } + } + if (parser.isSet(biasVoltageOption)) { + daemonConfig.biasVoltage = parser.value(biasVoltageOption).toFloat(&ok); + if (!ok) { + daemonConfig.biasVoltage = -1.; + qCritical() << "error in value for biasVoltage (maybe not a float)"; + } + } + + if (parser.isSet(biasPowerOnOff)) { + daemonConfig.bias_ON = true; + } else + try { + int biasPowerCfg = cfg.lookup("bias_switch"); + if (verbose > 2) + qDebug() << "bias switch:" << biasPowerCfg; + daemonConfig.bias_ON = biasPowerCfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'bias_switch' setting in configuration file. Assuming" << (int)daemonConfig.bias_ON; + } + + if (parser.isSet(preamp1Option)) { + daemonConfig.preamp[0] = true; + } else + try { + int preamp1Cfg = cfg.lookup("preamp1_switch"); + if (verbose > 2) + qDebug() << "preamp1 switch:" << preamp1Cfg; + daemonConfig.preamp[0] = preamp1Cfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'preamp1_switch' setting in configuration file. Assuming" << (int)daemonConfig.preamp[0]; + } + + if (parser.isSet(preamp2Option)) { + daemonConfig.preamp[1] = true; + } else + try { + int preamp2Cfg = cfg.lookup("preamp2_switch"); + if (verbose > 2) + qDebug() << "preamp2 switch:" << preamp2Cfg; + daemonConfig.preamp[1] = preamp2Cfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'preamp2_switch' setting in configuration file. Assuming " << (int)daemonConfig.preamp[1]; + } + + if (parser.isSet(gainOption)) { + daemonConfig.gain = true; + } else { + try { + int gainCfg = cfg.lookup("gain_switch"); + if (verbose > 2) qDebug() << "gain switch:" << gainCfg; + daemonConfig.gain = gainCfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + if (verbose > 0) + qWarning() << "No 'gain_switch' setting in configuration file. Assuming" << (int)daemonConfig.gain; + } + } + + int eventTriggerCfg { -1 }; + daemonConfig.eventTrigger = EVT_AND; + if ( parser.isSet( eventInputOption ) ) { + eventTriggerCfg = parser.value(eventInputOption).toInt(&ok); + if ( !ok || eventTriggerCfg > 3 ) { + qCritical() << "wrong trigger input signal (valid: 0..3)"; + return -1; + } + } else try { + eventTriggerCfg = cfg.lookup("trigger_input"); + if (verbose > 2) qDebug() << "event trigger : " << eventTriggerCfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'trigger_input' setting in configuration file. Assuming signal" << GPIO_SIGNAL_MAP[daemonConfig.eventTrigger].name; + } + + switch (eventTriggerCfg) { + case 0: + daemonConfig.eventTrigger = EVT_XOR; + break; + case 1: + daemonConfig.eventTrigger = EVT_AND; + break; + case 2: + daemonConfig.eventTrigger = TIME_MEAS_OUT; + break; + case 3: + daemonConfig.eventTrigger = EXT_TRIGGER; + break; + default: + daemonConfig.eventTrigger = EVT_AND; + break; + } + + if (parser.isSet(pol1Option)) { + unsigned int pol1int = parser.value(pol1Option).toUInt(&ok); + if (!ok || pol1int > 1) { + qCritical() << "wrong input polarity setting ch1 (valid: 0..3)"; + return -1; + } else { + daemonConfig.polarity[0] = (bool)pol1int; + } + } else { + try { + int pol1Cfg = cfg.lookup("input1_polarity"); + if (verbose > 2) + qDebug() << "input polarity ch1:" << pol1Cfg; + daemonConfig.polarity[0] = (bool)pol1Cfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + if (verbose > 0) + qWarning() << "No 'input1_polarity' setting in configuration file. Assuming" << (int)daemonConfig.polarity[0]; + } + } + + if (parser.isSet(pol2Option)) { + unsigned int pol2int = parser.value(pol2Option).toUInt(&ok); + if (!ok || pol2int > 1) { + qCritical() << "wrong input polarity setting ch2 (valid: 0,1)"; + return -1; + } else { + daemonConfig.polarity[1] = (bool)pol2int; + } + } else { + try { + int pol2Cfg = cfg.lookup("input2_polarity"); + if (verbose > 2) + qDebug() << "input polarity ch2:" << pol2Cfg; + daemonConfig.polarity[1] = (bool)pol2Cfg; + } catch (const libconfig::SettingNotFoundException& nfex) { + if (verbose > 0) + qWarning() << "No 'input2_polarity' setting in configuration file. Assuming" << (int)daemonConfig.polarity[1]; + } + } + + try { + std::string userNameCfg = cfg.lookup("mqtt_user"); + std::string passwordCfg = cfg.lookup("mqtt_password"); + if (verbose > 2) + qDebug() << "mqtt user: " << QString::fromStdString(userNameCfg) << " passw: " << QString::fromStdString(passwordCfg); + + daemonConfig.username = QString::fromStdString(userNameCfg); + daemonConfig.password = QString::fromStdString(passwordCfg); + } catch (const libconfig::SettingNotFoundException& nfex) { + if (verbose > 1) + qDebug() << "No 'mqtt_user' or 'mqtt_password' setting in configuration file. Will continue with previously stored credentials"; + } + + if (parser.isSet(stationIdOption)) { + daemonConfig.station_ID = parser.value(stationIdOption); + } else { + // Get the station id from config, if it exists + try { + std::string stationIdString = cfg.lookup("stationID"); + if (verbose) + qInfo() << "station id: " << QString::fromStdString(stationIdString); + daemonConfig.station_ID = QString::fromStdString(stationIdString); + } catch (const libconfig::SettingNotFoundException& nfex) { + qWarning() << "No 'stationID' setting in configuration file. Assuming stationID='0'"; + } + } + + Daemon daemon { daemonConfig }; + + return a.exec(); +} diff --git a/source/daemon/src/man/man1/muondetector-daemon.1 b/daemon/src/man/man1/muondetector-daemon.1 similarity index 100% rename from source/daemon/src/man/man1/muondetector-daemon.1 rename to daemon/src/man/man1/muondetector-daemon.1 diff --git a/source/daemon/src/man/pack_all_man.sh b/daemon/src/man/pack_all_man.sh similarity index 100% rename from source/daemon/src/man/pack_all_man.sh rename to daemon/src/man/pack_all_man.sh diff --git a/source/daemon/src/man/unpack_all_man.sh b/daemon/src/man/unpack_all_man.sh similarity index 100% rename from source/daemon/src/man/unpack_all_man.sh rename to daemon/src/man/unpack_all_man.sh diff --git a/source/daemon/src/muondetector-login.cpp b/daemon/src/muondetector-login.cpp similarity index 78% rename from source/daemon/src/muondetector-login.cpp rename to daemon/src/muondetector-login.cpp index e2eb96a6..74d63eed 100644 --- a/source/daemon/src/muondetector-login.cpp +++ b/daemon/src/muondetector-login.cpp @@ -6,22 +6,20 @@ #include #include #include +#include #include #include #include #include #include -//#include #include #include #include #include #include -#include #include "mqtthandler.h" - [[nodiscard]] auto getch() -> char; [[nodiscard]] auto getpass(const char* prompt, const bool show_asterisk) -> std::string; @@ -55,7 +53,7 @@ auto getpass(const char* prompt, const bool show_asterisk) -> std::string std::string password {}; char ch { getch() }; - std::cout << prompt << std::endl; + std::cout << prompt; while ((ch = getch()) != RETURN) { if (ch == BACKSPACE) { if (password.length() != 0) { @@ -123,15 +121,10 @@ auto getMacAddress() -> QString auto getMacAddressByteArray() -> QByteArray { - // QString::fromLocal8Bit(temp.data()).toStdString(); - // return QByteArray(getMacAddress().toStdString().c_str()); - // return QByteArray::fromStdString(getMacAddress().toStdString()); QString mac { getMacAddress() }; - // qDebug()<<"MAC address: "<> username; - std::string password { getpass("please enter password:", true) }; - QString hashedMacAddress { QString{QCryptographicHash::hash(getMacAddressByteArray(), QCryptographicHash::Sha224).toHex() } }; + std::string password { getpass("password: ", true) }; + QString hashedMacAddress { QString { QCryptographicHash::hash(getMacAddressByteArray(), QCryptographicHash::Sha224).toHex() } }; QDir temp; - QString saveDirPath{ "/var/muondetector/" + hashedMacAddress }; - if (!temp.exists(saveDirPath)){ + QString saveDirPath { "/var/muondetector/" + hashedMacAddress }; + if (!temp.exists(saveDirPath)) { temp.mkpath(saveDirPath); - if (!temp.exists(saveDirPath)){ + if (!temp.exists(saveDirPath)) { qFatal(QString("Could not create folder " + saveDirPath + ". Make sure the program is started with the correct permissions.").toStdString().c_str()); } } - if (!saveLoginData(QString{saveDirPath + "/loginData.save"},QString::fromStdString(username), QString::fromStdString(password))){ + if (!saveLoginData(QString { saveDirPath + "/loginData.save" }, QString::fromStdString(username), QString::fromStdString(password))) { return 1; } - MuonPi::MqttHandler mqttHandler {""}; + MuonPi::MqttHandler mqttHandler { "" }; std::unique_ptr context { new QObject }; QObject::connect(&mqttHandler, &MuonPi::MqttHandler::mqttConnectionStatus, [context = std::move(context)](bool connected) mutable { if (connected) { - std::cout << "login data is correct!" << std::endl; - } - { - // std::cout << "invalid login data or server not - // reachable!" << std::endl; + std::cout << "login data is correct!\n"; } context.release(); }); diff --git a/source/daemon/src/pigpiodhandler.cpp b/daemon/src/pigpiodhandler.cpp similarity index 75% rename from source/daemon/src/pigpiodhandler.cpp rename to daemon/src/pigpiodhandler.cpp index eeedc01b..5cb45a3f 100644 --- a/source/daemon/src/pigpiodhandler.cpp +++ b/daemon/src/pigpiodhandler.cpp @@ -1,9 +1,12 @@ -#include #include -#include +#include +#include +#include #include +#include "utility/gpio_mapping.h" +#include "pigpiodhandler.h" #include -#include +#include #include #include #include @@ -11,16 +14,11 @@ #include -//static int pi = -1; -static int spiHandle = -1; -//static QPointer pigHandlerAddress; // QPointer automatically clears itself if pigHandler object is destroyed - constexpr char CONSUMER[] = "muonpi"; const std::string chipname { "/dev/gpiochip0" }; template inline static T sqr(T x) { return x*x; } -//inline static long double sqr(long double x) { return x*x; } /* linear regression algorithm @@ -32,52 +30,49 @@ inline static T sqr(T x) { return x*x; } *offs = output intercept *slope = output slope */ -void calcLinearCoefficients(int n, quint64 *xarray, qint64 *yarray, - double *offs, double* slope, int arrayIndex = 0) +void calcLinearCoefficients(int n, quint64* xarray, qint64* yarray, + double* offs, double* slope, int arrayIndex = 0) { - if (n<3) return; - - long double sumx = 0.0L; /* sum of x */ - long double sumx2 = 0.0L; /* sum of x**2 */ - long double sumxy = 0.0L; /* sum of x * y */ - long double sumy = 0.0L; /* sum of y */ - long double sumy2 = 0.0L; /* sum of y**2 */ - - int ix=arrayIndex; - if (ix==0) ix=n-1; - else ix--; - - quint64 offsx=xarray[ix]; - qint64 offsy=yarray[ix]; -// long long int offsy=0; - - int i; - for (i=0; i pigpioHandler = pigHandlerAddress; - if (pigpioHandler->isInhibited()) return; + if (pigpioHandler->isInhibited()) + return; - static uint32_t lastTriggerTick=0; - static uint32_t lastXorAndTick=0; - static uint32_t lastTick=0; - static uint16_t pileupCounter=0; + static uint32_t lastTriggerTick = 0; + static uint32_t lastTick = 0; + static uint16_t pileupCounter = 0; - // look, if the last event occured just recently (less than 100us ago) + // look, if the last event occured just recently // if so, count the pileup counter up // count down if not - if (tick-lastTick<100) pileupCounter++; - else if (pileupCounter>0) pileupCounter--; + if (tick - lastTick < MuonPi::Config::event_count_deadtime_ticks) + { + pileupCounter++; + // if more than a certain number of pileups happened in a short period of time, leave immediately + if (pileupCounter > MuonPi::Config::event_count_max_pileups) + { + pileupCounter = MuonPi::Config::event_count_max_pileups; + lastTick = tick; + return; + } + } else if (pileupCounter > 0) + { + pileupCounter--; + } - // if more than 50 pileups happened in a short period of time, leave immediately - if (pileupCounter>50) return; + lastTick = tick; - try{ + try { // allow only registered signals to be processed here - // if gpio pin fired which is not in GPIO_SIGNAL list, return immediately - auto it=std::find_if(GPIO_PINMAP.cbegin(), GPIO_PINMAP.cend(), - [&user_gpio](const std::pair& val) { - if (val.second==user_gpio) return true; - return false; - }); - if (it==GPIO_PINMAP.end()) return; - -// if (user_gpio == GPIO_PINMAP[ADC_READY]) { -// //std::cout<<"ADC conv ready"<gpioTickOverflowCounter + tick; quint64 t0 = pigpioHandler->startOfProgram.toMSecsSinceEpoch(); - long double meanDiff=pigpioHandler->clockMeasurementOffset; + long double meanDiff = pigpioHandler->clockMeasurementOffset; - long double dx=timestamp-pigpioHandler->lastTimeMeasurementTick; - long double dy=pigpioHandler->clockMeasurementSlope*dx; - meanDiff+=dy; + long double dx = timestamp - pigpioHandler->lastTimeMeasurementTick; + long double dy = pigpioHandler->clockMeasurementSlope * dx; + meanDiff += dy; - qint64 meanDiffInt=(qint64)meanDiff; - double meanDiffFrac=(meanDiff-(qint64)meanDiff); - timestamp+=meanDiffInt; // add diff to real time - long int ts_sec=timestamp/1000000+(t0/1000); // conv. us to s - long int ts_nsec=1000*(timestamp%1000000)+(t0 % 1000) * 1000000L; - ts_nsec+=(long int)(1000.*meanDiffFrac); + qint64 meanDiffInt = (qint64)meanDiff; + double meanDiffFrac = (meanDiff - (qint64)meanDiff); + timestamp += meanDiffInt; // add diff to real time + long int ts_sec = timestamp / 1000000 + (t0 / 1000); // conv. us to s + long int ts_nsec = 1000 * (timestamp % 1000000) + (t0 % 1000) * 1000000L; + ts_nsec += (long int)(1000. * meanDiffFrac); - long double ppsOffs = (ts_sec-ts.tv_sec)+ts_nsec*1e-9; -// qDebug() << "PPS Offset: " << (double)(ppsOffs)*1e6 << " us"; + long double ppsOffs = (ts_sec - ts.tv_sec) + ts_nsec * 1e-9; if (std::fabs(ppsOffs) < 3600.) { qint32 t_diff_us = (double)(ppsOffs)*1e6; emit pigpioHandler->timePulseDiff(t_diff_us); } -// qint32 t_diff_us=ts.tv_nsec/1000; -// if (t_diff_us>500000L) t_diff_us=t_diff_us-1000000L; - } - if (tick-lastXorAndTick > MuonPi::Config::event_count_deadtime_ticks) { - lastXorAndTick = tick; - emit pigpioHandler->signal(user_gpio); } + + emit pigpioHandler->signal(user_gpio); + // level gives the information if it is up or down (only important if trigger is // at both: rising and falling edge) - } - catch (std::exception& e) - { + } catch (std::exception& e) { pigpioHandler = 0; - //pigpio_stop(pi); + pigpio_stop(pi); qCritical() << "Exception catched in 'static void cbFunction(int user_pi, unsigned int user_gpio, unsigned int level, uint32_t tick)':" << e.what(); - qCritical() << "with user_pi="< #include -#include #include -#include +#include using namespace std; @@ -16,8 +16,16 @@ using namespace std; string QtSerialUblox::fProtVersionString = ""; +void QtSerialUblox::closeAll() +{ + if ((serialPort != nullptr) && (serialPort->isOpen())) { + serialPort->flush(); + serialPort->close(); + } +} -std::string QtSerialUblox::toStdString(unsigned char* data, int dataSize) { +std::string QtSerialUblox::toStdString(unsigned char* data, int dataSize) +{ std::stringstream tempStream; for (int i = 0; i < dataSize; i++) { tempStream << data[i]; @@ -26,7 +34,8 @@ std::string QtSerialUblox::toStdString(unsigned char* data, int dataSize) { } QtSerialUblox::QtSerialUblox(const QString serialPortName, int newTimeout, int baudRate, - bool newDumpRaw, int newVerbose, bool newShowout, bool newShowin, QObject *parent) : QObject(parent) + bool newDumpRaw, int newVerbose, bool newShowout, bool newShowin, QObject* parent) + : QObject(parent) { _portName = serialPortName; _baudRate = baudRate; @@ -37,10 +46,11 @@ QtSerialUblox::QtSerialUblox(const QString serialPortName, int newTimeout, int b timeout = newTimeout; } -void QtSerialUblox::makeConnection() { +void QtSerialUblox::makeConnection() +{ // this function gets called with a signal from client-thread // (QtSerialUblox runs in a separate thread only communicating with main thread through messages) - if (verbose>4){ + if (verbose > 4) { qInfo() << this->thread()->objectName() << " thread id (pid): " << syscall(SYS_gettid); } if (!serialPort.isNull()) { @@ -51,9 +61,9 @@ void QtSerialUblox::makeConnection() { if (!serialPort->open(QIODevice::ReadWrite)) { emit gpsConnectionError(); emit toConsole(QObject::tr("Failed to open port %1, error: %2\ntrying again in %3 seconds\n") - .arg(_portName) - .arg(serialPort->errorString()) - .arg(timeout)); + .arg(_portName) + .arg(serialPort->errorString()) + .arg(timeout)); serialPort.clear(); delay(timeout); emit gpsRestart(); @@ -69,26 +79,31 @@ void QtSerialUblox::makeConnection() { } } -void QtSerialUblox::sendQueuedMsg(bool afterTimeout) { +void QtSerialUblox::sendQueuedMsg(bool afterTimeout) +{ if (afterTimeout) { - if (msgWaitingForAck==nullptr) { + if (msgWaitingForAck == nullptr) { return; } if (++sendRetryCounter >= MAX_SEND_RETRIES) { - sendRetryCounter=0; + sendRetryCounter = 0; ackTimer->stop(); delete msgWaitingForAck; msgWaitingForAck = nullptr; - if (verbose > 1) emit toConsole("sendQueuedMsg: deleted message after 5 timeouts\n"); + if (verbose > 1) + emit toConsole("sendQueuedMsg: deleted message after 5 timeouts\n"); sendQueuedMsg(); return; } ackTimer->start(timeout); sendUBX(*msgWaitingForAck); - if (verbose > 1) emit toConsole("sendQueuedMsg: repeated resend after timeout\n"); + if (verbose > 1) + emit toConsole("sendQueuedMsg: repeated resend after timeout\n"); + return; + } + if (outMsgBuffer.empty()) { return; } - if (outMsgBuffer.empty()) { return; } if (msgWaitingForAck) { if (verbose > 1) { emit toConsole("tried to send queued message but ack for previous message not yet received\n"); @@ -100,18 +115,20 @@ void QtSerialUblox::sendQueuedMsg(bool afterTimeout) { ackTimer->setSingleShot(true); ackTimer->start(timeout); sendUBX(*msgWaitingForAck); - if (verbose > 2) emit toConsole("sendQueuedMsg: sent fresh message\n"); + if (verbose > 2) + emit toConsole("sendQueuedMsg: sent fresh message\n"); outMsgBuffer.pop(); } -void QtSerialUblox::ackTimeout() { - if (msgWaitingForAck==nullptr) { +void QtSerialUblox::ackTimeout() +{ + if (msgWaitingForAck == nullptr) { return; } if (verbose > 1) { std::stringstream tempStream; tempStream << "ack timeout, trying to resend message 0x" << std::setfill('0') << std::setw(2) << hex - << ((msgWaitingForAck->msgID & 0xff00) >> 8) << " 0x" << std::setfill('0') << std::setw(2) << hex << (msgWaitingForAck->msgID & 0x00ff); + << ((msgWaitingForAck->msgID & 0xff00) >> 8) << " 0x" << std::setfill('0') << std::setw(2) << hex << (msgWaitingForAck->msgID & 0x00ff); for (unsigned int i = 0; i < msgWaitingForAck->data.length(); i++) { tempStream << " 0x" << std::setfill('0') << std::setw(2) << hex << (int)(msgWaitingForAck->data[i]); } @@ -121,26 +138,19 @@ void QtSerialUblox::ackTimeout() { sendQueuedMsg(true); } -void QtSerialUblox::onReadyRead() { +void QtSerialUblox::onReadyRead() +{ // this function gets called when the serial port emits readyRead signal - //cout << "\nstart readyread" <readAll(); if (dumpRaw) { emit toConsole(QString(temp)); - // if put std::string to console it gets stuck!? - //emit stdToConsole(temp.toStdString()); } - //buffer += temp.toStdString(); -// buffer += QString::fromLocal8Bit(temp.data()).toStdString(); - for (int i=0; i(0xb5); refstr += 0x62; std::size_t found = buffer.find(refstr); std::string mess = ""; - if (found != string::npos) - { + if (found != string::npos) { mess = buffer.substr(found, buffer.size()); // discard everything before start of the message buffer.erase(0, found); - } - else { + } else { // discard everything before the start of a NMEA message, too // to ensure that buffer won't grow too big if (discardAllNMEA) { @@ -192,11 +201,10 @@ bool QtSerialUblox::scanUnknownMessage(string &buffer, UbxMessage &message) } return false; } - // message.classID = (uint8_t)mess[2]; - // message.messageID = (uint8_t)mess[3]; message.msgID = (uint16_t)mess[2] << 8; message.msgID += (uint16_t)mess[3]; - if (mess.size() < 8) return false; + if (mess.size() < 8) + return false; int len = (int)(mess[4]); len += ((int)(mess[5])) << 8; if (((long int)mess.size() - 8) < len) { @@ -205,8 +213,9 @@ bool QtSerialUblox::scanUnknownMessage(string &buffer, UbxMessage &message) if (verbose > 1) { std::stringstream tempStream; tempStream << "received faulty UBX string:\n " << dec; - for (std::string::size_type i = 0; i < found; i++) tempStream - << setw(2) << hex << "0x" << (int)buffer[i] << " "; + for (std::string::size_type i = 0; i < found; i++) + tempStream + << setw(2) << hex << "0x" << (int)buffer[i] << " "; tempStream << endl; emit toConsole(QString::fromStdString(tempStream.str())); } @@ -219,8 +228,7 @@ bool QtSerialUblox::scanUnknownMessage(string &buffer, UbxMessage &message) unsigned char chkA; unsigned char chkB; calcChkSum(mess.substr(0, len + 6), &chkA, &chkB); - if (mess[len + 6] == chkA && mess[len + 7] == chkB) - { + if (mess[len + 6] == chkA && mess[len + 7] == chkB) { message.data = mess.substr(6, len); return true; } @@ -230,12 +238,6 @@ bool QtSerialUblox::scanUnknownMessage(string &buffer, UbxMessage &message) bool QtSerialUblox::sendUBX(uint16_t msgID, const std::string& payload, uint16_t nBytes) { - // std::cout << "0x"<< std::setfill('0') << std::setw(2) << std::hex << ((msgID & 0xff00) >> 8) - // << std::setfill('0') << std::setw(2) << std::hex << (msgID & 0xff); - // for (int i = 0; i(0xb5); s += 0x62; @@ -243,18 +245,12 @@ bool QtSerialUblox::sendUBX(uint16_t msgID, const std::string& payload, uint16_t s += (unsigned char)(msgID & 0xff); s += (unsigned char)(nBytes & 0xff); s += (unsigned char)((nBytes & 0xff00) >> 8); - for (int i = 0; i < nBytes; i++) s += payload[i]; + for (int i = 0; i < nBytes; i++) + s += payload[i]; unsigned char chkA, chkB; calcChkSum(s, &chkA, &chkB); s += chkA; s += chkB; - // cout<write(block)) { @@ -269,22 +265,20 @@ bool QtSerialUblox::sendUBX(uint16_t msgID, const std::string& payload, uint16_t emit toConsole(QString::fromStdString(tempStream.str())); } return true; - } - else { + } else { emit toConsole("wait for bytes written timeout while trying to write to serialPort"); } - } - else { + } else { emit toConsole("error writing to serialPort"); } - } - else { + } else { emit toConsole("error: serialPort not instantiated"); } return false; } -bool QtSerialUblox::sendUBX(uint16_t msgID, unsigned char* payload, uint16_t nBytes) { +bool QtSerialUblox::sendUBX(uint16_t msgID, unsigned char* payload, uint16_t nBytes) +{ std::stringstream payloadStream; std::string payloadString; for (int i = 0; i < nBytes; i++) { @@ -294,7 +288,8 @@ bool QtSerialUblox::sendUBX(uint16_t msgID, unsigned char* payload, uint16_t nBy return sendUBX(msgID, payloadString, nBytes); } -bool QtSerialUblox::sendUBX(UbxMessage &msg) { +bool QtSerialUblox::sendUBX(UbxMessage& msg) +{ return sendUBX(msg.msgID, msg.data, msg.data.size()); } @@ -303,8 +298,7 @@ void QtSerialUblox::calcChkSum(const std::string& buf, unsigned char* chkA, unsi // calc Fletcher checksum, ignore the message header (b5 62) *chkA = 0; *chkB = 0; - for (std::string::size_type i = 2; i < buf.size(); i++) - { + for (std::string::size_type i = 2; i < buf.size(); i++) { *chkA += buf[i]; *chkB += *chkA; } @@ -313,15 +307,14 @@ void QtSerialUblox::calcChkSum(const std::string& buf, unsigned char* chkA, unsi void QtSerialUblox::UBXSetCfgRate(uint16_t measRate, uint16_t navRate) { if (verbose > 3) { - emit toConsole(QString("Ublox UBXsetCfgRate running in thread " + QString("0x%1\n") - .arg((int)syscall(SYS_gettid)))); + emit toConsole(QString("Ublox UBXsetCfgRate running in thread " + QString("0x%1\n").arg((int)syscall(SYS_gettid)))); } unsigned char data[6]; // initialise all contents from data as 0 first! for (int i = 0; i < 6; i++) { data[i] = 0; } - if (measRate < 10 || navRate < 1 || navRate>127) { + if (measRate < 10 || navRate < 1 || navRate > 127) { emit UBXCfgError("measRate <10 || navRate<1 || navRate>127 error"); } data[0] = measRate & 0xff; @@ -332,31 +325,12 @@ void QtSerialUblox::UBXSetCfgRate(uint16_t measRate, uint16_t navRate) data[5] = 0; enqueueMsg(UBX_CFG_RATE, toStdString(data, 6)); - -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_RATE; - newMessage.data = toStdString(data, 6); - outMsgBuffer.push(newMessage); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } -*/ - // sendUBX(UBX_CFG_RATE, data, sizeof(data)); - /* Ack check has to be done differently, asynchronously - if (waitAck(UBX_CFG_RATE, 10000)) - { - emit toConsole("Set CFG successful"); - } - else { - emit UBXCfgError("Set CFG timeout"); - }*/ } -void QtSerialUblox::UBXSetCfgPrt(uint8_t port, uint8_t outProtocolMask) { +void QtSerialUblox::UBXSetCfgPrt(uint8_t port, uint8_t outProtocolMask) +{ if (verbose > 3) { - emit toConsole(QString("Ublox UBXSetCfgPort running in thread " + QString("0x%1\n") - .arg((int)syscall(SYS_gettid)))); + emit toConsole(QString("Ublox UBXSetCfgPort running in thread " + QString("0x%1\n").arg((int)syscall(SYS_gettid)))); } unsigned char data[20]; // initialise all contents from data as 0 first! @@ -375,7 +349,7 @@ void QtSerialUblox::UBXSetCfgPrt(uint8_t port, uint8_t outProtocolMask) { data[3] = 0; // txReady options (not used) // mode option: data[4] = 0b11000000; // charLen option (first 2 bits): 11 means 8 bit character length. - // (10 means 7 bit character length only with parity enabled) + // (10 means 7 bit character length only with parity enabled) data[5] = 0b00001000; // first 2 bits unimportant. 00 -> 1 stop bit. 100 -> no parity. last bit unimportant. data[6] = 0; data[7] = 0; //part of mode option but no meaning @@ -391,7 +365,6 @@ void QtSerialUblox::UBXSetCfgPrt(uint8_t port, uint8_t outProtocolMask) { data[13] = 0; //has no meaning but part of inProtoMask // outProtoMask enables/disables protocols for receiving messages from the gps module: - //data[14] = 0b00100011; // () () (RTCM3) () () () (NMEA) (UBX) FOR EXAMPLE data[14] = outProtocolMask; data[15] = 0; //has no meaning but part of outProtoMask @@ -401,25 +374,14 @@ void QtSerialUblox::UBXSetCfgPrt(uint8_t port, uint8_t outProtocolMask) { data[18] = 0; data[19] = 0; // reserved } - // sendUBX(UBX_CFG_PRT, data, 20); enqueueMsg(UBX_CFG_PRT, toStdString(data, 20)); -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_PRT; - newMessage.data = toStdString(data, 20); - outMsgBuffer.push(newMessage); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } -*/ } void QtSerialUblox::UBXSetCfgMsgRate(uint16_t msgID, uint8_t port, uint8_t rate) { // set message rate on port. (rate 1 means every intervall the messages is sent) // if port = -1 set all ports if (verbose > 3) { - emit toConsole(QString("Ublox UBXsetCfgMsg running in thread " + QString("0x%1\n") - .arg((int)syscall(SYS_gettid)))); + emit toConsole(QString("Ublox UBXsetCfgMsg running in thread " + QString("0x%1\n").arg((int)syscall(SYS_gettid)))); } unsigned char data[8]; // initialise all contents from data as 0 first! @@ -431,35 +393,15 @@ void QtSerialUblox::UBXSetCfgMsgRate(uint16_t msgID, uint8_t port, uint8_t rate) } data[0] = (uint8_t)((msgID & 0xff00) >> 8); data[1] = msgID & 0xff; - // cout<<"data[0]="<<(int)data[0]<<" data[1]="<<(int)data[1]<> 16; uint8_t resetMode = resetFlags & 0xff; unsigned char data[4]; - data[0]=navBbrMask & 0xff; - data [1]=(navBbrMask & 0xff00)>>8; - data[2]=resetMode; - data[3]=0; + data[0] = navBbrMask & 0xff; + data[1] = (navBbrMask & 0xff00) >> 8; + data[2] = resetMode; + data[3] = 0; UbxMessage newMessage; newMessage.msgID = UBX_CFG_RST; @@ -480,58 +422,48 @@ void QtSerialUblox::UBXReset(uint32_t resetFlags) void QtSerialUblox::UBXSetMinMaxSVs(uint8_t minSVs, uint8_t maxSVs) { -// uint16_t mask1 = 0x04; unsigned char data[40]; - data[2]=0x04; // MinMax flag in mask 1 - data[3]=0x00; // all other flags are zero - data[4]=0; data[5]=0; data[6]=0; data[7]=0; - data[10]=minSVs; - data[11]=maxSVs; + data[2] = 0x04; // MinMax flag in mask 1 + data[3] = 0x00; // all other flags are zero + data[4] = 0; + data[5] = 0; + data[6] = 0; + data[7] = 0; + data[10] = minSVs; + data[11] = maxSVs; enqueueMsg(UBX_CFG_NAVX5, toStdString(data, 40)); -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_NAVX5; - newMessage.data = toStdString(data, 40); - sendUBX(newMessage); -*/ } void QtSerialUblox::UBXSetMinCNO(uint8_t minCNO) { unsigned char data[40]; - data[2]=0x08; // minCNO flag in mask 1 - data[3]=0x00; // all other flags are zero - data[4]=0; data[5]=0; data[6]=0; data[7]=0; - data[12]=minCNO; + data[2] = 0x08; // minCNO flag in mask 1 + data[3] = 0x00; // all other flags are zero + data[4] = 0; + data[5] = 0; + data[6] = 0; + data[7] = 0; + data[12] = minCNO; enqueueMsg(UBX_CFG_NAVX5, toStdString(data, 40)); -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_NAVX5; - newMessage.data = toStdString(data, 40); - sendUBX(newMessage); -*/ } void QtSerialUblox::UBXSetAopCfg(bool enable, uint16_t maxOrbErr) { unsigned char data[40]; - data[2]=0x00; // aop flag in mask 2 - data[3]=0x40; // all other flags are zero - data[4]=0; data[5]=0; data[6]=0; data[7]=0; + data[2] = 0x00; // aop flag in mask 2 + data[3] = 0x40; // all other flags are zero + data[4] = 0; + data[5] = 0; + data[6] = 0; + data[7] = 0; - data[27]=(uint8_t)enable; - data[30]=maxOrbErr & 0xff; - data[31]=(maxOrbErr>>8) & 0xff; + data[27] = (uint8_t)enable; + data[30] = maxOrbErr & 0xff; + data[31] = (maxOrbErr >> 8) & 0xff; enqueueMsg(UBX_CFG_NAVX5, toStdString(data, 40)); -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_NAVX5; - newMessage.data = toStdString(data, 40); - sendUBX(newMessage); -*/ } void QtSerialUblox::UBXSaveCfg(uint8_t devMask) @@ -539,21 +471,21 @@ void QtSerialUblox::UBXSaveCfg(uint8_t devMask) unsigned char data[13]; // select the following sections to save: // ioPort, msgCfg, navCfg, rxmCfg, antConf - uint32_t sectionMask=0x01 | 0x02 | 0x08 | 0x10 | 0x400; + uint32_t sectionMask = 0x01 | 0x02 | 0x08 | 0x10 | 0x400; - data[0]=data[1]=data[2]=data[3]=0x00; // clear mask is all zero - data[8]=data[9]=data[10]=data[11]=0x00; // load mask is all zero - data[4]=sectionMask & 0xff; - data[5]=(sectionMask>>8) & 0xff; - data[6]=(sectionMask>>16) & 0xff; - data[7]=(sectionMask>>24) & 0xff; - data[12]=devMask; + data[0] = data[1] = data[2] = data[3] = 0x00; // clear mask is all zero + data[8] = data[9] = data[10] = data[11] = 0x00; // load mask is all zero + data[4] = sectionMask & 0xff; + data[5] = (sectionMask >> 8) & 0xff; + data[6] = (sectionMask >> 16) & 0xff; + data[7] = (sectionMask >> 24) & 0xff; + data[12] = devMask; enqueueMsg(UBX_CFG_CFG, toStdString(data, 13)); } -void QtSerialUblox::onRequestGpsProperties(){ - +void QtSerialUblox::onRequestGpsProperties() +{ } void QtSerialUblox::delay(int millisecondsWait) @@ -565,23 +497,17 @@ void QtSerialUblox::delay(int millisecondsWait) loop.exec(); } -void QtSerialUblox::pollMsgRate(uint16_t msgID) { +void QtSerialUblox::pollMsgRate(uint16_t msgID) +{ UbxMessage msg; unsigned char temp[2]; temp[0] = (uint8_t)((msgID & 0xff00) >> 8); temp[1] = (uint8_t)(msgID & 0xff); enqueueMsg(UBX_CFG_MSG, toStdString(temp, 2)); -/* - msg.msgID = UBX_CFG_MSG; - msg.data = toStdString(temp, 2); - outMsgBuffer.push(msg); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } -*/ } -void QtSerialUblox::pollMsg(uint16_t msgID) { +void QtSerialUblox::pollMsg(uint16_t msgID) +{ UbxMessage msg; unsigned char temp[1]; switch (msgID) { @@ -607,52 +533,27 @@ void QtSerialUblox::pollMsg(uint16_t msgID) { msg.msgID = msgID; msg.data = ""; enqueueMsg(msgID, ""); -/* - outMsgBuffer.push(msg); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } -*/ -// sendUBX(msg); break; } } auto QtSerialUblox::getProtVersion() -> double { - //QLocale::setDefault(QLocale(QLocale::English, QLocale::UnitedStates)); - /*QLocale english(QLocale(QLocale::English, QLocale::UnitedStates)); - return english.toFloat(fProtVersionString); */ - //return 0.; - double verValue = 0.; - try { - verValue = std::stod(fProtVersionString); - } catch (std::exception&) - { - // emit toConsole("Exception catched : " + QString(e.what())); - } - return verValue; + double verValue = 0.; + try { + verValue = std::stod(fProtVersionString); + } catch (std::exception&) { + } + return verValue; } void QtSerialUblox::enqueueMsg(uint16_t msgID, const std::string& payload) { - //sendUBX(msgID, payload, nrBytes); - UbxMessage newMessage; - newMessage.msgID = msgID; - newMessage.data = payload; -// enqueueMsg(newMessage); - outMsgBuffer.push(newMessage); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } -} - -/* -void QtSerialUblox::enqueueMsg(const UbxMessage& msg) -{ - outMsgBuffer.push(msg); - if (!msgWaitingForAck) { - sendQueuedMsg(); - } + UbxMessage newMessage; + newMessage.msgID = msgID; + newMessage.data = payload; + outMsgBuffer.push(newMessage); + if (!msgWaitingForAck) { + sendQueuedMsg(); + } } -*/ diff --git a/source/daemon/src/qtserialublox_processmessages.cpp b/daemon/src/qtserialublox_processmessages.cpp similarity index 65% rename from source/daemon/src/qtserialublox_processmessages.cpp rename to daemon/src/qtserialublox_processmessages.cpp index 44de0b7f..93d63664 100644 --- a/source/daemon/src/qtserialublox_processmessages.cpp +++ b/daemon/src/qtserialublox_processmessages.cpp @@ -1,17 +1,19 @@ -#include -#include -#include -#include -#include -#include -#include -#include +#include "utility/custom_io_operators.h" +#include "utility/unixtime_from_gps.h" +#include "qtserialublox.h" + #include +#include + +#include +#include +#include +#include using namespace std; const uint8_t usedPort = 1; // this is the uart port. (0 = i2c; 1 = uart; 2 = usb; 3 = isp;) - // see u-blox8-M8_Receiver... pdf documentation site 170 + // see u-blox8-M8_Receiver... pdf documentation site 170 // all about processing different ubx-messages: void QtSerialUblox::processMessage(const UbxMessage& msg) { @@ -19,7 +21,6 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) uint8_t messageID = msg.msgID & 0xff; std::vector sats; std::stringstream tempStream; - //std::string temp; uint16_t ackedMsgID; switch (classID) { case 0x05: // UBX-ACK @@ -31,16 +32,18 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) if (verbose > 1) { tempStream << "received ACK message but no message is waiting for Ack (msgID: 0x"; tempStream << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[0] << " 0x" - << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << ")\n"; + << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } break; } if (verbose > 2) { - if (messageID==1) tempStream << "received UBX-ACK-ACK message about msgID: 0x"; - else tempStream << "received UBX-ACK-NACK message about msgID: 0x"; + if (messageID == 1) + tempStream << "received UBX-ACK-ACK message about msgID: 0x"; + else + tempStream << "received UBX-ACK-NACK message about msgID: 0x"; tempStream << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[0] << " 0x" - << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << "\n"; + << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << "\n"; emit toConsole(QString::fromStdString(tempStream.str())); } ackedMsgID = (uint16_t)(msg.data[0]) << 8 | msg.data[1]; @@ -48,18 +51,16 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) if (verbose > 1) { tempStream << "received unexpected UBX-ACK message about msgID: 0x"; tempStream << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[0] << " 0x" - << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << "\n"; + << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[1] << "\n"; emit toConsole(QString::fromStdString(tempStream.str())); } break; - } + } switch (messageID) { case 0x00: emit UBXReceivedAckNak(msgWaitingForAck->msgID, (uint16_t)(msgWaitingForAck->data[0]) << 8 - | msgWaitingForAck->data[1]); - // sendQueuedMsg(true); // tries to send the message again - // return; // ends with an endless loop if a message is just wrong... + | msgWaitingForAck->data[1]); break; default: break; @@ -67,7 +68,8 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) ackTimer->stop(); delete msgWaitingForAck; msgWaitingForAck = 0; - if (verbose > 2) emit toConsole("processMessage: deleted message after ACK/NACK\n"); + if (verbose > 2) + emit toConsole("processMessage: deleted message after ACK/NACK\n"); sendQueuedMsg(); break; case 0x01: // UBX-NAV @@ -75,7 +77,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x03: if (verbose > 2) { tempStream << "received UBX-NAV-STATUS message (0x" << std::hex << std::setfill('0') << std::setw(2) - << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; + << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXNavStatus(msg.data); @@ -83,7 +85,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x04: if (verbose > 2) { tempStream << "received UBX-NAV-DOP message (0x" << std::hex << std::setfill('0') << std::setw(2) - << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; + << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXNavDOP(msg.data); @@ -91,7 +93,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x20: if (verbose > 2) { tempStream << "received UBX-NAV-TIMEGPS message (0x" << std::hex << std::setfill('0') << std::setw(2) - << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; + << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXNavTimeGPS(msg.data); @@ -99,7 +101,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x21: if (verbose > 2) { tempStream << "received UBX-NAV-TIMEUTC message (0x" << std::hex << std::setw(2) - << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; + << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXNavTimeUTC(msg.data); @@ -107,7 +109,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x22: if (verbose > 2) { tempStream << "received UBX-NAV-CLOCK message (0x" << std::hex << std::setfill('0') << std::setw(2) - << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; + << (int)classID << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXNavClock(msg.data); @@ -116,39 +118,27 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) sats = UBXNavSVinfo(msg.data, true); if (verbose > 2) { tempStream << "received UBX-NAV-SVINFO message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - tempStream << "nr sats = "< 2) { tempStream << "received UBX-NAV-SAT message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } - //mutex.lock(); emit gpsPropertyUpdatedGnss(sats, m_satList.updateAge()); m_satList = sats; - //mutex.unlock(); - //break; -// tempStream<<"Satellite List: "< 2) { tempStream << "received UBX-NAV-POSLLH message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } geodeticPos = UBXNavPosLLH(msg.data); @@ -157,7 +147,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) default: if (verbose > 2) { tempStream << "received unhandled UBX-NAV message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -176,62 +166,61 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) break; case 0x06: // UBX-CFG switch (messageID) { - case 0x01: // UBX-CFG-MSG (message configuration) - emit UBXreceivedMsgRateCfg( - (((uint16_t)msg.data[0]) << 8) | ((uint16_t)msg.data[1]), - (uint8_t)(msg.data[2 + usedPort]) - ); - // 2: port 0 (i2c); 3: port 1 (uart); 4: port 2 (usb); 5: port 3 (isp) - break; - case 0x13: // UBX-CFG-ANT - if (verbose > 2) { - tempStream << "received UBX-CFG-ANT message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXCfgAnt(msg.data); - break; - case 0x24: // UBX-CFG-NAV5 - if (verbose > 2) { - tempStream << "received UBX-CFG-NAV5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXCfgNav5(msg.data); - break; - case 0x23: // UBX-CFG-NAVX5 - if (verbose > 2) { - tempStream << "received UBX-CFG-NAVX5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXCfgNavX5(msg.data); - break; - case 0x31: // UBX-CFG-TP5 - if (verbose > 2) { - tempStream << "received UBX-CFG-TP5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXCfgTP5(msg.data); - break; - case 0x3e: // UBX-CFG-GNSS - if (verbose > 2) { - tempStream << "received UBX-CFG-GNSS message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXCfgGNSS(msg.data); - break; - default: - if (verbose > 2) { - tempStream << "received unhandled UBX-CFG message:"; - for (std::string::size_type i = 0; i < msg.data.size(); i++) { - tempStream << " 0x" << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[i]; - } - tempStream << "\n"; - emit toConsole(QString::fromStdString(tempStream.str())); + case 0x01: // UBX-CFG-MSG (message configuration) + emit UBXreceivedMsgRateCfg( + (((uint16_t)msg.data[0]) << 8) | ((uint16_t)msg.data[1]), + (uint8_t)(msg.data[2 + usedPort])); + // 2: port 0 (i2c); 3: port 1 (uart); 4: port 2 (usb); 5: port 3 (isp) + break; + case 0x13: // UBX-CFG-ANT + if (verbose > 2) { + tempStream << "received UBX-CFG-ANT message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXCfgAnt(msg.data); + break; + case 0x24: // UBX-CFG-NAV5 + if (verbose > 2) { + tempStream << "received UBX-CFG-NAV5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXCfgNav5(msg.data); + break; + case 0x23: // UBX-CFG-NAVX5 + if (verbose > 2) { + tempStream << "received UBX-CFG-NAVX5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXCfgNavX5(msg.data); + break; + case 0x31: // UBX-CFG-TP5 + if (verbose > 2) { + tempStream << "received UBX-CFG-TP5 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXCfgTP5(msg.data); + break; + case 0x3e: // UBX-CFG-GNSS + if (verbose > 2) { + tempStream << "received UBX-CFG-GNSS message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXCfgGNSS(msg.data); + break; + default: + if (verbose > 2) { + tempStream << "received unhandled UBX-CFG message:"; + for (std::string::size_type i = 0; i < msg.data.size(); i++) { + tempStream << " 0x" << std::setfill('0') << std::setw(2) << std::hex << (int)msg.data[i]; } + tempStream << "\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } } break; case 0x10: // UBX-ESF @@ -251,7 +240,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) default: if (verbose > 2) { tempStream << "received unhandled UBX-INF message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -270,52 +259,52 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) break; case 0x0a: // UBX-MON switch (messageID) { - case (UBX_MON_RXBUF & 0xff): - if (verbose > 2) { - tempStream << "received UBX-MON-RXBUF message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXMonRx(msg.data); - break; - case (UBX_MON_TXBUF & 0xff): - if (verbose > 2) { - tempStream << "received UBX-MON-TXBUF message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXMonTx(msg.data); - break; - case 0x09: - if (verbose > 2) { - tempStream << "received UBX-MON-HW message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXMonHW(msg.data); - break; - case 0x0b: - if (verbose > 2) { - tempStream << "received UBX-MON-HW2 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXMonHW2(msg.data); - break; - case 0x04: - if (verbose > 2) { - tempStream << "received UBX-MON-VER message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } - UBXMonVer(msg.data); - break; - default: - if (verbose > 2) { - tempStream << "received unhandled UBX-MON message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; - emit toConsole(QString::fromStdString(tempStream.str())); - } + case (UBX_MON_RXBUF & 0xff): + if (verbose > 2) { + tempStream << "received UBX-MON-RXBUF message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXMonRx(msg.data); + break; + case (UBX_MON_TXBUF & 0xff): + if (verbose > 2) { + tempStream << "received UBX-MON-TXBUF message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXMonTx(msg.data); + break; + case 0x09: + if (verbose > 2) { + tempStream << "received UBX-MON-HW message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXMonHW(msg.data); + break; + case 0x0b: + if (verbose > 2) { + tempStream << "received UBX-MON-HW2 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXMonHW2(msg.data); + break; + case 0x04: + if (verbose > 2) { + tempStream << "received UBX-MON-VER message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } + UBXMonVer(msg.data); + break; + default: + if (verbose > 2) { + tempStream << "received unhandled UBX-MON message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID + << " 0x" << std::hex << (int)messageID << ")\n"; + emit toConsole(QString::fromStdString(tempStream.str())); + } } break; case 0x27: // UBX-SEC @@ -329,7 +318,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x01: // UBX-TIM-TP if (verbose > 2) { tempStream << "received UBX-TIM-TP message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID << " 0x" - << std::hex << (int)messageID << ")\n"; + << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXTimTP(msg.data); @@ -337,7 +326,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) case 0x03: // UBX-TIM-TM2 if (verbose > 2) { tempStream << "received UBX-TIM-TM2 message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID << " 0x" - << std::hex << (int)messageID << ")\n"; + << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } UBXTimTM2(msg.data); @@ -345,7 +334,7 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) default: if (verbose > 2) { tempStream << "received unhandled UBX-TIM message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -359,14 +348,13 @@ void QtSerialUblox::processMessage(const UbxMessage& msg) default: if (verbose > 2) { tempStream << "received unknown UBX message (0x" << std::hex << std::setfill('0') << std::setw(2) << (int)classID - << " 0x" << std::hex << (int)messageID << ")\n"; + << " 0x" << std::hex << (int)messageID << ")\n"; emit toConsole(QString::fromStdString(tempStream.str())); } break; } } - bool QtSerialUblox::UBXTimTP(const std::string& msg) { // parse all fields @@ -380,21 +368,16 @@ bool QtSerialUblox::UBXTimTP(const std::string& msg) towSubMS += ((int)msg[5]) << 8; towSubMS += ((int)msg[6]) << 16; towSubMS += ((int)msg[7]) << 24; - //int itow = towMS / 1000; // quantization error int32_t qErr = (int)msg[8]; qErr += ((int)msg[9]) << 8; qErr += ((int)msg[10]) << 16; qErr += ((int)msg[11]) << 24; - //int quantErr = qErr; - //mutex.lock(); emit gpsPropertyUpdatedInt32(qErr, TPQuantErr.updateAge(), 'e'); TPQuantErr = qErr; - //mutex.unlock(); // week number uint16_t week = (int)msg[12]; week += ((int)msg[13]) << 8; - //int weekNr = week; // flags uint8_t flags = msg[14]; // ref info @@ -403,24 +386,29 @@ bool QtSerialUblox::UBXTimTP(const std::string& msg) double sr = towMS / 1000.; sr = sr - towMS / 1000; - // cout<<"0d 01 "< 3) { std::stringstream tempStream; - //std::string temp; tempStream << "*** UBX-TIM-TP message:" << endl; tempStream << " tow s : " << dec << towMS / 1000. << " s" << endl; - tempStream << " tow sub s : " << dec << towSubMS << " = " << (long int)(sr*1e9 + towSubMS + 0.5) << " ns" << endl; + tempStream << " tow sub s : " << dec << towSubMS << " = " << (long int)(sr * 1e9 + towSubMS + 0.5) << " ns" << endl; tempStream << " quantization err : " << dec << qErr << " ps" << endl; tempStream << " week nr : " << dec << week << endl; tempStream << " *flags : "; - for (int i = 7; i >= 0; i--) if (flags & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (flags & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; tempStream << " time base : " << string(((flags & 1) ? "UTC" : "GNSS")) << endl; tempStream << " UTC available : " << string((flags & 2) ? "yes" : "no") << endl; tempStream << " (T)RAIM info : " << (int)((flags & 0x0c) >> 2) << endl; tempStream << " *refInfo : "; - for (int i = 7; i >= 0; i--) if (refInfo & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (refInfo & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; string gnssRef; switch (refInfo & 0x0f) { @@ -511,28 +499,16 @@ bool QtSerialUblox::UBXTimTM2(const std::string& msg) accEst += ((int)msg[26]) << 16; accEst += ((int)msg[27]) << 24; - //mutex.lock(); -// emit gpsPropertyUpdatedUint32(accEst, timeAccuracy.updateAge(), 'a'); -// timeAccuracy = accEst; -// timeAccuracy.lastUpdate = std::chrono::system_clock::now(); - //mutex.unlock(); - double sr = towMsR / 1000.; sr = sr - towMsR / 1000; - // sr*=1000.; double sf = towMsF / 1000.; sf = sf - towMsF / 1000; - // sf*=1000.; - // cout<<"sr="< 2) { @@ -542,14 +518,18 @@ bool QtSerialUblox::UBXTimTM2(const std::string& msg) tempStream << " * last rising edge:" << endl; tempStream << " week nr : " << dec << wnR << endl; tempStream << " tow s : " << dec << towMsR / 1000. << " s" << endl; - tempStream << " tow sub s : " << dec << towSubMsR << " = " << (long int)(sr*1e9 + towSubMsR) << " ns" << endl; + tempStream << " tow sub s : " << dec << towSubMsR << " = " << (long int)(sr * 1e9 + towSubMsR) << " ns" << endl; tempStream << " * last falling edge:" << endl; tempStream << " week nr : " << dec << wnF << endl; tempStream << " tow s : " << dec << towMsF / 1000. << " s" << endl; - tempStream << " tow sub s : " << dec << towSubMsF << " = " << (long int)(sf*1e9 + towSubMsF) << " ns" << endl; + tempStream << " tow sub s : " << dec << towSubMsF << " = " << (long int)(sf * 1e9 + towSubMsF) << " ns" << endl; tempStream << " accuracy est : " << dec << accEst << " ns" << endl; tempStream << " flags : "; - for (int i = 7; i >= 0; i--) if (flags & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (flags & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; tempStream << " mode : " << string((flags & 1) ? "single" : "running") << endl; tempStream << " run : " << string((flags & 2) ? "armed" : "stopped") << endl; @@ -578,30 +558,27 @@ bool QtSerialUblox::UBXTimTM2(const std::string& msg) tempStream.clear(); if (flags & 0x80) { // if new rising edge - tempStream << unixtime_from_gps(wnR, towMsR / 1000, (long int)(sr*1e9 + towSubMsR)); - } - else { + tempStream << unixtime_from_gps(wnR, towMsR / 1000, (long int)(sr * 1e9 + towSubMsR)); + } else { tempStream << ".................... "; } if (flags & 0x04) { // if new falling edge - tempStream << unixtime_from_gps(wnF, towMsF / 1000, (long int)(sr*1e9 + towSubMsF)); - } - else { + tempStream << unixtime_from_gps(wnF, towMsF / 1000, (long int)(sr * 1e9 + towSubMsF)); + } else { tempStream << ".................... "; } tempStream << accEst - << " " << count - << " " << ((flags & 0x40) >> 6) - << " " << setfill('0') << setw(1) << ((flags & 0x18) >> 3) - << " " << ((flags & 0x20) >> 5); -// emit timTM2(QString::fromStdString(tempStream.str())); - if (verbose > 1){ - emit toConsole(QString::fromStdString(tempStream.str())+"\n"); + << " " << count + << " " << ((flags & 0x40) >> 6) + << " " << setfill('0') << setw(1) << ((flags & 0x18) >> 3) + << " " << ((flags & 0x20) >> 5); + if (verbose > 1) { + emit toConsole(QString::fromStdString(tempStream.str()) + "\n"); } - struct timespec ts_r = unixtime_from_gps(wnR, towMsR / 1000, (long int)(sr*1e9 + towSubMsR)/*, this->leapSeconds()*/); - struct timespec ts_f = unixtime_from_gps(wnF, towMsF / 1000, (long int)(sf*1e9 + towSubMsF)/*, this->leapSeconds()*/); + struct timespec ts_r = unixtime_from_gps(wnR, towMsR / 1000, (long int)(sr * 1e9 + towSubMsR)); + struct timespec ts_f = unixtime_from_gps(wnF, towMsF / 1000, (long int)(sf * 1e9 + towSubMsF)); struct gpsTimestamp ts; ts.rising_time = ts_r; @@ -609,7 +586,6 @@ bool QtSerialUblox::UBXTimTM2(const std::string& msg) ts.valid = (flags & 0x40); ts.channel = ch; - // fTimestamps.push(ts); ts.counter = count; ts.accuracy_ns = accEst; @@ -617,66 +593,61 @@ bool QtSerialUblox::UBXTimTM2(const std::string& msg) if (flags & 0x80) { // new rising edge detected ts.rising = true; - } if (flags & 0x04) { + } + if (flags & 0x04) { // new falling edge detected ts.falling = true; } - //mutex.lock(); emit gpsPropertyUpdatedUint32(count, eventCounter.updateAge(), 'c'); eventCounter = count; - //fTimestamps.push(ts); - //mutex.unlock(); - - static int64_t lastPulseLength = 0; - - UbxTimeMarkStruct tm; - tm.rising=ts.rising_time; - tm.falling=ts.falling_time; - tm.risingValid=ts.rising; - tm.fallingValid=ts.falling; - tm.accuracy_ns=accEst; - tm.valid=ts.valid; - tm.timeBase=(flags & 0x18) >> 3; - tm.utcAvailable=flags & 0x20; - tm.flags=flags; - tm.evtCounter=count; - - // try to recover the timestamp, if one edge is missing - if (!tm.risingValid && tm.fallingValid) { - tm.rising.tv_sec = tm.falling.tv_sec - lastPulseLength / 1000000000; - tm.rising.tv_nsec = tm.falling.tv_nsec - lastPulseLength % 1000000000; - if (tm.rising.tv_nsec >= 1000000000) { - tm.rising.tv_sec += 1; - tm.rising.tv_nsec -= 1000000000; - } else if (tm.rising.tv_nsec < 0) { - tm.rising.tv_sec -= 1; - tm.rising.tv_nsec += 1000000000; - } - //tm.risingValid = true; - } else if (!tm.fallingValid && tm.risingValid) { - tm.falling.tv_sec = tm.rising.tv_sec + lastPulseLength / 1000000000; - tm.falling.tv_nsec = tm.rising.tv_nsec + lastPulseLength % 1000000000; - if (tm.falling.tv_nsec >= 1000000000) { - tm.falling.tv_sec += 1; - tm.falling.tv_nsec -= 1000000000; - } - //tm.fallingValid = true; - } else if (!tm.fallingValid && !tm.risingValid) { - // nothing to recover here; ignore the event - //return false; - } else { - // the normal case, i.e. both edges are valid - // calculate the pulse length in this case - int64_t dts=(tm.falling.tv_sec-tm.rising.tv_sec)*1.0e9; - dts+=(tm.falling.tv_nsec-tm.rising.tv_nsec); - if (dts > 0 && dts < 1000000 ) lastPulseLength = dts; - } - + + static int64_t lastPulseLength = 0; + + UbxTimeMarkStruct tm; + tm.rising = ts.rising_time; + tm.falling = ts.falling_time; + tm.risingValid = ts.rising; + tm.fallingValid = ts.falling; + tm.accuracy_ns = accEst; + tm.valid = ts.valid; + tm.timeBase = (flags & 0x18) >> 3; + tm.utcAvailable = flags & 0x20; + tm.flags = flags; + tm.evtCounter = count; + + // try to recover the timestamp, if one edge is missing + if (!tm.risingValid && tm.fallingValid) { + tm.rising.tv_sec = tm.falling.tv_sec - lastPulseLength / 1000000000; + tm.rising.tv_nsec = tm.falling.tv_nsec - lastPulseLength % 1000000000; + if (tm.rising.tv_nsec >= 1000000000) { + tm.rising.tv_sec += 1; + tm.rising.tv_nsec -= 1000000000; + } else if (tm.rising.tv_nsec < 0) { + tm.rising.tv_sec -= 1; + tm.rising.tv_nsec += 1000000000; + } + } else if (!tm.fallingValid && tm.risingValid) { + tm.falling.tv_sec = tm.rising.tv_sec + lastPulseLength / 1000000000; + tm.falling.tv_nsec = tm.rising.tv_nsec + lastPulseLength % 1000000000; + if (tm.falling.tv_nsec >= 1000000000) { + tm.falling.tv_sec += 1; + tm.falling.tv_nsec -= 1000000000; + } + } else if (!tm.fallingValid && !tm.risingValid) { + // nothing to recover here; ignore the event + } else { + // the normal case, i.e. both edges are valid + // calculate the pulse length in this case + int64_t dts = (tm.falling.tv_sec - tm.rising.tv_sec) * 1.0e9; + dts += (tm.falling.tv_nsec - tm.rising.tv_nsec); + if (dts > 0 && dts < 1000000) + lastPulseLength = dts; + } + emit UBXReceivedTimeTM2(tm); return true; } - std::vector QtSerialUblox::UBXNavSat(const std::string& msg, bool allSats) { std::vector satList; @@ -695,62 +666,51 @@ std::vector QtSerialUblox::UBXNavSat(const std::string& msg, bool if (verbose > 3) { std::stringstream tempStream; - //std::string temp; tempStream << setfill(' ') << setw(3); tempStream << "*** UBX-NAV-SAT message:" << endl; tempStream << " iTOW : " << dec << iTOW / 1000 << " s" << endl; tempStream << " version : " << dec << (int)version << endl; tempStream << " Nr of sats : " << (int)numSvs << " (nr of sections=" << N << ")\n"; tempStream << " Sat Data :\n"; - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } uint8_t goodSats = 0; for (int i = 0; i < N; i++) { - //GnssSatellite sat(msg.substr(8 + 12 * i, 12)); - int n=8+i*12; + int n = 8 + i * 12; uint32_t flags; - uint8_t gnssId = msg[n+0]; - uint8_t satId = msg[n+1]; - uint8_t cnr = msg[n+2]; - int8_t elev = msg[n+3]; - int16_t azim = msg[n+4]; - azim += msg[n+5] << 8; - int16_t _prRes = msg[n+6]; - _prRes += msg[n+7] << 8; + uint8_t gnssId = msg[n + 0]; + uint8_t satId = msg[n + 1]; + uint8_t cnr = msg[n + 2]; + int8_t elev = msg[n + 3]; + int16_t azim = msg[n + 4]; + azim += msg[n + 5] << 8; + int16_t _prRes = msg[n + 6]; + _prRes += msg[n + 7] << 8; float prRes = _prRes / 10.; - flags = (int)msg[n+8]; - flags += ((int)msg[n+9]) << 8; - flags += ((int)msg[n+10]) << 16; - flags += ((int)msg[n+11]) << 24; -/* - fQuality = (int)(flags & 0x07); - if (flags & 0x08) fUsed = true; else fUsed = false; - fHealth = (int)(flags >> 4 & 0x03); - fOrbitSource = (flags >> 8 & 0x07); - fSmoothed = (flags & 0x80); - fDiffCorr = (flags & 0x40); -*/ - if (gnssId>7) gnssId=7; + flags = (int)msg[n + 8]; + flags += ((int)msg[n + 9]) << 8; + flags += ((int)msg[n + 10]) << 16; + flags += ((int)msg[n + 11]) << 24; + if (gnssId > 7) + gnssId = 7; GnssSatellite sat(gnssId, satId, cnr, elev, azim, prRes, flags); - if (sat.getCnr() > 0) goodSats++; + if (sat.getCnr() > 0) + goodSats++; satList.push_back(sat); } if (!allSats) { sort(satList.begin(), satList.end(), GnssSatellite::sortByCnr); - while (satList.back().getCnr() == 0 && satList.size() > 0) satList.pop_back(); + while (satList.back().getCnr() == 0 && satList.size() > 0) + satList.pop_back(); } - // nrSats = satList.size(); - //mutex.lock(); emit gpsPropertyUpdatedUint8(goodSats, nrSats.updateAge(), 's'); nrSats = goodSats; - //mutex.unlock(); - if (verbose>3) { + if (verbose > 3) { std::string temp; GnssSatellite::PrintHeader(true); for (vector::iterator it = satList.begin(); it != satList.end(); it++) { @@ -782,73 +742,80 @@ std::vector QtSerialUblox::UBXNavSVinfo(const std::string& msg, b if (verbose > 3) { std::stringstream tempStream; - //std::string temp; tempStream << setfill(' ') << setw(3); tempStream << "*** UBX-NAV-SVINFO message:" << endl; tempStream << " iTOW : " << dec << iTOW / 1000 << " s" << endl; - tempStream << " global flags : 0x" << hex << (int)globFlags <> temp; emit toConsole(QString::fromStdString(tempStream.str())); } uint8_t goodSats = 0; for (int i = 0; i < N; i++) { - int n=8+i*12; -// uint8_t chId = msg[n+0]; - uint8_t satId = msg[n+1]; - uint8_t flags = msg[n+2]; - uint8_t quality = msg[n+3]; - uint8_t cnr = msg[n+4]; - int8_t elev = msg[n+5]; - int16_t azim = msg[n+6]; - azim += msg[n+7] << 8; - int32_t prRes = msg[n+8]; - prRes += msg[n+9] << 8; - prRes += msg[n+10] << 16; - prRes += msg[n+11] << 24; + int n = 8 + i * 12; + uint8_t satId = msg[n + 1]; + uint8_t flags = msg[n + 2]; + uint8_t quality = msg[n + 3]; + uint8_t cnr = msg[n + 4]; + int8_t elev = msg[n + 5]; + int16_t azim = msg[n + 6]; + azim += msg[n + 7] << 8; + int32_t prRes = msg[n + 8]; + prRes += msg[n + 9] << 8; + prRes += msg[n + 10] << 16; + prRes += msg[n + 11] << 24; bool used = false; - if (flags & 0x01) used = true; + if (flags & 0x01) + used = true; uint8_t health = (flags >> 4 & 0x01); - health+=1; + health += 1; uint8_t orbitSource = 0; if (flags & 0x04) { - if (flags & 0x08) orbitSource = 1; - else if (flags & 0x20) orbitSource = 2; - else if (flags & 0x40) orbitSource = 3; + if (flags & 0x08) + orbitSource = 1; + else if (flags & 0x20) + orbitSource = 2; + else if (flags & 0x40) + orbitSource = 3; } bool smoothed = (flags & 0x80); bool diffCorr = (flags & 0x02); -//{ " GPS","SBAS"," GAL","BEID","IMES","QZSS","GLNS" }; - int gnssId=7; - if (satId<33) gnssId=0; - else if (satId<65) gnssId=3; - else if (satId<97 || satId==255) gnssId=6; - else if (satId<159) gnssId=1; - else if (satId<164) gnssId=3; - else if (satId<183) gnssId=4; - else if (satId<198) gnssId=5; - else if (satId<247) gnssId=2; - - GnssSatellite sat( gnssId, satId, cnr, elev, azim, 0.01*prRes, - quality, health, orbitSource, used, diffCorr, smoothed); - if (sat.getCnr() > 0) goodSats++; + int gnssId = 7; + if (satId < 33) + gnssId = 0; + else if (satId < 65) + gnssId = 3; + else if (satId < 97 || satId == 255) + gnssId = 6; + else if (satId < 159) + gnssId = 1; + else if (satId < 164) + gnssId = 3; + else if (satId < 183) + gnssId = 4; + else if (satId < 198) + gnssId = 5; + else if (satId < 247) + gnssId = 2; + + GnssSatellite sat(gnssId, satId, cnr, elev, azim, 0.01 * prRes, + quality, health, orbitSource, used, diffCorr, smoothed); + if (sat.getCnr() > 0) + goodSats++; satList.push_back(sat); } if (!allSats) { sort(satList.begin(), satList.end(), GnssSatellite::sortByCnr); - while (satList.back().getCnr() == 0 && satList.size() > 0) satList.pop_back(); + while (satList.back().getCnr() == 0 && satList.size() > 0) + satList.pop_back(); } - // nrSats = satList.size(); - //mutex.lock(); emit gpsPropertyUpdatedUint8(goodSats, nrSats.updateAge(), 's'); nrSats = goodSats; - //mutex.unlock(); - if (verbose>3) { + if (verbose > 3) { std::string temp; GnssSatellite::PrintHeader(true); for (vector::iterator it = satList.begin(); it != satList.end(); it++) { @@ -862,14 +829,13 @@ std::vector QtSerialUblox::UBXNavSVinfo(const std::string& msg, b return satList; } - -void QtSerialUblox::UBXCfgGNSS(const string &msg) +void QtSerialUblox::UBXCfgGNSS(const string& msg) { // UBX-CFG-GNSS: GNSS configuration // parse all fields // version -// send: -// "0,0,ff,1,6,5,ff,0,1,0,0,0" + // send: + // "0,0,ff,1,6,5,ff,0,1,0,0,0" uint8_t version = msg[0]; uint8_t numTrkChHw = msg[1]; uint8_t numTrkChUse = msg[2]; @@ -877,15 +843,14 @@ void QtSerialUblox::UBXCfgGNSS(const string &msg) int N = (msg.size() - 4) / 8; - if (verbose>2) - { + if (verbose > 2) { std::stringstream tempStream; tempStream << "*** UBX CFG-GNSS message:" << endl; tempStream << " version : " << dec << (int)version << endl; tempStream << " nr of hw tracking channels : " << dec << (int)numTrkChHw << endl; tempStream << " nr of channels in use : " << dec << (int)numTrkChUse << endl; tempStream << " Nr of config blocks : " << (int)numConfigBlocks - << " (nr of sections=" << N << ")"; + << " (nr of sections=" << N << ")"; tempStream << " Config Data :\n"; emit toConsole(QString::fromStdString(tempStream.str())); } @@ -900,15 +865,14 @@ void QtSerialUblox::UBXCfgGNSS(const string &msg) config.flags |= (int)msg[9 + 8 * i] << 8; config.flags |= (int)msg[10 + 8 * i] << 16; config.flags |= (int)msg[11 + 8 * i] << 24; - if (verbose>2) - { + if (verbose > 2) { std::stringstream tempStream; tempStream << " " << i << ": GNSS name : " - << GNSS_ID_STRING[config.gnssId] << endl; + << GNSS_ID_STRING[config.gnssId] << endl; tempStream << " reserved (min) tracking channels : " - << dec << (int)config.resTrkCh << endl; + << dec << (int)config.resTrkCh << endl; tempStream << " max nr of tracking channels used : " - << dec << (int)config.maxTrkCh << endl; + << dec << (int)config.maxTrkCh << endl; tempStream << " flags : 0x" << std::hex << (int)config.flags << "\n"; emit toConsole(QString::fromStdString(tempStream.str())); } @@ -917,42 +881,37 @@ void QtSerialUblox::UBXCfgGNSS(const string &msg) emit UBXReceivedGnssConfig(numTrkChHw, configs); } -void QtSerialUblox::onSetGnssConfig(const std::vector& gnssConfigs) { +void QtSerialUblox::onSetGnssConfig(const std::vector& gnssConfigs) +{ - const std::size_t N= gnssConfigs.size(); - unsigned char* data {static_cast(calloc(sizeof(unsigned char), 4+8*N))}; - data[0]=0; - data[1]=0; - data[2]=0xff; - data[3]=static_cast(N); + const std::size_t N = gnssConfigs.size(); + unsigned char* data { static_cast(calloc(sizeof(unsigned char), 4 + 8 * N)) }; + data[0] = 0; + data[1] = 0; + data[2] = 0xff; + data[3] = static_cast(N); for (std::size_t i { 0 }; i < N; i++) { - uint32_t flags=gnssConfigs[i].flags; + uint32_t flags = gnssConfigs[i].flags; if (getProtVersion() >= 15.0) { - flags |= 0x0001<<16; - if (gnssConfigs[i].gnssId==5) flags |= 0x0004<<16; + flags |= 0x0001 << 16; + if (gnssConfigs[i].gnssId == 5) + flags |= 0x0004 << 16; } - data[4 + 8 * i]=gnssConfigs[i].gnssId; - data[5 + 8 * i]=gnssConfigs[i].resTrkCh; - data[6 + 8 * i]=gnssConfigs[i].maxTrkCh; - data[8 + 8 * i]=flags & 0xff; - data[9 + 8 * i]=(flags>>8) & 0xff; - data[10 + 8 * i]=(flags>>16) & 0xff; - data[11 + 8 * i]=(flags>>24) & 0xff; + data[4 + 8 * i] = gnssConfigs[i].gnssId; + data[5 + 8 * i] = gnssConfigs[i].resTrkCh; + data[6 + 8 * i] = gnssConfigs[i].maxTrkCh; + data[8 + 8 * i] = flags & 0xff; + data[9 + 8 * i] = (flags >> 8) & 0xff; + data[10 + 8 * i] = (flags >> 16) & 0xff; + data[11 + 8 * i] = (flags >> 24) & 0xff; } - enqueueMsg(UBX_CFG_GNSS, toStdString(data, static_cast(4+8*N))); + enqueueMsg(UBX_CFG_GNSS, toStdString(data, static_cast(4 + 8 * N))); free(data); -/* - UbxMessage newMessage; - newMessage.msgID = UBX_CFG_GNSS; - newMessage.data = toStdString(data, 4+8*N); - sendUBX(newMessage); -*/ } - -void QtSerialUblox::UBXCfgNav5(const string &msg) +void QtSerialUblox::UBXCfgNav5(const string& msg) { // UBX CFG-NAV5: satellite information // parse all fields @@ -972,42 +931,32 @@ void QtSerialUblox::UBXCfgNav5(const string &msg) uint8_t cnoThreshNumSVs = msg[24]; uint8_t cnoThresh = msg[25]; - - if (verbose>2) - { + if (verbose > 2) { std::stringstream tempStream; tempStream << "*** UBX CFG-NAV5 message:" << endl; tempStream << " mask : " << std::hex << (int)mask << endl; tempStream << " dynamic model used : " << dec << (int)dynModel << endl; tempStream << " fixMode : " << dec << (int)fixMode << endl; - tempStream << " fixed Alt : " << (double)fixedAlt*0.01 << " m" << endl; - tempStream << " fixed Alt Var : " << (double)fixedAltVar*0.0001 << " m^2" << endl; + tempStream << " fixed Alt : " << (double)fixedAlt * 0.01 << " m" << endl; + tempStream << " fixed Alt Var : " << (double)fixedAltVar * 0.0001 << " m^2" << endl; tempStream << " min elevation : " << dec << (int)minElev << " deg\n"; tempStream << " cnoThresh required for fix : " << dec << (int)cnoThresh << " dBHz\n"; - tempStream << " min nr of SVs having cnoThresh for fix : " << dec << (int)cnoThreshNumSVs<(0), 'u'); + emit gpsPropertyUpdatedUint32(msss / 1000, std::chrono::duration(0), 'u'); - if (verbose>3) - { + if (verbose > 3) { std::stringstream tempStream; tempStream << "*** UBX NAV-STATUS message:" << endl; tempStream << " iTOW : " << dec << iTOW / 1000 << " s" << endl; tempStream << " gpsFix : " << dec << (int)gpsFix << endl; - tempStream << " time to first fix: " << dec << (float)ttff/1000. << " s" << endl; - tempStream << " uptime : " << dec << (float)msss/1000. << " s" << endl; - tempStream << " flags : " << hex << "0x"<<(int)flags << endl; - tempStream << " flags2 : " << hex << "0x"<<(int)flags2 << endl; + tempStream << " time to first fix: " << dec << (float)ttff / 1000. << " s" << endl; + tempStream << " uptime : " << dec << (float)msss / 1000. << " s" << endl; + tempStream << " flags : " << hex << "0x" << (int)flags << endl; + tempStream << " flags2 : " << hex << "0x" << (int)flags2 << endl; emit toConsole(QString::fromStdString(tempStream.str())); } } -GeodeticPos QtSerialUblox::UBXNavPosLLH(const string &msg){ +GeodeticPos QtSerialUblox::UBXNavPosLLH(const string& msg) +{ GeodeticPos pos; // GPS time of week uint32_t iTOW = (unsigned int)msg[0]; @@ -1103,11 +1051,9 @@ void QtSerialUblox::UBXNavClock(const std::string& msg) iTOW += ((int)msg[1]) << 8; iTOW += ((int)msg[2]) << 16; iTOW += ((int)msg[3]) << 24; - //uint32_t itow = iTOW / 1000; // clock bias if (verbose > 3) { std::stringstream tempStream; - //std::string temp; tempStream << "clkB[0]=" << std::setfill('0') << std::setw(2) << std::hex << (int)msg[4] << endl; tempStream << "clkB[1]=" << std::setfill('0') << std::setw(2) << std::hex << (int)msg[5] << endl; tempStream << "clkB[2]=" << std::setfill('0') << std::setw(2) << std::hex << (int)msg[6] << endl; @@ -1118,32 +1064,26 @@ void QtSerialUblox::UBXNavClock(const std::string& msg) clkB += ((int)msg[5]) << 8; clkB += ((int)msg[6]) << 16; clkB += ((int)msg[7]) << 24; - //int32_t bias = clkB; // clock drift int32_t clkD = (int)msg[8]; clkD += ((int)msg[9]) << 8; clkD += ((int)msg[10]) << 16; clkD += ((int)msg[11]) << 24; - //int32_t drift = clkD; //mutex.lock(); emit gpsPropertyUpdatedInt32(clkD, clkDrift.updateAge(), 'd'); emit gpsPropertyUpdatedInt32(clkB, clkBias.updateAge(), 'b'); clkDrift = clkD; clkBias = clkB; - //mutex.unlock(); // time accuracy estimate uint32_t tAcc = (int)msg[12]; tAcc += ((int)msg[13]) << 8; tAcc += ((int)msg[14]) << 16; tAcc += ((int)msg[15]) << 24; - //uint32_t tAccuracy = tAcc; - //timeAccuracy = tAcc; // freq accuracy estimate uint32_t fAcc = (int)msg[16]; fAcc += ((int)msg[17]) << 8; fAcc += ((int)msg[18]) << 16; fAcc += ((int)msg[19]) << 24; - //uint32_t fAccuracy = fAcc; emit gpsPropertyUpdatedUint32(tAcc, timeAccuracy.updateAge(), 'a'); timeAccuracy = tAcc; @@ -1155,25 +1095,19 @@ void QtSerialUblox::UBXNavClock(const std::string& msg) // meaning of columns: // 01 22 - signature of NAV-CLOCK message // second in current week (s), clock bias (ns), clock drift (ns/s), time accuracy (ns), freq accuracy (ps/s) - // cout<<"01 22 "< 3) { std::stringstream tempStream; - //std::string temp; tempStream << "*** UBX-NAV-CLOCK message:" << endl; tempStream << " iTOW : " << dec << iTOW / 1000 << " s" << endl; tempStream << " clock bias : " << dec << clkB << " ns" << endl; tempStream << " clock drift : " << dec << clkD << " ns/s" << endl; tempStream << " time accuracy : " << dec << tAcc << " ns" << endl; tempStream << " freq accuracy : " << dec << fAcc << " ps/s\n"; - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } } - void QtSerialUblox::UBXNavTimeGPS(const std::string& msg) { // parse all fields @@ -1188,8 +1122,6 @@ void QtSerialUblox::UBXNavTimeGPS(const std::string& msg) fTOW += ((int)msg[6]) << 16; fTOW += ((int)msg[7]) << 24; - // int32_t ftow=iTOW/1000; - uint16_t wnR = (int)msg[8]; wnR += ((int)msg[9]) << 8; @@ -1201,8 +1133,6 @@ void QtSerialUblox::UBXNavTimeGPS(const std::string& msg) tAcc += ((int)msg[13]) << 8; tAcc += ((int)msg[14]) << 16; tAcc += ((int)msg[15]) << 24; - //uint32_t tAccuracy = tAcc; - double sr = iTOW / 1000.; sr = sr - iTOW / 1000; @@ -1211,39 +1141,37 @@ void QtSerialUblox::UBXNavTimeGPS(const std::string& msg) // 01 20 - signature of NAV-TIMEGPS message // week nr, second in current week, ns of timestamp in current second, // nr of leap seconds wrt UTC, accuracy (ns) - // cout<<"01 20 "< 3) { std::stringstream tempStream; - //std::string temp; tempStream << "*** UBX-NAV-TIMEGPS message:" << endl; tempStream << " week nr : " << dec << wnR << endl; tempStream << " iTOW : " << dec << iTOW << " ms = " << iTOW / 1000 << " s" << endl; - tempStream << " fTOW : " << dec << fTOW << " = " << (long int)(sr*1e9 + fTOW) << " ns" << endl; + tempStream << " fTOW : " << dec << fTOW << " = " << (long int)(sr * 1e9 + fTOW) << " ns" << endl; tempStream << " leap seconds : " << dec << (int)leapS << " s" << endl; tempStream << " time accuracy : " << dec << tAcc << " ns" << endl; tempStream << " flags : "; - for (int i = 7; i >= 0; i--) if (flags & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (flags & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; tempStream << " tow valid : " << string((flags & 1) ? "yes" : "no") << endl; tempStream << " week valid : " << string((flags & 2) ? "yes" : "no") << endl; tempStream << " leap sec valid : " << string((flags & 4) ? "yes" : "no"); - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } - //mutex.lock(); emit gpsPropertyUpdatedUint32(tAcc, timeAccuracy.updateAge(), 'a'); timeAccuracy = tAcc; timeAccuracy.lastUpdate = std::chrono::system_clock::now(); - if (flags & 4) { leapSeconds = leapS; } - //mutex.unlock(); + if (flags & 4) { + leapSeconds = leapS; + } - struct timespec ts = unixtime_from_gps(wnR, iTOW / 1000, (long int)(sr*1e9 + fTOW)/*, this->leapSeconds()*/); + struct timespec ts = unixtime_from_gps(wnR, iTOW / 1000, (long int)(sr * 1e9 + fTOW)); std::stringstream tempStream; - //std::string temp; tempStream << ts.tv_sec << '.' << ts.tv_nsec << "\n"; - //tempStream >> temp; if (verbose > 1) { emit toConsole(QString::fromStdString(tempStream.str())); } @@ -1263,12 +1191,9 @@ void QtSerialUblox::UBXNavTimeUTC(const std::string& msg) tAcc += ((int)msg[5]) << 8; tAcc += ((int)msg[6]) << 16; tAcc += ((int)msg[7]) << 24; - //uint32_t tAccuracy = tAcc; - //mutex.lock(); emit gpsPropertyUpdatedUint32(tAcc, timeAccuracy.updateAge(), 'a'); timeAccuracy = tAcc; timeAccuracy.lastUpdate = std::chrono::system_clock::now(); - //mutex.unlock(); int32_t nano = (int)msg[8]; nano += ((int)msg[9]) << 8; @@ -1293,12 +1218,9 @@ void QtSerialUblox::UBXNavTimeUTC(const std::string& msg) // 01 21 - signature of NAV-TIMEUTC message // second in current week, year, month, day, hour, minute, seconds(+fraction) // accuracy (ns) - // cout<<"01 21 "< 3) { std::stringstream tempStream; - //std::string temp; tempStream << "*** UBX-NAV-TIMEUTC message:" << endl; tempStream << " iTOW : " << dec << iTOW << " ms = " << iTOW / 1000 << " s" << endl; tempStream << " nano : " << dec << nano << " ns" << endl; @@ -1306,7 +1228,11 @@ void QtSerialUblox::UBXNavTimeUTC(const std::string& msg) tempStream << " UTC time h:m:s : " << dec << setw(2) << setfill('0') << hour << ":" << (int)min << ":" << (double)(sec + nano * 1e-9) << endl; tempStream << " time accuracy : " << dec << tAcc << " ns" << endl; tempStream << " flags : "; - for (int i = 7; i >= 0; i--) if (flags & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (flags & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; tempStream << " tow valid : " << string((flags & 1) ? "yes" : "no") << endl; tempStream << " week valid : " << string((flags & 2) ? "yes" : "no") << endl; @@ -1341,7 +1267,6 @@ void QtSerialUblox::UBXNavTimeUTC(const std::string& msg) utcStd = "unknown"; } tempStream << " UTC standard : " << utcStd << "\n"; - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -1370,8 +1295,6 @@ void QtSerialUblox::UBXMonHW(const std::string& msg) // 01 21 - signature of NAV-TIMEUTC message // second in current week, year, month, day, hour, minute, seconds(+fraction) // accuracy (ns) - // cout<<"0a 09 "< 3) { std::stringstream tempStream; @@ -1382,7 +1305,11 @@ void QtSerialUblox::UBXMonHW(const std::string& msg) tempStream << " antenna power : " << dec << (int)antPower << endl; tempStream << " jamming indicator: " << dec << (int)jamInd << endl; tempStream << " flags : "; - for (int i = 7; i >= 0; i--) if (flags & 1 << i) tempStream << i; else tempStream << "-"; + for (int i = 7; i >= 0; i--) + if (flags & 1 << i) + tempStream << i; + else + tempStream << "-"; tempStream << endl; tempStream << " RTC calibrated : " << string((flags & 1) ? "yes" : "no") << endl; tempStream << " safe boot : " << string((flags & 2) ? "yes" : "no") << endl; @@ -1393,7 +1320,6 @@ void QtSerialUblox::UBXMonHW(const std::string& msg) } GnssMonHwStruct hw(noisePerMS, agcCnt, antStatus, antPower, jamInd, flags); emit gpsMonHW(hw); - //emit gpsMonHW(noisePerMS, agcCnt, antStatus, antPower, jamInd, flags); } void QtSerialUblox::UBXMonHW2(const std::string& msg) @@ -1407,14 +1333,14 @@ void QtSerialUblox::UBXMonHW2(const std::string& msg) uint8_t cfgSrc = msg[4]; uint32_t lowLevCfg = msg[8]; - lowLevCfg |= msg[9]<<8; - lowLevCfg |= msg[10]<<16; - lowLevCfg |= msg[11]<<24; + lowLevCfg |= msg[9] << 8; + lowLevCfg |= msg[10] << 16; + lowLevCfg |= msg[11] << 24; uint32_t postStatus = msg[20]; - postStatus |= msg[21]<<8; - postStatus |= msg[22]<<16; - postStatus |= msg[23]<<24; + postStatus |= msg[21] << 8; + postStatus |= msg[22] << 16; + postStatus |= msg[23] << 24; if (verbose > 3) { std::stringstream tempStream; @@ -1429,7 +1355,6 @@ void QtSerialUblox::UBXMonHW2(const std::string& msg) } GnssMonHw2Struct hw2(ofsI, ofsQ, magI, magQ, cfgSrc); emit gpsMonHW2(hw2); - //emit gpsMonHW2(ofsI,magI,ofsQ,magQ,cfgSrc); } void QtSerialUblox::UBXMonVer(const std::string& msg) @@ -1438,11 +1363,11 @@ void QtSerialUblox::UBXMonVer(const std::string& msg) std::string hwString = ""; std::string swString = ""; - for (int i=0; msg[i]!=0 && i<30; i++) { - swString+=(char)msg[i]; + for (int i = 0; msg[i] != 0 && i < 30; i++) { + swString += (char)msg[i]; } - for (int i=30; msg[i]!=0 && i<40; i++) { - hwString+=(char)msg[i]; + for (int i = 30; msg[i] != 0 && i < 40; i++) { + hwString += (char)msg[i]; } if (verbose > 2) { @@ -1462,28 +1387,29 @@ void QtSerialUblox::UBXMonVer(const std::string& msg) } if (s.size()) { result.push_back(s); - size_t n = s.find("PROTVER",0); - if (n!=std::string::npos) { - std::string str = s.substr(7,s.size()-7); - while (str.size() && !isdigit(str[0])) str.erase(0,1); - while (str.size() && (str[str.size()-1]==' ' || !std::isgraph(static_cast(str[str.size()-1])) )) str.erase(str.size()-1,1); + size_t n = s.find("PROTVER", 0); + if (n != std::string::npos) { + std::string str = s.substr(7, s.size() - 7); + while (str.size() && !isdigit(str[0])) + str.erase(0, 1); + while (str.size() && (str[str.size() - 1] == ' ' || !std::isgraph(static_cast(str[str.size() - 1])))) + str.erase(str.size() - 1, 1); fProtVersionString = str; if (verbose > 3) - emit toConsole("catched PROTVER string: '"+QString::fromStdString(fProtVersionString)+"'\n"); - float nr=QtSerialUblox::getProtVersion(); - if (verbose > 3) emit toConsole("ver: "+QString::number(nr)+"\n"); + emit toConsole("catched PROTVER string: '" + QString::fromStdString(fProtVersionString) + "'\n"); + float nr = QtSerialUblox::getProtVersion(); + if (verbose > 3) + emit toConsole("ver: " + QString::number(nr) + "\n"); } if (verbose > 2) { - emit toConsole(QString::fromStdString(s)+"\n"); + emit toConsole(QString::fromStdString(s) + "\n"); } } i = msg.find((char)0x00, i + 1); } -// return result; emit gpsVersion(QString::fromStdString(swString), QString::fromStdString(hwString), QString::fromStdString(fProtVersionString)); } - void QtSerialUblox::UBXMonTx(const std::string& msg) { // parse all fields @@ -1493,7 +1419,6 @@ void QtSerialUblox::UBXMonTx(const std::string& msg) uint8_t peakUsage[6]; uint8_t tUsage; uint8_t tPeakUsage; - //uint8_t errors; for (int i = 0; i < 6; i++) { pending[i] = msg[2 * i]; @@ -1504,25 +1429,17 @@ void QtSerialUblox::UBXMonTx(const std::string& msg) tUsage = msg[24]; tPeakUsage = msg[25]; - //errors = msg[26]; // meaning of columns: // 01 21 - signature of NAV-TIMEUTC message // second in current week, year, month, day, hour, minute, seconds(+fraction) // accuracy (ns) - // cout<<"0a 09 "< 3) { std::stringstream tempStream; - //std::string temp; tempStream << setfill(' ') << setw(3); tempStream << "*** UBX-MON-TXBUF message:" << endl; tempStream << " global TX buf usage : " << dec << (int)tUsage << " %" << endl; @@ -1542,8 +1459,6 @@ void QtSerialUblox::UBXMonTx(const std::string& msg) tempStream << " (" << dec << i << ") " << setw(3) << pending[i]; } tempStream << "\n"; - //tempStream << setw(1) << setfill(' '); - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -1555,28 +1470,22 @@ void QtSerialUblox::UBXMonRx(const std::string& msg) uint16_t pending[6]; uint8_t usage[6]; uint8_t peakUsage[6]; - uint8_t tUsage=0; - uint8_t tPeakUsage=0; + uint8_t tUsage = 0; + uint8_t tPeakUsage = 0; for (int i = 0; i < 6; i++) { pending[i] = msg[2 * i]; pending[i] |= (uint16_t)msg[2 * i + 1] << 8; usage[i] = msg[i + 12]; peakUsage[i] = msg[i + 18]; - tUsage+=usage[i]; - tPeakUsage+=peakUsage[i]; + tUsage += usage[i]; + tPeakUsage += peakUsage[i]; } emit UBXReceivedRxBuf(tUsage, tPeakUsage); -// emit gpsPropertyUpdatedUint8(tUsage, txBufUsage.updateAge(), 'b'); -// emit gpsPropertyUpdatedUint8(tPeakUsage, txBufPeakUsage.updateAge(), 'p'); -// txBufUsage = tUsage; -// txBufPeakUsage = tPeakUsage; - //mutex.unlock(); if (verbose > 3) { std::stringstream tempStream; - //std::string temp; tempStream << setfill(' ') << setw(3); tempStream << "*** UBX-MON-RXBUF message:" << endl; tempStream << " global RX buf usage : " << dec << (int)tUsage << " %" << endl; @@ -1596,8 +1505,6 @@ void QtSerialUblox::UBXMonRx(const std::string& msg) tempStream << " (" << dec << i << ") " << setw(3) << pending[i]; } tempStream << "\n"; - //tempStream << setw(1) << setfill(' '); - //tempStream >> temp; emit toConsole(QString::fromStdString(tempStream.str())); } } @@ -1607,17 +1514,16 @@ void QtSerialUblox::UBXCfgNavX5(const std::string& msg) // parse all fields uint8_t version = msg[0]; uint16_t mask1 = msg[1]; - mask1 |= msg[2]<<8; + mask1 |= msg[2] << 8; uint8_t minSVs = msg[10]; uint8_t maxSVs = msg[11]; uint8_t minCNO = msg[12]; uint8_t iniFix3D = msg[14]; uint16_t wknRollover = msg[18]; - wknRollover |= msg[19]<<8; -// uint8_t usePPP = msg[26]; + wknRollover |= msg[19] << 8; uint8_t aopCfg = msg[27]; uint16_t aopOrbMaxErr = msg[30]; - aopOrbMaxErr |= msg[31]<<8; + aopOrbMaxErr |= msg[31] << 8; if (verbose > 2) { std::stringstream tempStream; tempStream << "*** UBX-MON-NAVX5 message:" << endl; @@ -1631,32 +1537,30 @@ void QtSerialUblox::UBXCfgNavX5(const std::string& msg) tempStream << " max AOP orbit error : " << (int)aopOrbMaxErr << " m" << endl; emit toConsole(QString::fromStdString(tempStream.str())); } - //emit gpsMonHW2(ofsI,magI,ofsQ,magQ,cfgSrc); } void QtSerialUblox::UBXCfgAnt(const std::string& msg) { // parse all fields uint16_t flags = msg[0]; - flags |= msg[1]<<8; + flags |= msg[1] << 8; uint16_t pins = msg[2]; - pins |= msg[3]<<8; + pins |= msg[3] << 8; if (verbose > 2) { std::stringstream tempStream; tempStream << "*** UBX-CFG-ANT message:" << endl; tempStream << " flags : 0x" << hex << (int)flags << dec << endl; - tempStream << " ant supply control signal : " << string((flags&0x01)?"on":"off") << endl; - tempStream << " short detection : " << string((flags&0x02)?"on":"off") << endl; - tempStream << " open detection : " << string((flags&0x04)?"on":"off") << endl; - tempStream << " pwr down on short : " << string((flags&0x08)?"on":"off") << endl; - tempStream << " auto recovery from short : " << string((flags&0x10)?"on":"off") << endl; - tempStream << " supply switch pin : " << (int)(pins&0x1f) << endl; - tempStream << " short detection pin : " << (int)((pins>>5)&0x1f) << endl; - tempStream << " open detection pin : " << (int)((pins>>10)&0x1f) << endl; + tempStream << " ant supply control signal : " << string((flags & 0x01) ? "on" : "off") << endl; + tempStream << " short detection : " << string((flags & 0x02) ? "on" : "off") << endl; + tempStream << " open detection : " << string((flags & 0x04) ? "on" : "off") << endl; + tempStream << " pwr down on short : " << string((flags & 0x08) ? "on" : "off") << endl; + tempStream << " auto recovery from short : " << string((flags & 0x10) ? "on" : "off") << endl; + tempStream << " supply switch pin : " << (int)(pins & 0x1f) << endl; + tempStream << " short detection pin : " << (int)((pins >> 5) & 0x1f) << endl; + tempStream << " open detection pin : " << (int)((pins >> 10) & 0x1f) << endl; emit toConsole(QString::fromStdString(tempStream.str())); } - //emit gpsMonHW2(ofsI,magI,ofsQ,magQ,cfgSrc); } void QtSerialUblox::UBXCfgTP5(const std::string& msg) @@ -1666,33 +1570,33 @@ void QtSerialUblox::UBXCfgTP5(const std::string& msg) tp.tpIndex = msg[0]; tp.version = msg[1]; tp.antCableDelay = msg[4]; - tp.antCableDelay |= msg[5]<<8; + tp.antCableDelay |= msg[5] << 8; tp.rfGroupDelay = msg[6]; - tp.rfGroupDelay |= msg[7]<<8; + tp.rfGroupDelay |= msg[7] << 8; tp.freqPeriod = msg[8]; - tp.freqPeriod |= msg[9]<<8; - tp.freqPeriod |= msg[10]<<16; - tp.freqPeriod |= msg[11]<<24; + tp.freqPeriod |= msg[9] << 8; + tp.freqPeriod |= msg[10] << 16; + tp.freqPeriod |= msg[11] << 24; tp.freqPeriodLock = msg[12]; - tp.freqPeriodLock |= msg[13]<<8; - tp.freqPeriodLock |= msg[14]<<16; - tp.freqPeriodLock |= msg[15]<<24; + tp.freqPeriodLock |= msg[13] << 8; + tp.freqPeriodLock |= msg[14] << 16; + tp.freqPeriodLock |= msg[15] << 24; tp.pulseLenRatio = msg[16]; - tp.pulseLenRatio |= msg[17]<<8; - tp.pulseLenRatio |= msg[18]<<16; - tp.pulseLenRatio |= msg[19]<<24; + tp.pulseLenRatio |= msg[17] << 8; + tp.pulseLenRatio |= msg[18] << 16; + tp.pulseLenRatio |= msg[19] << 24; tp.pulseLenRatioLock = msg[20]; - tp.pulseLenRatioLock |= msg[21]<<8; - tp.pulseLenRatioLock |= msg[22]<<16; - tp.pulseLenRatioLock |= msg[23]<<24; + tp.pulseLenRatioLock |= msg[21] << 8; + tp.pulseLenRatioLock |= msg[22] << 16; + tp.pulseLenRatioLock |= msg[23] << 24; tp.userConfigDelay = msg[24]; - tp.userConfigDelay |= msg[25]<<8; - tp.userConfigDelay |= msg[26]<<16; - tp.userConfigDelay |= msg[27]<<24; + tp.userConfigDelay |= msg[25] << 8; + tp.userConfigDelay |= msg[26] << 16; + tp.userConfigDelay |= msg[27] << 24; tp.flags = msg[28]; - tp.flags |= msg[29]<<8; - tp.flags |= msg[30]<<16; - tp.flags |= msg[31]<<24; + tp.flags |= msg[29] << 8; + tp.flags |= msg[30] << 16; + tp.flags |= msg[31] << 24; bool isFreq = tp.flags & 0x08; bool isLength = tp.flags & 0x10; @@ -1705,44 +1609,51 @@ void QtSerialUblox::UBXCfgTP5(const std::string& msg) tempStream << " rf group delay : " << dec << (int)tp.rfGroupDelay << " ns" << endl; tempStream << " user config delay : " << dec << (int)tp.userConfigDelay << " ns" << endl; if (isFreq) { - tempStream << " pulse frequency : " << dec << (int)tp.freqPeriod << " Hz" << endl; - tempStream << " locked pulse frequency : " << dec << (int)tp.freqPeriodLock << " Hz" << endl; + tempStream << " pulse frequency : " << dec << (int)tp.freqPeriod << " Hz" << endl; + tempStream << " locked pulse frequency : " << dec << (int)tp.freqPeriodLock << " Hz" << endl; } else { - tempStream << " pulse period : " << dec << (int)tp.freqPeriod << " us" << endl; - tempStream << " locked pulse period : " << dec << (int)tp.freqPeriodLock << " us" << endl; + tempStream << " pulse period : " << dec << (int)tp.freqPeriod << " us" << endl; + tempStream << " locked pulse period : " << dec << (int)tp.freqPeriodLock << " us" << endl; } if (isLength) { - tempStream << " pulse length : " << dec << (int)tp.pulseLenRatio << " us" << endl; - tempStream << " locked pulse length : " << dec << (int)tp.pulseLenRatioLock << " us" << endl; + tempStream << " pulse length : " << dec << (int)tp.pulseLenRatio << " us" << endl; + tempStream << " locked pulse length : " << dec << (int)tp.pulseLenRatioLock << " us" << endl; } else { - tempStream << " pulse duty cycle : " << dec << (double)tp.pulseLenRatio/((uint64_t)1<<32) << endl; - tempStream << " locked pulse duty cycle : " << dec << (double)tp.pulseLenRatioLock/((uint64_t)1<<32) << endl; + tempStream << " pulse duty cycle : " << dec << (double)tp.pulseLenRatio / ((uint64_t)1 << 32) << endl; + tempStream << " locked pulse duty cycle : " << dec << (double)tp.pulseLenRatioLock / ((uint64_t)1 << 32) << endl; } tempStream << " flags : 0x" << hex << (int)tp.flags << dec << endl; - tempStream << " tp active : " << string((tp.flags&0x01)?"yes":"no") << endl; - - tempStream << " lockGpsFreq : " << string((tp.flags&0x02)?"on":"off") << endl; - tempStream << " lockedOtherSet : " << string((tp.flags&0x04)?"on":"off") << endl; - tempStream << " isFreq : " << string((tp.flags&0x08)?"on":"off") << endl; - tempStream << " isLength : " << string((tp.flags&0x10)?"on":"off") << endl; - tempStream << " alignToTow : " << string((tp.flags&0x20)?"on":"off") << endl; - tempStream << " polarity : " << string((tp.flags&0x40)?"rising":"falling") << endl; + tempStream << " tp active : " << string((tp.flags & 0x01) ? "yes" : "no") << endl; + + tempStream << " lockGpsFreq : " << string((tp.flags & 0x02) ? "on" : "off") << endl; + tempStream << " lockedOtherSet : " << string((tp.flags & 0x04) ? "on" : "off") << endl; + tempStream << " isFreq : " << string((tp.flags & 0x08) ? "on" : "off") << endl; + tempStream << " isLength : " << string((tp.flags & 0x10) ? "on" : "off") << endl; + tempStream << " alignToTow : " << string((tp.flags & 0x20) ? "on" : "off") << endl; + tempStream << " polarity : " << string((tp.flags & 0x40) ? "rising" : "falling") << endl; tempStream << " time grid : "; - if (getProtVersion()<16) tempStream<< string((tp.flags&0x80)?"GPS":"UTC") << endl; + if (getProtVersion() < 16) + tempStream << string((tp.flags & 0x80) ? "GPS" : "UTC") << endl; else { - int timeGrid = (tp.flags & UbxTimePulseStruct::GRID_UTC_GPS)>>7; + int timeGrid = (tp.flags & UbxTimePulseStruct::GRID_UTC_GPS) >> 7; switch (timeGrid) { - case 0: tempStream<<"UTC"<> 8) & 0xff; - msg[6]=tp.rfGroupDelay & 0xff; - msg[7]=(tp.rfGroupDelay >> 8) & 0xff; - msg[8]=tp.freqPeriod & 0xff; - msg[9]=(tp.freqPeriod>>8) & 0xff; - msg[10]=(tp.freqPeriod>>16) & 0xff; - msg[11]=(tp.freqPeriod>>24) & 0xff; - msg[12]=tp.freqPeriodLock & 0xff; - msg[13]=(tp.freqPeriodLock>>8) & 0xff; - msg[14]=(tp.freqPeriodLock>>16) & 0xff; - msg[15]=(tp.freqPeriodLock>>24) & 0xff; - msg[16]=tp.pulseLenRatio & 0xff; - msg[17]=(tp.pulseLenRatio>>8) & 0xff; - msg[18]=(tp.pulseLenRatio>>16) & 0xff; - msg[19]=(tp.pulseLenRatio>>24) & 0xff; - msg[20]=tp.pulseLenRatioLock & 0xff; - msg[21]=(tp.pulseLenRatioLock>>8) & 0xff; - msg[22]=(tp.pulseLenRatioLock>>16) & 0xff; - msg[23]=(tp.pulseLenRatioLock>>24) & 0xff; - msg[24]=tp.userConfigDelay & 0xff; - msg[25]=(tp.userConfigDelay >> 8) & 0xff; - msg[26]=(tp.userConfigDelay >> 16) & 0xff; - msg[27]=(tp.userConfigDelay >> 24) & 0xff; - msg[28]=tp.flags & 0xff; - msg[29]=(tp.flags >> 8) & 0xff; - msg[30]=(tp.flags >> 16) & 0xff; - msg[31]=(tp.flags >> 24) & 0xff; + msg[1] = 0; + msg[4] = tp.antCableDelay & 0xff; + msg[5] = (tp.antCableDelay >> 8) & 0xff; + msg[6] = tp.rfGroupDelay & 0xff; + msg[7] = (tp.rfGroupDelay >> 8) & 0xff; + msg[8] = tp.freqPeriod & 0xff; + msg[9] = (tp.freqPeriod >> 8) & 0xff; + msg[10] = (tp.freqPeriod >> 16) & 0xff; + msg[11] = (tp.freqPeriod >> 24) & 0xff; + msg[12] = tp.freqPeriodLock & 0xff; + msg[13] = (tp.freqPeriodLock >> 8) & 0xff; + msg[14] = (tp.freqPeriodLock >> 16) & 0xff; + msg[15] = (tp.freqPeriodLock >> 24) & 0xff; + msg[16] = tp.pulseLenRatio & 0xff; + msg[17] = (tp.pulseLenRatio >> 8) & 0xff; + msg[18] = (tp.pulseLenRatio >> 16) & 0xff; + msg[19] = (tp.pulseLenRatio >> 24) & 0xff; + msg[20] = tp.pulseLenRatioLock & 0xff; + msg[21] = (tp.pulseLenRatioLock >> 8) & 0xff; + msg[22] = (tp.pulseLenRatioLock >> 16) & 0xff; + msg[23] = (tp.pulseLenRatioLock >> 24) & 0xff; + msg[24] = tp.userConfigDelay & 0xff; + msg[25] = (tp.userConfigDelay >> 8) & 0xff; + msg[26] = (tp.userConfigDelay >> 16) & 0xff; + msg[27] = (tp.userConfigDelay >> 24) & 0xff; + msg[28] = tp.flags & 0xff; + msg[29] = (tp.flags >> 8) & 0xff; + msg[30] = (tp.flags >> 16) & 0xff; + msg[31] = (tp.flags >> 24) & 0xff; enqueueMsg(UBX_CFG_TP5, toStdString(msg, 32)); } -void QtSerialUblox::UBXNavDOP(const string &msg) +void QtSerialUblox::UBXNavDOP(const string& msg) { // UBX-NAV-DOP: dilution of precision values UbxDopStruct d; @@ -1824,18 +1735,17 @@ void QtSerialUblox::UBXNavDOP(const string &msg) emit UBXReceivedDops(d); - if (verbose>3) - { + if (verbose > 3) { std::stringstream tempStream; tempStream << "*** UBX NAV-DOP message:" << endl; tempStream << " iTOW : " << dec << iTOW / 1000 << " s" << endl; - tempStream << " geometric DOP : " << dec << d.gDOP/100. << endl; - tempStream << " position DOP : " << dec << d.pDOP/100. << endl; - tempStream << " time DOP : " << dec << d.tDOP/100. << endl; - tempStream << " vertical DOP : " << dec << d.vDOP/100. << endl; - tempStream << " horizontal DOP : " << dec << d.hDOP/100. << endl; - tempStream << " northing DOP : " << dec << d.nDOP/100. << endl; - tempStream << " easting DOP : " << dec << d.eDOP/100. << endl; + tempStream << " geometric DOP : " << dec << d.gDOP / 100. << endl; + tempStream << " position DOP : " << dec << d.pDOP / 100. << endl; + tempStream << " time DOP : " << dec << d.tDOP / 100. << endl; + tempStream << " vertical DOP : " << dec << d.vDOP / 100. << endl; + tempStream << " horizontal DOP : " << dec << d.hDOP / 100. << endl; + tempStream << " northing DOP : " << dec << d.nDOP / 100. << endl; + tempStream << " easting DOP : " << dec << d.eDOP / 100. << endl; emit toConsole(QString::fromStdString(tempStream.str())); } } diff --git a/daemon/src/utility/custom_io_operators.cpp b/daemon/src/utility/custom_io_operators.cpp new file mode 100644 index 00000000..adf868ed --- /dev/null +++ b/daemon/src/utility/custom_io_operators.cpp @@ -0,0 +1,23 @@ +#include "utility/custom_io_operators.h" + +std::ostream& operator<<(std::ostream& os, const QString& someQString) +{ + os << someQString.toStdString(); + return os; +} + +std::ostream& operator<<(std::ostream& os, const std::chrono::time_point& timestamp) +{ + std::chrono::microseconds mus = std::chrono::duration_cast(timestamp.time_since_epoch()); + std::chrono::seconds secs = std::chrono::duration_cast(mus); + std::chrono::microseconds subs = mus - secs; + + os << secs.count() << "." << std::setw(6) << std::setfill('0') << subs.count() << " " << std::setfill(' '); + return os; +} + +std::ostream& operator<<(std::ostream& os, const timespec& ts) +{ + os << ts.tv_sec << "." << std::setw(9) << std::setfill('0') << ts.tv_nsec << " " << std::setfill(' '); + return os; +} diff --git a/daemon/src/utility/filehandler.cpp b/daemon/src/utility/filehandler.cpp new file mode 100644 index 00000000..3fce7637 --- /dev/null +++ b/daemon/src/utility/filehandler.cpp @@ -0,0 +1,506 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "utility/filehandler.h" +#include +#include + +using namespace CryptoPP; + +const unsigned long int lftpUploadTimeout = MuonPi::Config::Upload::timeout; // in msecs +const int uploadReminderInterval = MuonPi::Config::Upload::reminder; // in minutes +const int logReminderInterval = MuonPi::Config::Log::interval; // in minutes + +static std::string SHA256HashString(std::string aString) +{ + std::string digest; + CryptoPP::SHA256 hash; + + CryptoPP::StringSource foo(aString, true, + new CryptoPP::HashFilter(hash, new CryptoPP::StringSink(digest))); + return digest; +} + +static QString getMacAddress() +{ + QNetworkConfiguration nc; + QNetworkConfigurationManager ncm; + QList configsForEth, configsForWLAN, allConfigs; + // getting all the configs we can + foreach (nc, ncm.allConfigurations(QNetworkConfiguration::Active)) { + if (nc.type() == QNetworkConfiguration::InternetAccessPoint) { + // selecting the bearer type here + if (nc.bearerType() == QNetworkConfiguration::BearerWLAN) { + configsForWLAN.append(nc); + } + if (nc.bearerType() == QNetworkConfiguration::BearerEthernet) { + configsForEth.append(nc); + } + } + } + // further in the code WLAN's and Eth's were treated differently + allConfigs.append(configsForWLAN); + allConfigs.append(configsForEth); + QString MAC; + foreach (nc, allConfigs) { + QNetworkSession networkSession(nc); + QNetworkInterface netInterface = networkSession.interface(); + // these last two conditions are for omiting the virtual machines' MAC + // works pretty good since no one changes their adapter name + if (!(netInterface.flags() & QNetworkInterface::IsLoopBack) + && !netInterface.humanReadableName().toLower().contains("vmware") + && !netInterface.humanReadableName().toLower().contains("virtual")) { + MAC = QString(netInterface.hardwareAddress()); + break; + } + } + return MAC; +} + +static QByteArray getMacAddressByteArray() +{ + QString mac = getMacAddress(); + QByteArray byteArray; + byteArray.append(mac); + return byteArray; +} + +static QString dateStringNow() +{ + return QDateTime::currentDateTimeUtc().toString("yyyy-MM-dd_hh-mm-ss"); +} + +FileHandler::FileHandler(const QString& userName, const QString& passWord, quint32 fileSizeMB, QObject* parent) + : QObject(parent) +{ + lastUploadDateTime = QDateTime(QDate::currentDate(), QTime(0, 0, 0, 0), Qt::TimeSpec::UTC); + dailyUploadTime = QTime(11, 11, 11, 111); + fileSize = fileSizeMB; + QDir temp; + QString fullPath = +"/var/muondetector/"; + hashedMacAddress = QString(QCryptographicHash::hash(getMacAddressByteArray(), QCryptographicHash::Sha224).toHex()); + fullPath += hashedMacAddress; + configPath = fullPath + "/"; + configFilePath = fullPath + "/currentWorkingFileInformation.conf"; + loginDataFilePath = fullPath + "/loginData.save"; + fullPath += "/notUploadedFiles/"; + dataFolderPath = fullPath; + if (!temp.exists(fullPath)) { + temp.mkpath(fullPath); + if (!temp.exists(fullPath)) { + qDebug() << "could not create folder " << fullPath; + } + } + QString uploadedFiles = configPath + "uploadedFiles/"; + if (!temp.exists(uploadedFiles)) { + temp.mkpath(uploadedFiles); + if (!temp.exists(uploadedFiles)) { + qDebug() << "could not create folder " << uploadedFiles; + } + } + bool rewrite_login = false; + if (!readLoginData()) { + qDebug() << "could not read login data from file"; + } + if (userName != "" || passWord != "") { + username = userName; + password = passWord; + rewrite_login = true; + } + if (rewrite_login) { + if (!saveLoginData(userName, passWord)) { + qDebug() << "could not save login data"; + } + } +} + +QString FileHandler::getCurrentDataFileName() const +{ + if (dataFile == nullptr) + return ""; + QFileInfo fi(*dataFile); + return fi.absoluteFilePath(); +} + +QString FileHandler::getCurrentLogFileName() const +{ + if (logFile != nullptr) + return ""; + QFileInfo fi(*logFile); + return fi.absoluteFilePath(); +} + +QFileInfo FileHandler::dataFileInfo() const +{ + if (dataFile == nullptr) + return QFileInfo(); + QFileInfo fi(*dataFile); + return fi; +} + +QFileInfo FileHandler::logFileInfo() const +{ + if (logFile == nullptr) + return QFileInfo(); + QFileInfo fi(*logFile); + return fi; +} + +// return current log file age in s +qint64 FileHandler::currentLogAge() +{ + if (dataFile == nullptr) + return -1; + if (configFilePath == "") + return -1; + QDateTime now = QDateTime::currentDateTime(); + QFileInfo fi(configFilePath); +#if QT_VERSION >= 0x050a00 + qint64 difftime = -now.secsTo(dataFile->fileTime(QFileDevice::FileBirthTime)); +#else + qint64 difftime = -now.secsTo(fi.created()); +#endif + + return difftime; +} + +void FileHandler::start() +{ + // set upload reminder + QTimer* uploadReminder = new QTimer(this); + uploadReminder->setInterval(60 * 1000 * uploadReminderInterval); // every 5 minutes or so + uploadReminder->setSingleShot(false); + connect(uploadReminder, &QTimer::timeout, this, &FileHandler::onUploadRemind); + uploadReminder->start(); + // open files that are currently written + openFiles(); + emit mqttConnect(username, password); + qDebug() << "sent mqttConnect"; +} + +// SLOTS +void FileHandler::onUploadRemind() +{ + if (dataFile == nullptr) { + return; + } + QDateTime todaysRegularUploadTime = QDateTime(QDate::currentDate(), dailyUploadTime, Qt::TimeSpec::UTC); + if (dataFile->size() > (1024 * 1024 * fileSize)) { + switchFiles(); + } + if (lastUploadDateTime < todaysRegularUploadTime && QDateTime::currentDateTimeUtc() > todaysRegularUploadTime) { + switchFiles(); + if (password.size() != 0 || username.size() != 0) { + } + lastUploadDateTime = QDateTime::currentDateTimeUtc(); + } +} + +// DATA SAVING +bool FileHandler::openFiles(bool writeHeader) +{ + if (dataFile != nullptr || logFile != nullptr) { + closeFiles(); + } + if (currentWorkingFilePath == "" || currentWorkingLogPath == "") { + readFileInformation(); + } + if (currentWorkingFilePath == "" || currentWorkingLogPath == "") { + writeHeader = true; + QString fileNamePart = createFileName(); + currentWorkingFilePath = dataFolderPath + "data_" + fileNamePart; + currentWorkingLogPath = dataFolderPath + "log_" + fileNamePart; + while (notUploadedFilesNames.contains(QFileInfo(currentWorkingFilePath).fileName())) { + fileNamePart = createFileName(); + currentWorkingFilePath = dataFolderPath + "data_" + fileNamePart; + currentWorkingLogPath = dataFolderPath + "log_" + fileNamePart; + } + writeConfigFile(); + } + dataFile = new QFile(currentWorkingFilePath); + dataFile->setPermissions(defaultPermissions); + if (!dataFile->open(QIODevice::ReadWrite | QIODevice::Append)) { + qDebug() << "file open failed in 'ReadWrite' mode at location " << currentWorkingFilePath; + // the following return statement induced wrong behavior: + // in case the data file couldn't be opened, the log file QFile object would never be instantiated + // this would prevent local logging + } + logFile = new QFile(currentWorkingLogPath); + logFile->setPermissions(defaultPermissions); + if (!logFile->open(QIODevice::ReadWrite | QIODevice::Append)) { + qDebug() << "file open failed in 'ReadWrite' mode at location " << currentWorkingLogPath; + } + if (!dataFile->isOpen() || !logFile->isOpen()) + return false; + // write header + if (writeHeader) { + QTextStream dataOut(dataFile); + dataOut << "#unix_timestamp_rising(s) unix_timestamp_trailing(s) time_accuracy(ns) valid timebase(0=gps,2=utc) utc_available\n"; + QTextStream logOut(logFile); + logOut << "#log parameters: time parname value unit\n"; + } + emit logRotateSignal(); + return true; +} + +void FileHandler::closeFiles() +{ + if (dataFile != nullptr) { + if (dataFile->isOpen()) { + dataFile->close(); + } + delete dataFile; + dataFile = nullptr; + } + if (logFile != nullptr) { + if (logFile->isOpen()) { + logFile->close(); + } + delete logFile; + logFile = nullptr; + } +} + +bool FileHandler::writeConfigFile() +{ + QFile configFile(configFilePath); + if (!configFile.open(QIODevice::ReadWrite | QIODevice::Truncate)) { + qDebug() << "file open failed in 'ReadWrite' mode at location " << configFilePath; + return false; + } + configFile.resize(0); + QTextStream out(&configFile); + out << currentWorkingFilePath << endl + << currentWorkingLogPath << endl; + return true; +} + +bool FileHandler::switchFiles(QString fileName) +{ + closeFiles(); + currentWorkingFilePath = "data_" + fileName; + currentWorkingLogPath = "log_" + fileName; + if (fileName == "") { + QString fileNamePart = createFileName(); + currentWorkingFilePath = dataFolderPath + "data_" + fileNamePart; + currentWorkingLogPath = dataFolderPath + "log_" + fileNamePart; + } + writeConfigFile(); + if (!openFiles(true)) { + closeFiles(); + return false; + } + return true; +} + +bool FileHandler::readFileInformation() +{ + QDir directory(dataFolderPath); + notUploadedFilesNames = directory.entryList(QStringList() << "*.dat", QDir::Files); + QFile configFile(configFilePath); + if (!configFile.open(QIODevice::ReadWrite)) { + qDebug() << "file open failed in 'ReadWrite' mode at location " << configFilePath; + return false; + } + QTextStream in(&configFile); + if (configFile.size() == 0) { + return true; + } + if (!in.atEnd()) { + currentWorkingFilePath = in.readLine(); + } + if (!in.atEnd()) { + currentWorkingLogPath = in.readLine(); + } + return true; +} + +void FileHandler::writeToDataFile(const QString& data) +{ + if (dataFile == nullptr) { + return; + } + QTextStream out(dataFile); + out << data << "\n"; +} + +void FileHandler::writeToLogFile(const QString& log) +{ + if (logFile == nullptr) { + return; + } + QTextStream out(logFile); + out << log << "\n"; +} + +QString FileHandler::createFileName() +{ + // creates a fileName based on date time and mac address + if (dataFolderPath == "") { + qDebug() << "could not open data folder"; + return ""; + } + QString fileName = dateStringNow(); + fileName = fileName + ".dat"; + return fileName; +} + +// upload related stuff + +bool FileHandler::uploadDataFile(QString fileName) +{ + char envName[] = "LFTP_PASSWORD"; + if (setenv(envName, password.toStdString().c_str(), 1) != 0) { + qDebug() << "setenv returned not 0"; + } + QProcess lftpProcess(this); + lftpProcess.setProgram("lftp"); + QStringList arguments; + arguments << "--env-password"; + arguments << "-p" << QString::number(MuonPi::Config::Upload::port); + arguments << "-u" << QString(username); + arguments << MuonPi::Config::Upload::url; + arguments << "-e" << QString("mkdir " + hashedMacAddress + " ; cd " + hashedMacAddress + " && put " + fileName + " ; exit"); + lftpProcess.setArguments(arguments); + lftpProcess.start(); + if (!lftpProcess.waitForFinished(lftpUploadTimeout)) { + qDebug() << lftpProcess.readAllStandardOutput(); + qDebug() << lftpProcess.readAllStandardError(); + qDebug() << "lftp not installed or timed out after " << lftpUploadTimeout / 1000 << " s"; + system("unset LFTP_PASSWORD"); + return false; + } + if (lftpProcess.exitStatus() != 0) { + qDebug() << "lftp returned exit status other than 0"; + unsetenv(envName); + return false; + } + unsetenv(envName); + return true; +} + +bool FileHandler::uploadRecentDataFiles() +{ + readFileInformation(); + QDir lftpDir; + lftpDir.setPath(lftpDir.homePath() + "/.lftp"); + if (!lftpDir.exists()) { + lftpDir.mkpath("."); + } + QFile lftp_rc_file(lftpDir.path() + "/rc"); + if (!lftp_rc_file.exists() || lftp_rc_file.size() < 10) { + if (!lftp_rc_file.open(QIODevice::ReadWrite)) { + qDebug() << "could not open .lftp/rc file"; + return false; + } + lftp_rc_file.write("set ssl:verify-certificate no\n"); + lftp_rc_file.close(); + } + for (auto& fileName : notUploadedFilesNames) { + QString filePath = dataFolderPath + fileName; + if (filePath != currentWorkingFilePath && filePath != currentWorkingLogPath) { + if (!uploadDataFile(filePath)) { + qDebug() << "failed to upload recent files"; + return false; + } + QFile::rename(filePath, QString(configPath + "uploadedFiles/" + fileName)); + } + } + return true; +} + +// crypto related stuff + +bool FileHandler::saveLoginData(QString username, QString password) +{ + QFile loginDataFile(loginDataFilePath); + loginDataFile.setPermissions(QFileDevice::ReadOwner | QFileDevice::WriteOwner); + if (!loginDataFile.open(QIODevice::ReadWrite)) { + qDebug() << "could not open login data save file"; + return false; + } + loginDataFile.resize(0); + + AutoSeededRandomPool rnd; + std::string plainText = QString(username + ";" + password).toStdString(); + std::string keyText; + std::string encrypted; + + keyText = SHA256HashString(getMacAddress().toStdString()); + SecByteBlock key((const byte*)keyText.data(), keyText.size()); + + // Generate a random IV + SecByteBlock iv(AES::BLOCKSIZE); + rnd.GenerateBlock(iv, iv.size()); + + // Encrypt + + CFB_Mode::Encryption cfbEncryption; + cfbEncryption.SetKeyWithIV(key, key.size(), iv, iv.size()); + + StringSource encryptor(plainText, true, + new StreamTransformationFilter(cfbEncryption, + new StringSink(encrypted))); + loginDataFile.write((const char*)iv.data(), iv.size()); + loginDataFile.write(encrypted.c_str()); + return true; +} + +bool FileHandler::readLoginData() +{ + QFile loginDataFile(loginDataFilePath); + if (!loginDataFile.open(QIODevice::ReadWrite)) { + qDebug() << "could not open login data save file"; + return false; + } + + std::string keyText; + std::string encrypted; + std::string recovered; + + keyText = SHA256HashString(getMacAddress().toStdString()); + SecByteBlock key((const byte*)keyText.data(), keyText.size()); + + // read encrypted message and IV from file + SecByteBlock iv(AES::BLOCKSIZE); + char ivData[AES::BLOCKSIZE]; + if (int read = loginDataFile.read(ivData, AES::BLOCKSIZE) != AES::BLOCKSIZE) { + qDebug() << "read " << read << " bytes but should read " << AES::BLOCKSIZE << " bytes"; + return false; + } + iv.Assign((byte*)ivData, AES::BLOCKSIZE); + QByteArray data = loginDataFile.readAll(); + encrypted = std::string(data.constData(), data.length()); // <-- right :) + + // Decrypt + CFB_Mode::Decryption cfbDecryption; + cfbDecryption.SetKeyWithIV(key, key.size(), iv, iv.size()); + + StringSource decryptor(encrypted, true, + new StreamTransformationFilter(cfbDecryption, + new StringSink(recovered))); + QString recoverdQString = QString::fromStdString(recovered); + QStringList loginData = recoverdQString.split(';', QString::SkipEmptyParts); + if (loginData.size() < 2) { + return false; + } + username = loginData.at(0); + password = loginData.at(1); + return true; +} diff --git a/daemon/src/utility/geohash.cpp b/daemon/src/utility/geohash.cpp new file mode 100644 index 00000000..3ab6a1bf --- /dev/null +++ b/daemon/src/utility/geohash.cpp @@ -0,0 +1,60 @@ +#include +#include "utility/geohash.h" + +static const QString base32 = "0123456789bcdefghjkmnpqrstuvwxyz"; // (geohash-specific) Base32 map + +/** + * Geohash: Gustavo Niemeyer’s geocoding system. + */ +QString GeoHash::hashFromCoordinates(double lon, double lat, int precision) +{ + if (precision < 0 || precision > 12) + precision = 12; + + uint8_t idx = 0; // index into base32 map + uint8_t bit = 0; // each char holds 5 bits + bool evenBit = true; + QString geohash = ""; + + double latMin = -90., latMax = 90.; + double lonMin = -180., lonMax = 180.; + + if (lon < lonMin || lon > lonMax) + return geohash; + if (lat < latMin || lat > latMax) + return geohash; + + while (geohash.size() < precision) { + if (evenBit) { + // bisect E-W longitude + const double lonMid = (lonMin + lonMax) / 2.; + if (lon >= lonMid) { + idx = idx * 2 + 1; + lonMin = lonMid; + } else { + idx = idx * 2; + lonMax = lonMid; + } + } else { + // bisect N-S latitude + const double latMid = (latMin + latMax) / 2.; + if (lat >= latMid) { + idx = idx * 2 + 1; + latMin = latMid; + } else { + idx = idx * 2; + latMax = latMid; + } + } + evenBit = !evenBit; + + if (++bit == 5) { + // 5 bits gives us a character: append it and start over + geohash += base32.at(idx); + bit = 0; + idx = 0; + } + } + + return geohash; +} diff --git a/source/daemon/src/gpio_mapping.cpp b/daemon/src/utility/gpio_mapping.cpp similarity index 80% rename from source/daemon/src/gpio_mapping.cpp rename to daemon/src/utility/gpio_mapping.cpp index c66cc29f..ebe19526 100644 --- a/source/daemon/src/gpio_mapping.cpp +++ b/daemon/src/utility/gpio_mapping.cpp @@ -1,4 +1,4 @@ -#include "gpio_mapping.h" +#include "utility/gpio_mapping.h" #include "config.h" #include diff --git a/source/gui/LICENSE b/gui/LICENSE similarity index 100% rename from source/gui/LICENSE rename to gui/LICENSE diff --git a/source/gui/README b/gui/README similarity index 100% rename from source/gui/README rename to gui/README diff --git a/source/gui/config/changelog b/gui/config/changelog similarity index 100% rename from source/gui/config/changelog rename to gui/config/changelog diff --git a/source/gui/config/description.txt b/gui/config/description.txt similarity index 100% rename from source/gui/config/description.txt rename to gui/config/description.txt diff --git a/gui/config/muon.ico b/gui/config/muon.ico new file mode 100644 index 0000000000000000000000000000000000000000..83b24830aebf680f6e3c07b7675f30e1d510d4c4 GIT binary patch literal 96062 zcmeHQ2YeLO*L}O21VU3p5D)4AL$_N&pJ zjJ<@r;krLku3w1#H#mMD`v-yH62NQha6EU%>GS)0y^!hgfB3dYXE4u&fu+Wn|4%@Z z7GT>SE|xNKKAv|B+e&Q2U~}}T|LFRS$Ff8Mf8H z$$uHaN@iS(e(l883;k@0Z{gxm_$Dr7x^S+%d!O9`zIZSXXht(^Lx2tPv#|MK7GCo= zaF+nwwE)d4G<^NO9Nc9ydPiA&_{QX$F;D$~lVe$kl}O_HKfF&IaMx_o_Cq?6J*8Wak6UBSXsMp zw5(nZWpLoCg7l-K_oBr(-u0Jv1 z4mmXKW!X8WyMfPn%NEO+HQRx|3}KM8Zs^F3$(6b+`85Y~nS{A9uzP_|UJW`%KKW0$ z7#j?^EpE+L(5RWRV{T75I;Eu$6B)r&xYwQre*c*CunXqa@y0M3EZ8BuK zn`pZ^SLEsJ-p}znjwSi!NwYmvFr$Z9S;>_gV!g^)Rn7c^ZWsFVq(Ly zO1DD6mfJahkG};x_iLHGd}+A!?j*+PJMh**({~-q!CV-a8;frgIJ+C)>$XraHe%f_ zgD)MP`mCHD8i#9IUk;2V z6~Q(pRE)*1-V7SnU;c@&mWnUPMSqV_lF(7fn~l$|OlD#wQv3hnipsCEzl2V_G91h; zg)CR`>i#owXq<+|Z8-8LX<1XyvcsX^Y$D`p>UgK(E(yRG=XiThCC#cUL4t*B?tX4# z&5GH5Gv1XMzbp?GbARHSeG58~C#z{lc6$EU&HFEcemOW4jE!5p#lYC_Ml~V<(0e>%S!a?m&uP^&rhroccm>Z*jO$4X)biiMp}$<+>Z=`Tz0<_Puoi+-^}uoe?diw>0Df9 zy>tFz&7^bx##fS+i{b@-lwg=U4W9Z{zcu?VD4yDP^$M0_>e3ZLped>xa;%4hNN-nP!EqTY4NrSVz@nxiG zH6^FUoc}yj_YEDI+E&IRcED|%p)(x9-z%Te*aWfzR?^#tWxtEUcT@)Nx5e%K$pikF z^k`6=(RS9bibwJcPfO2C{u%$;g^4p0d;i4WBny9fX-H9PV&F!9DPII3t?O9 zgfr>@$q8?ThcnV5V68(#&@~5Hjku$YP2HMXcEBDI$~;^s=ln6LIb!Bqb%x)8w<_n7 z>^5QRfxMt+j`}9!VGmAwA>BBb*g;9mhnMT=T8hmh_WP^knLGSG_zML~p}gmx6YmrH zlAUM(=IsFF>yqaJ-r~0&@SwkraT=r6CL%UE5NH354v+rq{SLk;(5?LQD!Ae;`pu&9 z;Uig(H_DE?`zYD@ZPxdNc>HsMJKli9b@WkZXS{*_GA8Ifr*CG&y4|2>?E~o9??aT- zx?0Kp@595}+lUp49e9;1*78Gki|$xVp1EB~Vz2P-9}0~KcFw=R*m&4p?!4Y(_-WPs z`K4l6uc1eu&SKl&pNJ!6JeJd3fnLNzugjKkaFcc(WlT_Gr@k{cN$YQd{ME6El9s^3 ziD9ARVfAOAZI55#-=Z_g{=8?A_Q1Tb-w4ux;`EK)?&_~By8xr2A zFGRmlRGz#QG_-$c&uCpQ2K~BBuFhRUZmXc=|84_*(8pozqGZAQKH1gVBcxrr{*Hc0 zNz^N_0a|>troNnSI&_!ol)UB}D)0E>m52n}3_v33TIC z2b*pRO*7}$+~@97TJE~h13D7?8HWdXr1>p*mpKaZ%`;^3cj!6Q#!EL%aE&V;4<<6)U zGOD(eWehq;OfYUP+R3lMZvebhfj*A)98Po33F^4i_qCFh-Oet3TeEPa6Kxa3 zeobATbUe#rky2tEwfUOkA$!s<7s@wD9qmr_H0Z}^>8K`1%Q_0QA~@dqJfkFck5VD= zQ4?$2=k9x@+zX#7b=qM4J2=2257ms3FTKcZ$LYGQuV;hYcVlsbzV&O3KJ_l`+$UlU zGU_N#vi4qsJv*h@O;K_(O#M9Ad$|3ban5s>{pg4{(32KDmTtq_XALif+!zD;x)GRYuSZoU+4%L@rEPyr zsEd4Uecl%4`S|b+NmpbA)<&$`OWw)cP3^a^5&4-`OoZ~AKK1r$pn)~wt*2Tex0Jj= zHhqnQ6j{i=XWUTvD?CDZ+e)`W{mpoB^+Z8=qmh!|`Zzy_&)xsMN19a6CtrJia>U5n zzOm3Jypnf9S?B%`YY!?J;`!C_KAn7%Wa^tf$M?36L!^$A;LCB8-8Lk}tv`GmgLHOj z8+d0a;OuW5)@CBt$0_&3ZA>UrUlVhq#H+u~;BA0Plo}V`>6$z6d_Cx+nmD#l@kU*d zJg;z#7>RpDiJNUXxxYsmS1l~vy+3PlGF_dLXMNozx!*}_u9lv`8tL0` zwO{J0mO?wiDVq#Kn?seWK-Z?hhULO9L-`wZ4Ar`jbcL_spOMZqE(v&RRJpkH@GjS4 zWeRlGX5J2x>ywiDJ`rn=#K-{8HtqGqT2Jo^>DM}Iuy%4>MfgoOYVn47-;Nr0xy}~e zpqJdN!x`H)AYRJ+KGL&a_a$;W)mt(Z<4v5I+c@r|H2S zXdHc8uiUF-PhV%e?d#`}dn;W5eyW$>#;apeC+2a9?W^%^5NnU+HtZ+Fm2Ue6IHoNn zJ!2S&Yxd1}M~gMiG3Ni3vw=0laWemDi4JR%R;@=psS+6)AM&q8mAx`lC7r>UiMPq% zPj9NR@>FdlN&Wmdcmw%UvHh=%9M)3snY&kMDOEX2e(mjyH}ccRZjP0YV1Lu$WhC^> za>Z*)o{=_tGqKh@FYIYswAb-opLu_Pe=F;-27`<+e@!>fXxk4PZ@$dN8~Ak--Sb&< zDhWBVk@%(Wg)wR#>Yy6id?-9K*g3SrJq2HZn{D~`!5(ST zKnZ1e9o`1O_FLqJGJ(1RvG#a=>F3#`y@vPsz&rh{+jQ-7cVc2=N1p<)_Ws0;zoDm@ zqbGFyaVKfo3LVyHo3Zyby~oM$A>F7N%0zY25pRRkZn;f8Ceic*rH5CBcumx6mtoGG zX&c{>{?g}xx31n9TI`U|Mm4x3)sH}|J$VtZwo!XNu}0t3w71W`9%`Sn)$sY~<{NU` z5%9Q7qiwi%ecf}ZBOjjnT*R=(_oY9+ms;V(u%4@%xRhZx-u@#Kb8`pWB; z4IWcYAAL*2%YEXVtHn=e?-cPoa{L$v?M(cv@Z}eLd^boJX9o zy3iBe56`+S*G|*SW9oalc}LrR!n@;xg*f1K*i59QgJb?k%F_o0ieir&W{;XcHx)UW$^*Z$!!5PV{s6WFg|we(dUn-ylk^ zj;Cu>mqTsQyVb&IiK79zt( zQ4={2o}-OT+c)FAkiK`b&*AKMz#m^vJ!AOei7BV;3-yykwYfBGKAP*(E2Qpq9vShX z6591xgT~sw@1Ki8j2ZGPJ;-;1KZ!PqUfxxPkBV_c-MsS+`K+rqK|1>4j5xG*zP|FD z?;H3IzIOC2Ojdu(!%=TL+HxntmKa;Gh^XArz_U+gzvq+r!19t0eMbDp=I&nE@vRrJ z#vb^KJwn^^5yU@HUuI6I^&KMh`^1F19cwp0zN#8AtZhhsN{4CIvCgb_;~4RqX1p%_ zR8BZ!JAGQkiQetl?>9#I8BX@ab)*Oy+bgc`bdepTU>k z#XC*tV`W@rdtZNf0a$M1`&ORteJJ<)UY0vNPf0b^M9QfKa=EGv`-?Zze}-wt*jWjl=0WtZknEz2iJN&0o0ftZVfWV%prW#=o^w{UvvI2cM7)d-l`k9Wkql1-HEKpg-gYUTE?K`yvaXQ}Md=z$HZ>vIx^T))5z;FH- z%GeHPoiQu1=Jf1|umv?zFUg`0B5N}t4|B?gft*z@qgVrdY^|edbFmIdD03Bwb3TKt zPG5l=*66>wMLp~s?*W@uzNzJmc-bxwxyN$Y`<&RzD|N1^;3&&G&3RU~GdAwt$`?gk zw{X-Eu*S*IwR`XZr;oM`!`er{nl_#zarW0|4Qp$^P|!8scEuWT_^z5PG4ES!ZKxxY zXT&v<>(dhAMb1@?avm9rm?5_q4m-}w<6n`-(yYcMhK+Rs=tfrJD3oWDx85B6AmWZA zYd1MMeVU7OyyRXk{#1^^HHpU*QYRHL4 z{Zb$D;tCe`%Igi4On6-x@s>_GPbQv%?SJd5q~^6zQY^ZHv_^~?^-sp>G7fE+=QpJD z9hPb8ziflUO40R=_|9PO74F~tYa6AFk%c~5DZN;OUZC|!alNo``2X*JPiz2h%)GA-mzsQwjb=h-AYRIYsCy-fak6PqHaLW z@s&z0yQHk#6xBo;t5*;Q^`W%%bb}4|TZ1OP@0)7)O+WR{Gjz@Gyc=bpXS)pcB+5w7 zKH&8T{J?)Ars|}DTVmJ0okFhFDd6~YNLc1QpQ;_3Df7hoymtD-W7uF(pe22D4Kz)g zAGK-zz)X1uxA{+kKfa2(UnXJf-DunAY6)zvU?3sL{lU&5uN{V15?|FA$@LX<+}SQQ z9Uu=H`Nq&a7>}NBQaK~GBhTn-VQ0QtV!yjea`(DYa&<3-S|nFU%sZDGvAa>P6ct~K zOGVwEPZaDssus2y*eYSW7O{Dk7nI8{zD_Fo?vR_+LvpuzPMZ1NkOyJEenh<|kE;*l zaZgw5yUPFJ_y4Ib^00bWs(2c~?+{ttz#OmSgbsSF!CtXx%XSQYcz7GS`d7+oKcvNP za>V`Y<~s!2Gghs)+Te;c##G*LNhSFsgq%OO=h5y)`&%^PJj~kS;rhEmKHtPC_X|@o zOKdY%*uXC0j;Y%)XQpaN4{8B>;5+lmdgLyz`_jMXZ{{*@`^GB=E%~Z$@0p&zog8-! z?7C_5mw}fP*uut|`gk$zYNza28@V#r$ zFUlBg`|=4Txq{R}3K>f_`(8$`Q}y!5z7TQ^!x`Uj&z97@)J*k zSoq`Tx?*h-Waz4@sZgd*@3SASiQKI5E_rtmrd8o!js6kpO7?f7o^8~)iGZwXy*KN5 zy#{?=)z4$BhZ9vZm&6bHSc^622i?d;0fcZ_h0&`!$ro>-VR@8|1aQ)3zT(CqmZ` zfU^WU)_CtfCN)m;J*D?uoUYsOl``^Iy#Kqzh`D7fWV;6bdU^E6Gq+`++T}{yh9Nhm z;f?vy<=c$5zSpqm?zE9~Jqhx+(#Ey zYKSY=s6RAO9b`RXh3wA><(RbrRl|G{%bQ_-eQaz&X{kP!s5<#2)}fBMiA{4)9XQwL zS4hF?G4d^RBYWHv--U8%=VquO0xZP#yHZ}hC$uDr)mMr=o#wbhxQnr?YJhz!B?e(C^IjEBt+-x9}~bqb1CkA@x} zh!>9cjRk52^~Zmvew3aq1Fv-(U+dpUKUv#8<{i*BeADLKXJpUXMU4GqoB(sHeeDW4 z=TM_QE7#b%?8a!rHf_kBar$@Jh#C~?K71FbqshLiCkx8ruKIJW@96fs6S3PHd=v5N ztf@E>G|tQer~Edwt&(rYj?>XKwqfDm(0C|n!d#2<)2vH2Clho~%4N*G^FoggsN2Ui zF+f+Ae5fC@Pn#?GN-cAxZM3zOEm%6NdX?7kCoS#x0KV^+kgJs*zGvfy%)z-;J!;6B z6V$)Rm6$9ADijO zd{Zt%H}WC|wMUCoI!U|Z?T9apdc2@Cc;Z?33X;>{4SrDs0ELD%;?mAPdAxMVjCAoM zr*|XH7{lRxK6NcdbG+y;CqH$%b`AXTkEqVBSfkyojp~yjTO0K{%G>JUiws+;*}wGe zy-o5Obj`F04phI&?Y<`@26cT&LwMiZ@GW$HFtk{dmE9myp>Ov7&@K`z*U&z;{I(7c z^v5VG59^jFL%*`>w$y(qKeOilJx{mQVh!@wOQB*7vRw@w)>bc?;5hg8eur{QpSX{) z+ob(g8o)dw_=ViQY3lcND=J}bi#cz)eQ&i_PbbX4Qu*Y=|@1H zt^IfTo%@?o^1SL5&}YWxwNzigS5?rUB_;5jQ0z6#|9P+m>Te;I#oia{i`QT44eCFk zAC7kKc6TW$idcnwSNf1ofm-3f9p5`(d@zQMD#I28*(Tp~+`m>m!8)*M=o+vSat#K= zz5P#zwT%&s!zF#csRG^&V`3jC@|sq4g5!fVh2BvU1Ln<+H^#NqjCvqIrVSXsAabPj zT-IB7;#Tlf)ZGoYmZkZQysmhW3V{CcfPS;a;ah5)sEbhp@Fm+EJM=LQG=_aK?`_{x zkJj1Y_)e6&mw%$cIjs{cQ~$x8fT#{nh(|`{ReHWNB0-H2EjgcOZ|Wo%1z3|AtbCC2CT@pbvGi zmI3WgjCETAU9cZyy+^9yePL@?&lQqfAC)k4+XvKZTCDLKc?I?y#zndHW$eq8n}XQ? zsFT)-4XC&DJM2odRYp_4PLU5u51Ehexh*&R_U_MR9Z$2i?2##tX|V=6H9n(Q`*k+l z57xO($8XLN?SVSpY2^WoX;6<{WXvUNjPg3GjB56Sb&y-DZye{%Pv1_<1F*HZ)u%M? z7xo@_C#@rYrOvEdqk(eIVc2OHUp)B@CH-3~sa6{LH)1>e{R_-ToS^_gT= zwLElp1h7V%RmioJ@m=N_0@(n(NZpfHZo5)RxBpYZZ_9jd@`DP6OQey1>~q*nElRho z&3slQ_rt-5yQrC3tg-Lp`^2UFnbeosLyphg)4d)wW9FLH@Cet%;XR1=j~@dqw8qG% z;EmsX4am;qk@n}g9se<@i44;CsUm^3#0+AMeiZNRsE1(JJ8j>X`K<-)fjh1jKp$lk za7SAsYkttz@cna2K2q}>=Z$kmS-fiTvRb<1HlCUFH^xf1`E}`odm8$YsS8q;r!G|V zhA7GXHR3ig9s%QH8AHR)4}aB;o~hVb^%?j$>xXI9@M6q-de)Kteey$@M%Q-C{U$8j z+vjNvWDMHPoW>~Rc3_qD{a6nxx_p#eS3=1>s*Nkwh_}|NC-T@*$KT$+vw2J#d^6Z9 zhN^wqep4^4g_>WcPbi@yumYJP6#bX}2CEOAw7)6zP3kde#+Wi4zJIfJVmM=Pc*^5i zc@6e8ES{1v9=c^-?+jt>v053dp=|kf&x{$yin^b-ZXWpKf7Q+#amJ0dwm0F^3uip- z=aRm#KHSoe{PLGhhO}R!J0`t)5&9-`zs&yG_sp-D2pi-^_~<-XPb-*wW{wGctrbv9 ze{dUR=vQ3ZQpY=aKC#=dd@B9a_0_5E;I!6StRW`~KnV?N@G&&h**w<$Ff85kMA<&3 z4%T7R;UxlXl!ISY!yV_1^T=FY=o?yIrUI z8-2W7m;QFolaBFGLHs$UjQ3wun>{!y2Ve#_bJs2hiH+NigdRksLrI6Hl?9>1;P zjT}C+U!m?rY`9_O1;3s6i0dT3s+M=Ikhut5uf20SDcX4{(NVI#N zEg)a3<&N{lIUJ()O4DlLub;@Zh@5H)(nnMnah$Zbo3gz5-nu>Q^{QzBLq}pv8tYA4 z@n!w}4)|zHSNAobGdgzE^;_H)K5e5PNk`XU%MCdWeDd~#`Eiev_WLBPSeY)YQJ1dD zH3-tVwo0gDNjlLSIcwIr(*3?4d7I(b+77_Zpb$Ui7VBZy1DjuL#H{G>Wwuc#Xjs)F zd13cAJ| zsx<4Fja{<^IaDae3;8&ljj3o3i~N<8l|;>Dpk_VE#A6b@R;r&|jMiu>)rOqxJnV z<2U)-dupoVyb*7-wUsY)RY0t-*8I3U&qC+ML%vZJ=cg0yA?J@=7Of+g>koT zdJTP~hMX8-e3{QT_l)1TqH=V|HCrd@*LL}L;JSSn<p`retD6s} zHriX&(-B-(CCGSlzL_7+Tq=`}>GrKu563u6-Mjn+8x><0eTtpIV=JXF%dqmxV?={G~N8<0a!BvIcOIx$G-}c`p<8PFq z>wZf^*AS1k3w6}O#o9Y|y2j&eb9=e=A)rt26}GGIU_;EraZ?X@q_5iSiZ#}=5615T z-UT?JE$!W=dVeD4*`RAFJd|-^jMumpYXF*Yc%+YaB3?Ei{y1eEe291Kqc%DAnQN=+ zu8Rb|?Dt?CF4`*Cy7;Yia+W-W>%RsP4^oCa-De3y@pk z53=`{$E*+iiW=&OHRd43e4xKpcfX9b(I$5b@W$K%-TZE!+cOPKBVK^Dcf;YIJQsBE zavj#Du3U|0hgQ>z>*9G4%atzzvHIbR9c|%-N|p-hkEgAHaY4GVbZhI`625P{%?t7u zeb_1%@kI^t8M#l)X{Dc>d6taLC=6N1$;ZUp(Hm4fN8V3gma3y1`FA+u6Y9D2KipZ# zBaHvGkH=3-60}$Yjk-5ntl=8UZ2QvUZC^;W*ZeipP^SR#dZE5sB+sL-)F~d(q;ZC= z4Sqsm!9JF5$Nt<=*yADFP_B=D39*rP#29sjlov8X;ew*Bf}DDp-w(z3amKe8wT@h5 z2T#+yj`}EVBK1)d{cQ13V=kcAtDAG5iB~hnwU;fH7$tK&o%ZA@U5OiC0ptFR z{rOt`V%UheX3>-sI~n~KjM4l?t(FdIH0rB9BEDt?{CRK=aW0H2!9Yj&?(yJu=dO1NkOqjnT2axTlK9- zkB961fN_QO;|HnV9OsU68LF*~@#bBCv0GGg`2cZeqfwL3js>@4#;Ny#@1M42?|sO% zhOOS-f5wVeSB)KG+PTi9strEsfK~hb(tFJB)OUAY83f#)XJ&~~ibkD2osk@z7Oo)c^=`TW<_NLNgZRewm85|^d1O_=XPJO9)-;rEDXAdI&R zR%_4=Z|2`vL#__|oY8NhwwqO!<@W(UsndE6yo>aVMYz{cRxcNQ zEBx{Qy5g;s>aMl5@tdYT`50(XusU2OjzZm!$NC@b)c2wqBUZ?gOGf`F^QoNf(^*Y( z)MdjRAM5$Kzb!3gDn-c@d{?yB*zsi^|2M9fj6kgo9Ss_@X@4OTJK^q!uGvl7$2YqB zu3b3Fu|M=dMebx%ndGh5FZ}q<@s_qB{9UGlP%j{-UH2!$Muz#FW$ix0xSmaR!>UP<=HAHwa%= zGp_;G?$BXv{OV2GevuY1XNhB$Rrs<#m+`xlk)~o4oaUccx>4PI#^%a#W(-tQ^(JuU zP7|H(8BRODg_s%_``1n;ABBx>u#23@nz`Y|vsuT){+l^%jK_4sm$jYick1u}+5U}_ z8NeCw1|2pU_uj9&|AA@k)AVn}r?6pSZA|<7MEn?YLVJo~Q?bfCcKMEVXs$0RBh?{C ztPvM)s4)ir;JDI%6{tnzlY^{$SL$N-xH&*8ywV*va9j1^xH<+Nphm|Fgk$u-_tHAmVh)La*rO zVeMpNT<}cFR;-gnyTr0j{P{-jKZIPqtG%d6S=#VZ`s)L^`{VCXFB-YHtfMd>NbZ7( zH_BD?V?GOC{&j_~GHM33gneIKo0-qC z@0rV!XH*2^jPU(N!=A>xK3(n}$9U4pby}6>|W3JmB=h%83 zZMDs?&OlqpSIk4E{ThxjgBN`P`tC(ttJv?al)NLaHR@%sRz{`#cS%pR*75#apYk^E zW60IX3p$tJcwVIWs4*{~lexgZ>%uR!pmSiYh2(@cwKxMNPK@2W|DufG%X;lm$Ze4Q zp4VY*-0H2UH3?P?+;g0pRLgw5fPQM`B=cLd(s=uC`u>~W41YKBZ#jnc`ao9P@Hg!m zm#QnV*2*W2b8KGI2XQ2|N>nmx`s#dK)RAbHW6d9<4g+jJj0s>ot{3%gJE&2PJd$)$ zDd<>OE6?;pn9nu$tkD`%3$?Hyw`TbJweSqyi!lVAwwGdECWUpL{bS7auXXbeTztnm zq*lCS^f&7NPXsgq@ND;KA1OWKG$haen7i&*~>jrLRED2 z$5U5*8Z}1SsJ^aPBX6r&;`*R5UT6A*Z}8v%CI16oWDRfTE_qtymlq)uI>~V_sD1|C zMq!OB6JORn`+BcxtIzqgVMjZLA)G^7g1R$SmJVtIoM~%c$*>K{l{1Ph`}KpdULSDw zxejZrZF(xMq%rT5lQJD^{PqxUeHZeVbTJ5L=Ga2_h&lS0K2-~~b7#(Df3-d6IZvpM zgmK~a=a7do2beXObag!#k5vCg)Rck`h;ho^mKQntKk3i7N>y`>A29eR^q%x$DU|Dc zZ41dK6MO_*Tgs_FtUVJ`J#+Y|F~+nPT~}1T`+1v|e?lj?%LywPZJ(WZi1v@(I@&gN z%{KXO{0(w_QTT>u`fG8Tn9%N7R|4-s`xx~p*8ZYALwg1NnA}r`jD?TdSknS?W0y@R zSKNkpK3#2W`yBI_dh0{L0BsOX^B1iB12sz+muJ5}Wy4A(QrCLn`&^E70T@qY&Euo4 ztWbN(d>8r)uDZOs=y)aLMp!$`$%nwc-ly96>0}5zQ9BPV*ToLJN*c9(SzD(R7+40G z3Oz`_pCH(^klRY)Ie+W$wsz5IBQDjbA8mUF#?%u_{O&1hsfy83qd00>RQAVsajmJr zZIv;P^vSWl7~>4+k8BQFS+O``5K%KmwJv1XI`hW)^?l;<`{&Zmy&VhYG3E8wA(sck zl+)k2)|GA@3)aLkYO`40+lZY+9v^LvhK>rna}7Z1Hr9FPcg1z`bkC$*rfWCbXvd@d z(0ac}{r0xHNZubaLrc?uvwMPJC8K}ecl0ph+CI}^ZP>a!vT5l5Nuf%q@uyrDj(OGh zLZ=z{yx%s!d7=Dd*r~yH$$L#KX!rO#b3_=o&zj8B-$MPo8kk$G^T2T?9<|q52&OVZMUG|MURyi6I+D!{jmmX@RE4{GKsd-GBt$n=(K6~zau&sRL zoS#lV2G?$I%E#v4=_^Q2%o1%QhQ49NZw7z+kPrLTpz&IohWW2yV&QD;p(nho!y4Px z&*)*`jW#gWP^63!G8QznDALywqfe-h(}lJ6YM}hkCGGpLra9}^1kkH6=iB>4fuJ!d zCg!dCu4*=F)<>>Z3hM;k()bb3w6wlY=$?beZ{Cjq$b6b+J_B-_54=?COBlKKS2;1U zakj#j6|dyowXTM27-noO=l5eZUt5b{G~`RlT^Yd|V|6L(TX7W1Z^jiEe3bfAnE1Az z&w7f!+Ii%&=}UAp?HJ~~u!(`QxkudYZBDdpHr9kc9hW)ljazY(-rua{&A7u*=F)l& zV`iC`XMZm1GV1Ek+UL^s*oY_cImYE$`(gk6fO<9Kd=zq{?|%j5#U2B7IHTS6#UZN_ z&nitb@jQaLRt~Y0#NgT=Mx>b&`y6G}G3%+;_B403C)nqc$CRfkM%|XC=2`-3mPaDy zowV^KH7M+FfNQE|wB{J=I5chdrVL)YHx1T6&lV0^pM+%1v&TE_&w}4IANrw<6Cb*M zuOubBm2L6XroIQd-`I|N1x#kUHH9l8Mg)tU7T4ryfAB%NCt$knjCF~i`WH3e)JTwNiYZ=qjL#+y_ zFV?;_MP2ykTu1t-`!YxFWIca8F**Xi(@w>WeM-J;}LX?{)G34E!{R5 zaZmroR|}XM>pW%UZ`w|{#wgcYE*D$X@P`vi);Uc3`?TDRwVAn=qS<%a3yWQwv3g9* zW4f!HGU`XuW}No9?si?~F3?tP$CBG|F60_iY0yx5E#9b|JIF{A`>p#eTj0#Z-Gr?N zXycu$!y4P>VLixGaYfF|jX6izX-~Y6H$Ho(k~>hVrHh&&W7JXYoOg$P?#=sCvBvjc zojJyFxXrEG-{=#fkAZdcD=6BVPimj-gh4+a^@PSpNkg$-)g6yMEq#`5(c^4=(r&Cx zR=}L&?6gOYUm@Tv$q8>iE}e~-vs~F4ZzlHXH>WSXdZ~-0h3ba<^)&%=&sd;(s#Smw zfpy!2gan_>3K?MI}0aYuo?1kXcyMq|4bYF7E!3P@<7|y z<@*(hTAX1H|An2QN_N7Ry)Tg6t_R-!a>Cp4#S<}>QRf8SIOl)E7DxXRYhhK*-N49! z@vlj6+K{QZPOK4&o??Tho%kZGV`1jtotfVdu&185IH1lRYoO65T;+-aM(!YM<_D`Q z$Jk=0HRaeB=3saqzerlX*Hs3tNo%W3nYYuBi5{K3_pfZlJMCE82AvrFZH7&&EAU-@ zSv&#sE&80nn?dW~+oC^~>-IFMuH=5iUoa2;9@Grs`kTf%Cf>S%zE$!Gd1A;|gB`Z? zJ|5?kp~qizW48|yYOHq+2gVL$UcSwPx;{J9KS zm)5S4f-}T*Bz-z{$H8okGZS}-f1XsJzi*j+*X>E)PRHd9m?P_aW#`|dWAwjsUBs)4 z_s;tYIgXzx{f&Iz2EcpHNL0%O{E5EFZp-%iC{9xzAN z`8pSVvsNV69pc{JU+Nm25gVXTvy?h!8oaS)+syLDI%W#%&MZ!e?YG}YcT7JUYu9tF z?(5Y(##(92K_J%XM`KKl5kCWZ%ySvjGZ+`JS}DWmkKz)BJ|p&iFg7b;mf}neX^(I1pc4dowLqRi8sWgP(OVW z?{~_4U)_H8@}-D>Ym|ex6dOu7xcnFE4*a}invQ-2v_Y=vJ7L>F7@p2u`7Bu9<2FNI zSfA9y&E8A=jar*1JLi0zgSRm7mOQ_7ImYCk; z#v{Fr@o|;mIDX_0yJmd~|JJ$VPYp-b3jJJ<9GL!!B>aL}_ZXL88+3qSz*-*N_+Myk zlXv~Wc*|Qc9*M!mjenoMVukFR@eVKtlaTE@Ki`iJPkmMv{JbD2zEZ~VFvhh7a_lY$ z*({vz23X4r8pj$AL1`SU~DFM!F4%uS;plB*p285 zlFlA{_9W~#NeLZg)uM4SdF9%$@s;xaOMtO@6Sp18(!9;A;(wX>-1trVXdmGkS);Hy z#{IhEaGy*C?O6Wf6iJ-(mHa;WG5Ig9bf(h2Q*p%+$8xXi2G&jb#> z-7mA@n_G;n0nW|gm0|MAaPbLUj5d-o81Jt!-hYNNKThXRx8SG8tobOvZ0N!gXZ|fY!Z; zd06Q%M`6j=)_V{igV*nuK?WXo%Wz<3_;FDY8ci5qmDRe!~RI%DNSGT zUWwScqE=6_ksEX9m>mOIam*UQkX4wnIVg@r>G( zTog3#L16BE%yj~`o%kKpFP2V>p2GbP;@Uabe~RZm3E95P$W6(f?^o?QZ^kxHrh302>`ZZ~9|+tk#*ClAH7^mXvs zyYRc_)a{4zV!cB(u{R6Ngw~&&^DgXhdU3=IH7oJ3n!N3xibK8FiP+D?dJi+U=hz=| zzKsj}+sK*!ocYheKn@0SFpz_R91NUS7{GJ}{7Vct@*kYlw*M5%ml*%d=bpyetz3JT z|ID^Tv?+g+*~Zh(oS1UnQKOB45crqUHs5Gdoh)tsOU;Y@=l$(JP5CV6C8o6bpX@)c zv)NXMCmL<$?NV-NwEbtE=D(rQ=IcHR2e#GGw3T98;Awb~MB8idMf7cfuf~^4 zw7o80E>QwsSKsErd4WT~K}g$%r5poijs4fPbxM@^ws%twZJq7s)k(AupHjNEQi=BA zQ!3Q9ixLCT!ahX0Emxv_iZDqLZu4pG=S#FtIVL@)&0!4E&XI0RBRy}qH2BlCWek() z|32^?b>=r={ipi|9optwujB7ddU}v(KTq`ZB^263dSwT`6aBMKx{h|T%}yjpi|vD| zYcptj=fIb%!)xaUwsm4#V(>Pcq~}qAFAQdj^8#Pa&+`Ib#NQV9A`o_PZD5<9uLgEH zh5rV0x|9FffLX%5ct2|gOr59VY2=cT@JsnoVJ52=&dX1<+Yuruy=W~hzZrQFZFp>aF2Ev1K@cssMr-$SE! mXWIN1moiQ>&oel4ia2?ujg!*Je_Co=$}xBT{#hC_+V=l1WBMKd literal 0 HcmV?d00001 diff --git a/source/gui/config/muondetector-gui.1 b/gui/config/muondetector-gui.1 similarity index 100% rename from source/gui/config/muondetector-gui.1 rename to gui/config/muondetector-gui.1 diff --git a/source/gui/config/muondetector-gui.desktop b/gui/config/muondetector-gui.desktop similarity index 100% rename from source/gui/config/muondetector-gui.desktop rename to gui/config/muondetector-gui.desktop diff --git a/source/gui/include/calibform.h b/gui/include/calibform.h similarity index 74% rename from source/gui/include/calibform.h rename to gui/include/calibform.h index ebf63203..b9909ad8 100644 --- a/source/gui/include/calibform.h +++ b/gui/include/calibform.h @@ -1,8 +1,8 @@ #ifndef CALIBFORM_H #define CALIBFORM_H -#include #include +#include #include struct CalibStruct; @@ -12,12 +12,11 @@ namespace Ui { class CalibForm; } -class CalibForm : public QWidget -{ +class CalibForm : public QWidget { Q_OBJECT public: - explicit CalibForm(QWidget *parent = 0); + explicit CalibForm(QWidget* parent = 0); ~CalibForm(); signals: void calibRequest(); @@ -25,14 +24,14 @@ class CalibForm : public QWidget void setBiasDacVoltage(float val); void setDacVoltage(uint8_t ch, float val); void updatedCalib(const QVector& items); - void setBiasSwitch(bool state); + void setBiasSwitch(bool state); public slots: void onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector& calibList); void onAdcSampleReceived(uint8_t channel, float value); QString getCalibParameter(const QString& name); const CalibStruct& getCalibItem(const QString& name); - void setCalibParameter(const QString &name, const QString &value); + void setCalibParameter(const QString& name, const QString& value); bool voltageCalibValid(); bool currentCalibValid(); void onUiEnabledStateChange(bool connected); @@ -41,19 +40,17 @@ public slots: private slots: void on_readCalibPushButton_clicked(); void on_writeEepromPushButton_clicked(); - void on_doBiasCalibPushButton_clicked(); void doFit(); - void on_transferBiasCoeffsPushButton_clicked(); void on_calibItemTableWidget_cellChanged(int row, int column); private: - Ui::CalibForm *ui; + Ui::CalibForm* ui; QVector fCalibList; QVector fPoints1, fPoints2, fPoints3; - double fSlope1=0.,fOffs1=0.; - double fSlope2=0.,fOffs2=0.; - - CalibScanDialog* calScan = nullptr; + double fSlope1 = 0., fOffs1 = 0.; + double fSlope2 = 0., fOffs2 = 0.; + + CalibScanDialog* calScan = nullptr; }; #endif // CALIBFORM_H diff --git a/source/gui/include/calibscandialog.h b/gui/include/calibscandialog.h similarity index 64% rename from source/gui/include/calibscandialog.h rename to gui/include/calibscandialog.h index 32636413..60806618 100644 --- a/source/gui/include/calibscandialog.h +++ b/gui/include/calibscandialog.h @@ -10,12 +10,11 @@ namespace Ui { class CalibScanDialog; } -class CalibScanDialog : public QDialog -{ +class CalibScanDialog : public QDialog { Q_OBJECT public: - explicit CalibScanDialog(QWidget *parent = 0); + explicit CalibScanDialog(QWidget* parent = 0); ~CalibScanDialog(); public slots: @@ -26,21 +25,20 @@ private slots: void transferCurrentCalibCoeffs(); private: - Ui::CalibScanDialog *ui; + Ui::CalibScanDialog* ui; QVector fCalibList; - bool fAutoCalibRunning=false; - uint8_t fCurrentCalibRunning=0; - float fCurrBias=0.; + bool fAutoCalibRunning = false; + uint8_t fCurrentCalibRunning = 0; + float fCurrBias = 0.; QVector fPoints1, fPoints2, fPoints3; - double fSlope1=0.,fOffs1=0.; - double fSlope2=0.,fOffs2=0.; + double fSlope1 = 0., fOffs1 = 0.; + double fSlope2 = 0., fOffs2 = 0.; double fLastRSenseHiVoltage = 0.; double fLastRSenseLoVoltage = 0.; - void setCalibParameter(const QString &name, const QString &value); - QString getCalibParameter(const QString &name); + void setCalibParameter(const QString& name, const QString& value); + QString getCalibParameter(const QString& name); void manualCurrentCalibProgress(double vbias, double ibias); - }; #endif // CALIBSCANDIALOG_H diff --git a/source/gui/include/custom_histogram_widget.h b/gui/include/custom_histogram_widget.h similarity index 62% rename from source/gui/include/custom_histogram_widget.h rename to gui/include/custom_histogram_widget.h index 00865b94..715ab1fd 100644 --- a/source/gui/include/custom_histogram_widget.h +++ b/gui/include/custom_histogram_widget.h @@ -6,30 +6,38 @@ #include #include #include -#include #include +#include class QwtPlotHistogram; class Histogram; -class CustomHistogram : public QwtPlot, public Histogram -{ +class CustomHistogram : public QwtPlot, public Histogram { Q_OBJECT signals: void histogramCleared(QString histogramName); + public: - CustomHistogram(QWidget *parent = 0) : QwtPlot(parent){ initialize();} - CustomHistogram(const QwtText &title_l, QWidget *parent = 0) : QwtPlot(title_l, parent){ initialize();} + CustomHistogram(QWidget* parent = 0) + : QwtPlot(parent) + { + initialize(); + } + CustomHistogram(const QwtText& title_l, QWidget* parent = 0) + : QwtPlot(title_l, parent) + { + initialize(); + } ~CustomHistogram(); void initialize(); - QwtPlotGrid *grid = nullptr; + bool enabled() const { return fEnabled; } + QwtPlotGrid* grid = nullptr; QString title = "Histogram"; - //virtual void replot(); public slots: void update(); void clear(); - void setStatusEnabled(bool status); + void setEnabled(bool status); void setXMin(double val); void setXMax(double val); bool getLogX() const { return fLogX; } @@ -42,13 +50,14 @@ public slots: void setData(const Histogram& hist); private slots: - void popUpMenu(const QPoint &pos); + void popUpMenu(const QPoint& pos); void exportToFile(); private: QwtPlotHistogram* fBarChart = nullptr; - bool fLogY=false; - bool fLogX=false; + bool fLogY = false; + bool fLogX = false; + bool fEnabled { false }; }; #endif // CUSTOMHISTOGRAM_H diff --git a/source/gui/include/custom_plot_widget.h b/gui/include/custom_plot_widget.h similarity index 55% rename from source/gui/include/custom_plot_widget.h rename to gui/include/custom_plot_widget.h index 716a334b..79fb8a3a 100644 --- a/source/gui/include/custom_plot_widget.h +++ b/gui/include/custom_plot_widget.h @@ -1,32 +1,35 @@ #ifndef CUSTOMPLOT_H #define CUSTOMPLOT_H +#include #include -#include #include +#include #include -//#include -//#include -//#include -class CustomPlot : public QwtPlot -{ +class CustomPlot : public QwtPlot { Q_OBJECT public: - CustomPlot(QWidget *parent = 0) : QwtPlot(parent){ initialize();} - CustomPlot(const QwtText &title, QWidget *parent = 0) : QwtPlot(title, parent){ initialize();} + CustomPlot(QWidget* parent = 0) + : QwtPlot(parent) + { + initialize(); + } + CustomPlot(const QwtText& title, QWidget* parent = 0) + : QwtPlot(title, parent) + { + initialize(); + } ~CustomPlot(); void initialize(); - QwtPlotGrid *grid = nullptr; + QwtPlotGrid* grid = nullptr; QwtPlotCurve& curve(const QString& curveName); - void addCurve(const QString& name, const QColor& curveColor=Qt::blue); + void addCurve(const QString& name, const QColor& curveColor = Qt::blue); - void setStatusEnabled(bool status); + void setEnabled(bool enabled); // for other plots: subclass "CustomPlot" and put all specific functions (like below) to the new class - - //const QString title = "Plot"; static QwtPlotCurve INVALID_CURVE; signals: @@ -40,13 +43,12 @@ public slots: void exportToFile(); private slots: - void popUpMenu(const QPoint &pos); + void popUpMenu(const QPoint& pos); private: QMap fCurveMap; - bool fLogY=false; - bool fLogX=false; - + bool fLogY = false; + bool fLogX = false; }; #endif // CUSTOMPLOT_H diff --git a/source/gui/include/gnssposwidget.h b/gui/include/gnssposwidget.h similarity index 66% rename from source/gui/include/gnssposwidget.h rename to gui/include/gnssposwidget.h index 7fb66045..ccb3cf3f 100644 --- a/source/gui/include/gnssposwidget.h +++ b/gui/include/gnssposwidget.h @@ -1,17 +1,17 @@ #ifndef GNSSPOSWIDGET_H #define GNSSPOSWIDGET_H -#include -#include -#include -#include #include #include +#include #include +#include +#include +#include class GnssSatellite; -constexpr int DEFAULT_CONTROL_POINTS=5; +constexpr int DEFAULT_CONTROL_POINTS = 5; namespace Ui { class GnssPosWidget; @@ -27,42 +27,40 @@ struct SatHistoryPoint { QDateTime time; }; -class GnssPosWidget : public QWidget -{ +class GnssPosWidget : public QWidget { Q_OBJECT public: - explicit GnssPosWidget(QWidget *parent = 0); + explicit GnssPosWidget(QWidget* parent = 0); ~GnssPosWidget(); - void resizeEvent(QResizeEvent *event); + void resizeEvent(QResizeEvent* event); public slots: - void onSatsReceived(const QVector &satlist); + void onSatsReceived(const QVector& satlist); void replot(); void onUiEnabledStateChange(bool connected); private slots: void on_satSizeSpinBox_valueChanged(int arg1); - void popUpMenu(const QPoint &); + void popUpMenu(const QPoint&); void exportToFile(); private: - Ui::GnssPosWidget *ui; -// QMap> satTracks; + Ui::GnssPosWidget* ui; QMap>> satTracks; QVector fCurrentSatlist; -// int cnrColorRange=40; - QPointF polar2cartUnity(const QPointF &pol); - QPolygonF getPolarUnitPolygon(const QPointF& pos, int controlPoints=DEFAULT_CONTROL_POINTS); + QPointF polar2cartUnity(const QPointF& pol); + QPolygonF getPolarUnitPolygon(const QPointF& pos, int controlPoints = DEFAULT_CONTROL_POINTS); QPolygonF getCartPolygonUnity(const QPointF& polarPos); void drawPolarPixMap(QPixmap& pm); void drawCartesianPixMap(QPixmap& pm); int alphaFromCnr(int cnr); }; -inline uint qHash(const QPoint& p){ - return 1000*p.x()+p.y(); +inline uint qHash(const QPoint& p) +{ + return 1000 * p.x() + p.y(); } #endif // GNSSPOSWIDGET_H diff --git a/source/gui/include/gpssatsform.h b/gui/include/gpssatsform.h similarity index 62% rename from source/gui/include/gpssatsform.h rename to gui/include/gpssatsform.h index c648bc73..ffcbee40 100644 --- a/source/gui/include/gpssatsform.h +++ b/gui/include/gpssatsform.h @@ -1,12 +1,9 @@ #ifndef GPSSATSFORM_H #define GPSSATSFORM_H -#include -//#include -//#include #include #include -//#include +#include struct GeodeticPos; class GnssSatellite; @@ -17,19 +14,11 @@ namespace Ui { class GpsSatsForm; } -//struct SatHistoryPoint; -/* -struct SatHistoryPoint { - QPointF pos; - QColor color; -}; -*/ -class GpsSatsForm : public QWidget -{ +class GpsSatsForm : public QWidget { Q_OBJECT public: - explicit GpsSatsForm(QWidget *parent = 0); + explicit GpsSatsForm(QWidget* parent = 0); ~GpsSatsForm(); public slots: @@ -37,9 +26,7 @@ public slots: void onTimeAccReceived(quint32 acc); void onFreqAccReceived(quint32 acc); void onIntCounterReceived(quint32 cnt); -// void onGpsMonHWReceived(quint16 noise, quint16 agc, quint8 antStatus, quint8 antPower, quint8 jamInd, quint8 flags); void onGpsMonHWReceived(const GnssMonHwStruct& hwstruct); -// void onGpsMonHW2Received(qint8 ofsI, quint8 magI, qint8 ofsQ, quint8 magQ, quint8 cfgSrc); void onGpsMonHW2Received(const GnssMonHw2Struct& hw2struct); void onGpsVersionReceived(const QString& swString, const QString& hwString, const QString& protString); void onGpsFixReceived(quint8 val); @@ -48,10 +35,8 @@ public slots: void onUbxUptimeReceived(quint32 val); private: - Ui::GpsSatsForm *ui; + Ui::GpsSatsForm* ui; QVector iqTrack; -// QMap> satTracks; - }; #endif // GPSSATSFORM_H diff --git a/source/gui/include/histogramdataform.h b/gui/include/histogramdataform.h similarity index 78% rename from source/gui/include/histogramdataform.h rename to gui/include/histogramdataform.h index 72d8770a..aa85a9e2 100644 --- a/source/gui/include/histogramdataform.h +++ b/gui/include/histogramdataform.h @@ -1,9 +1,9 @@ #ifndef HISTOGRAMDATAFORM_H #define HISTOGRAMDATAFORM_H -#include #include #include +#include class Histogram; @@ -11,13 +11,13 @@ namespace Ui { class histogramDataForm; } -class histogramDataForm : public QWidget -{ +class histogramDataForm : public QWidget { Q_OBJECT signals: void histogramCleared(QString histogramName); + public: - explicit histogramDataForm(QWidget *parent = 0); + explicit histogramDataForm(QWidget* parent = 0); ~histogramDataForm(); public slots: void onHistogramReceived(const Histogram& h); @@ -29,9 +29,9 @@ private slots: void on_tableWidget_cellClicked(int row, int column); private: - Ui::histogramDataForm *ui; + Ui::histogramDataForm* ui; QMap fHistoMap; - QString fCurrentHisto=""; + QString fCurrentHisto = ""; }; #endif // HISTOGRAMDATAFORM_H diff --git a/source/gui/include/i2cform.h b/gui/include/i2cform.h similarity index 67% rename from source/gui/include/i2cform.h rename to gui/include/i2cform.h index b2730269..6f1c1339 100644 --- a/source/gui/include/i2cform.h +++ b/gui/include/i2cform.h @@ -1,9 +1,9 @@ #ifndef I2CFORM_H #define I2CFORM_H -#include -#include #include +#include +#include struct I2cDeviceEntry; @@ -11,12 +11,11 @@ namespace Ui { class I2cForm; } -class I2cForm : public QWidget -{ +class I2cForm : public QWidget { Q_OBJECT public: - explicit I2cForm(QWidget *parent = nullptr); + explicit I2cForm(QWidget* parent = nullptr); ~I2cForm(); signals: @@ -24,7 +23,7 @@ class I2cForm : public QWidget void scanI2cBusRequest(); public slots: - void onI2cStatsReceived(quint32 bytesRead, quint32 bytesWritten, const QVector& deviceList); + void onI2cStatsReceived(quint32 bytesRead, quint32 bytesWritten, const QVector& deviceList); void onUiEnabledStateChange(bool connected); private slots: @@ -33,7 +32,7 @@ private slots: void on_scanBusPushButton_clicked(); private: - Ui::I2cForm *ui; + Ui::I2cForm* ui; }; #endif // I2CFORM_H diff --git a/source/gui/include/logplotswidget.h b/gui/include/logplotswidget.h similarity index 80% rename from source/gui/include/logplotswidget.h rename to gui/include/logplotswidget.h index 1fb1b509..05f87f8c 100644 --- a/source/gui/include/logplotswidget.h +++ b/gui/include/logplotswidget.h @@ -1,11 +1,11 @@ #ifndef LOGPLOTSWIDGET_H #define LOGPLOTSWIDGET_H -#include #include -#include #include +#include #include +#include namespace Ui { class LogPlotsWidget; @@ -15,12 +15,12 @@ struct LogInfoStruct; class LogBuffer { public: - LogBuffer(const QString& a_name) { name=a_name; } + LogBuffer(const QString& a_name) { name = a_name; } LogBuffer() = default; - ~LogBuffer() {} + ~LogBuffer() { } void clear() { buffer.clear(); } - void setName(const QString& a_name) { name=a_name; } - void setUnit(const QString& a_unit) { unit=a_unit; } + void setName(const QString& a_name) { name = a_name; } + void setUnit(const QString& a_unit) { unit = a_unit; } void push_back(const QPointF& p) { buffer.push_back(p); } QPointF& at(int i) { return buffer[i]; } const QPointF& operator()(int i) const { return buffer[i]; } @@ -28,18 +28,18 @@ class LogBuffer { QVector& data() { return buffer; } const QString& getName() const { return name; } const QString& getUnit() const { return unit; } + private: QVector buffer; - QString name=""; - QString unit=""; + QString name = ""; + QString unit = ""; }; -class LogPlotsWidget : public QWidget -{ +class LogPlotsWidget : public QWidget { Q_OBJECT public: - explicit LogPlotsWidget(QWidget *parent = 0); + explicit LogPlotsWidget(QWidget* parent = 0); ~LogPlotsWidget(); public slots: @@ -50,7 +50,7 @@ public slots: void onBiasCurrentCalculated(float ibias); void onGpioRatesReceived(quint8 whichrate, QVector rates); void onLogInfoReceived(const LogInfoStruct& lis); - + private slots: void updateLogTable(); @@ -60,7 +60,7 @@ private slots: void on_pointSizeSpinBox_valueChanged(int arg1); private: - Ui::LogPlotsWidget *ui; + Ui::LogPlotsWidget* ui; QMap fLogMap; QString fCurrentLog = ""; }; diff --git a/source/gui/include/mainwindow.h b/gui/include/mainwindow.h similarity index 80% rename from source/gui/include/mainwindow.h rename to gui/include/mainwindow.h index 6c42c6d7..4923061c 100644 --- a/source/gui/include/mainwindow.h +++ b/gui/include/mainwindow.h @@ -1,13 +1,12 @@ #ifndef MAINWINDOW_H #define MAINWINDOW_H +#include #include -#include #include -#include #include #include -//#include #include +#include // for sig handling: #include @@ -25,19 +24,18 @@ struct GnssMonHwStruct; struct GnssMonHw2Struct; struct LogInfoStruct; struct UbxTimeMarkStruct; - +enum class ADC_SAMPLING_MODE; enum class TCP_MSG_KEY : quint16; namespace Ui { - class MainWindow; +class MainWindow; } -class MainWindow : public QMainWindow -{ +class MainWindow : public QMainWindow { Q_OBJECT public: - explicit MainWindow(QWidget *parent = 0); + explicit MainWindow(QWidget* parent = 0); ~MainWindow(); signals: @@ -80,10 +78,10 @@ class MainWindow : public QMainWindow void adcModeReceived(quint8 mode); void logInfoReceived(const LogInfoStruct& lis); void mqttStatusChanged(bool connected); - void timeMarkReceived(const UbxTimeMarkStruct&); - void polaritySwitchReceived(bool pol1, bool pol2); - void gpioInhibitReceived(bool inhibit); - void mqttInhibitReceived(bool inhibit); + void timeMarkReceived(const UbxTimeMarkStruct&); + void polaritySwitchReceived(bool pol1, bool pol2); + void gpioInhibitReceived(bool inhibit); + void mqttInhibitReceived(bool inhibit); public slots: void receivedTcpMessage(TcpMessage tcpMessage); @@ -94,11 +92,11 @@ public slots: void makeConnection(QString ipAddress, quint16 port); void onTriggerSelectionChanged(GPIO_SIGNAL signal); void onHistogramCleared(QString histogramName); - void onAdcModeChanged(quint8 mode); - void onRateScanStart(uint8_t ch); - void gpioInhibit(bool inhibit); - void mqttInhibit(bool inhibit); - void onPolarityChanged(bool pol1, bool pol2); + void onAdcModeChanged(ADC_SAMPLING_MODE mode); + void onRateScanStart(uint8_t ch); + void gpioInhibit(bool inhibit); + void mqttInhibit(bool inhibit); + void onPolarityChanged(bool pol1, bool pol2); private slots: void resetAndHit(); @@ -112,16 +110,13 @@ private slots: void onIpButtonClicked(); void connected(); + void connection_error(int error_code, const QString message); void sendInputSwitch(uint8_t id); - void on_discr1Edit_editingFinished(); - void on_discr1Slider_sliderReleased(); - void on_discr1Slider_valueChanged(int value); - void on_discr1Slider_sliderPressed(); - void on_discr2Slider_sliderReleased(); - void on_discr2Slider_valueChanged(int value); - void on_discr2Slider_sliderPressed(); + + void on_discr1Save_clicked(); + void on_discr2Save_clicked(); + void on_biasPowerButton_clicked(); - void on_discr2Edit_editingFinished(); void on_biasVoltageSlider_sliderReleased(); void on_biasVoltageSlider_valueChanged(int value); void on_biasVoltageSlider_sliderPressed(); @@ -133,7 +128,7 @@ private slots: void on_saveDacButton_clicked(); private: - Ui::MainWindow *ui; + Ui::MainWindow* ui; void uiSetConnectedState(); void uiSetDisconnectedState(); float parseValue(QString text); @@ -152,21 +147,22 @@ private slots: float biasDacVoltage = 0.; bool biasON, uiValuesUpToDate = false; quint8 pcaPortMask = 0; - QVector sliderValues = QVector({0,0}); + std::array sliderValues { 0, 0 }; + bool sliderValuesDirty { true }; float maxThreshVoltage; - QErrorMessage errorM; - TcpConnection *tcpConnection = nullptr; - QStandardItemModel *addresses; - QList *addressColumn; + QErrorMessage errorM; + TcpConnection* tcpConnection = nullptr; + QStandardItemModel* addresses; + QList* addressColumn; bool saveSettings(QStandardItemModel* model); bool loadSettings(QStandardItemModel* model); - bool eventFilter(QObject *object, QEvent *event); - bool connectedToDemon = false; - bool mouseHold = false; + bool eventFilter(QObject* object, QEvent* event); + bool connectedToDemon = false; + bool mouseHold = false; bool automaticRatePoll = true; QTimer andTimer, xorTimer, ratePollTimer; - CalibForm *calib = nullptr; - CalibScanDialog *calibscandialog = nullptr; + CalibForm* calib = nullptr; + CalibScanDialog* calibscandialog = nullptr; double biasCalibOffset = 0.; double biasCalibSlope = 1.; double minBiasVoltage = 0.; diff --git a/source/gui/include/map.h b/gui/include/map.h similarity index 57% rename from source/gui/include/map.h rename to gui/include/map.h index c5cbbc69..2c15a2f2 100644 --- a/source/gui/include/map.h +++ b/gui/include/map.h @@ -2,7 +2,6 @@ #define MAP_H #include -//#include struct GeodeticPos; @@ -10,17 +9,16 @@ namespace Ui { class Map; } -class Map : public QWidget -{ +class Map : public QWidget { Q_OBJECT public: - explicit Map(QWidget *parent = nullptr); + explicit Map(QWidget* parent = nullptr); void onGeodeticPosReceived(GeodeticPos pos); ~Map(); private: - QObject *mapComponent = nullptr; - Ui::Map *mapUi; + QObject* mapComponent = nullptr; + Ui::Map* mapUi; }; #endif // MAP_H diff --git a/source/gui/include/parametermonitorform.h b/gui/include/parametermonitorform.h similarity index 69% rename from source/gui/include/parametermonitorform.h rename to gui/include/parametermonitorform.h index 6a4798f4..7ffcdb42 100644 --- a/source/gui/include/parametermonitorform.h +++ b/gui/include/parametermonitorform.h @@ -3,6 +3,7 @@ #include #include +#include struct CalibStruct; struct UbxTimeMarkStruct; @@ -11,31 +12,30 @@ namespace Ui { class ParameterMonitorForm; } -class ParameterMonitorForm : public QWidget -{ +class ParameterMonitorForm : public QWidget { Q_OBJECT public: - explicit ParameterMonitorForm(QWidget *parent = 0); + explicit ParameterMonitorForm(QWidget* parent = 0); ~ParameterMonitorForm(); signals: void setDacVoltage(uint8_t ch, float val); void biasVoltageCalculated(float vbias); void biasCurrentCalculated(float ibias); - void adcModeChanged(quint8 mode); + void adcModeChanged(ADC_SAMPLING_MODE mode); void gpioInhibitChanged(bool inhibitState); void mqttInhibitChanged(bool inhibitState); void biasEnableChanged(bool state); void preamp1EnableChanged(bool state); void preamp2EnableChanged(bool state); void polarityChanged(bool pol1, bool pol2); - void timingSelectionChanged(uint8_t sel); - void triggerSelectionChanged(GPIO_SIGNAL signal); - void gainSwitchChanged(bool state); + void timingSelectionChanged(uint8_t sel); + void triggerSelectionChanged(GPIO_SIGNAL signal); + void gainSwitchChanged(bool state); public slots: - void onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector &calibList); + void onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector& calibList); void onAdcSampleReceived(uint8_t channel, float value); void onDacReadbackReceived(uint8_t channel, float value); void onInputSwitchReceived(uint8_t index); @@ -49,9 +49,9 @@ public slots: void onTimeAccReceived(quint32 acc); void onFreqAccReceived(quint32 acc); void onIntCounterReceived(quint32 cnt); - void onTimeMarkReceived(const UbxTimeMarkStruct& tm); - void onPolaritySwitchReceived(bool pol1, bool pol2); - void onUiEnabledStateChange(bool connected); + void onTimeMarkReceived(const UbxTimeMarkStruct& tm); + void onPolaritySwitchReceived(bool pol1, bool pol2); + void onUiEnabledStateChange(bool connected); private slots: void on_dacSpinBox1_valueChanged(double arg1); @@ -63,18 +63,18 @@ private slots: void on_dacSlider3_valueChanged(int value); void on_dacSlider4_valueChanged(int value); void on_gpioInhibitCheckBox_clicked(bool checked); - void onPolarityCheckBoxClicked(bool checked); - void on_timingSelectionComboBox_currentIndexChanged(int index); - void on_adcTriggerSelectionComboBox_currentIndexChanged(int index); + void onPolarityCheckBoxClicked(bool checked); + void on_timingSelectionComboBox_currentIndexChanged(int index); + void on_adcTriggerSelectionComboBox_currentIndexChanged(int index); private: - Ui::ParameterMonitorForm *ui; + Ui::ParameterMonitorForm* ui; QVector fCalibList; - double fLastBiasVoltageLo=-999.; - double fLastBiasVoltageHi=-999.; + double fLastBiasVoltageLo = -999.; + double fLastBiasVoltageHi = -999.; - QString getCalibParameter(const QString &name); + QString getCalibParameter(const QString& name); bool currentCalibValid(); }; diff --git a/source/gui/include/plotcustom.h b/gui/include/plotcustom.h similarity index 69% rename from source/gui/include/plotcustom.h rename to gui/include/plotcustom.h index 30548a12..d5769180 100644 --- a/source/gui/include/plotcustom.h +++ b/gui/include/plotcustom.h @@ -1,19 +1,23 @@ #ifndef PLOTCUSTOM_H #define PLOTCUSTOM_H +#include #include -#include #include +#include #include -#include -//#include -//#include -//#include -class PlotCustom : public QwtPlot -{ +class PlotCustom : public QwtPlot { public: - PlotCustom(QWidget *parent = 0) : QwtPlot(parent){ initialize();} - PlotCustom(const QwtText &title_l, QWidget *parent = 0) : QwtPlot(title_l, parent){ initialize();} + PlotCustom(QWidget* parent = 0) + : QwtPlot(parent) + { + initialize(); + } + PlotCustom(const QwtText& title_l, QWidget* parent = 0) + : QwtPlot(title_l, parent) + { + initialize(); + } // for other plots: subclass "PlotCustom" and put all specific functions (like below) to the new class void plotXorSamples(QVector& xorSamples); @@ -28,7 +32,6 @@ public slots: void initialize(); QString xAxisPreset = "seconds"; void plotSamples(QVector& samples, QwtPlotCurve& curve); - int plotPreset = 0; QwtPlotGrid grid; QwtPlotCurve xorCurve; QwtPlotCurve andCurve; diff --git a/gui/include/scanform.h b/gui/include/scanform.h new file mode 100644 index 00000000..fb3def09 --- /dev/null +++ b/gui/include/scanform.h @@ -0,0 +1,74 @@ +#ifndef SCANFORM_H +#define SCANFORM_H + +#include +#include +#include +#include +#include +#include + +// list of possible scan parameters +const static QVector SP_NAMES = { "VOID", "THR1", "THR2", "BIAS", "DAC4" , "TIME" }; +// list of possible observables +const static QVector OP_NAMES = { "VOID", "UBXRATE" }; + +namespace Ui { +class ScanForm; +} + +class ScanForm : public QWidget { + Q_OBJECT + +public: + struct ScanPoint { + double value { 0. }; + double error { 0. }; + double temp { 0. }; + }; + + explicit ScanForm(QWidget* parent = 0); + ~ScanForm(); + +signals: + void setThresholdVoltage(uint8_t ch, float val); + void setBiasControlVoltage(float val); + void gpioInhibitChanged(bool inhibitState); + void mqttInhibitChanged(bool inhibitState); +public slots: + void onTimeMarkReceived(const UbxTimeMarkStruct& tm); + void onUiEnabledStateChange(bool connected); + void onDacReadbackReceived(uint8_t channel, float value); + +private slots: + void on_scanStartPushButton_clicked(); + void on_scanParComboBox_currentIndexChanged(int index); + void scanParIteration(); + void adjustScanPar(QString scanParName, double value); + void finishScan(); + void updateScanPlot(); + void on_plotDifferentialCheckBox_toggled(bool checked); + void exportData(); + +private: + Ui::ScanForm* ui; + bool active = false; + UbxTimeMarkStruct lastTM; + double minRange = 0.; + double maxRange = 0.; + double stepSize = 0.001; + quint8 scanPar = 0; + quint8 obsPar = 0; + double currentScanPar = 0.0; + uint64_t currentCounts; + double currentTimeInterval = 0.; + double maxMeasurementTimeInterval = 1.; + unsigned long maxMeasurementStatistics { 0 }; + bool waitForFirst = false; + + QMap scanData; + bool plotDifferential = false; + double fLastDacs[4] = { 0., 0., 0., 0. }; +}; + +#endif // SCANFORM_H diff --git a/source/gui/include/settings.h b/gui/include/settings.h similarity index 81% rename from source/gui/include/settings.h rename to gui/include/settings.h index ab73b5af..e01a4f42 100644 --- a/source/gui/include/settings.h +++ b/gui/include/settings.h @@ -4,29 +4,26 @@ #include #include #include -//#include #include -struct GnssSatellite; +class GnssSatellite; -class UbxMsgRateTableItem : public QTableWidgetItem -{ +class UbxMsgRateTableItem : public QTableWidgetItem { public: using QTableWidgetItem::QTableWidgetItem; - uint16_t key; - int rate; - QString name; + uint16_t key; + int rate; + QString name; }; namespace Ui { - class Settings; +class Settings; } -class Settings : public QDialog -{ - Q_OBJECT +class Settings : public QDialog { + Q_OBJECT public: - explicit Settings(QWidget *parent = nullptr); + explicit Settings(QWidget* parent = nullptr); signals: void sendSetUbxMsgRateChanges(QMap ubxMsgRateChanges); @@ -37,10 +34,9 @@ class Settings : public QDialog void setTP5Config(const UbxTimePulseStruct& tp); void sendUbxSaveCfg(); - public slots: void addUbxMsgRates(QMap ubxMsgRates); - void onItemChanged(QTableWidgetItem *item); + void onItemChanged(QTableWidgetItem* item); void onUiEnabledStateChange(bool connected); void onTxBufReceived(quint8 val); void onTxBufPeakReceived(quint8 val); @@ -51,12 +47,11 @@ public slots: void onConfigChanged(); private slots: - void onSettingsButtonBoxClicked(QAbstractButton *button); + void onSettingsButtonBoxClicked(QAbstractButton* button); void on_ubxResetPushButton_clicked(); void writeGnssConfig(); void writeTpConfig(); - void on_timeGridComboBox_currentIndexChanged(int index); void on_freqPeriodLineEdit_editingFinished(); @@ -76,7 +71,7 @@ private slots: void on_saveConfigPushButton_clicked(); private: - Ui::Settings *ui; + Ui::Settings* ui; QMap oldSettings; bool fGnssConfigChanged = false; bool fTpConfigChanged = false; diff --git a/source/gui/include/spiform.h b/gui/include/spiform.h similarity index 61% rename from source/gui/include/spiform.h rename to gui/include/spiform.h index ecab4c7b..8f04f395 100644 --- a/source/gui/include/spiform.h +++ b/gui/include/spiform.h @@ -7,16 +7,15 @@ namespace Ui { class SpiForm; } -class SpiForm : public QWidget -{ +class SpiForm : public QWidget { Q_OBJECT public: - explicit SpiForm(QWidget *parent = nullptr); + explicit SpiForm(QWidget* parent = nullptr); ~SpiForm(); private: - Ui::SpiForm *ui; + Ui::SpiForm* ui; }; #endif // SPIFORM_H diff --git a/source/gui/include/status.h b/gui/include/status.h similarity index 62% rename from source/gui/include/status.h rename to gui/include/status.h index 986a6820..ad8ea553 100644 --- a/source/gui/include/status.h +++ b/gui/include/status.h @@ -1,32 +1,31 @@ #ifndef STATUS_H #define STATUS_H -#include -#include +#include #include #include -#include #include +#include +#include #include namespace Ui { class Status; } -class Status : public QWidget -{ +class Status : public QWidget { Q_OBJECT public: - explicit Status(QWidget *parent = nullptr); + explicit Status(QWidget* parent = nullptr); ~Status(); signals: - void inputSwitchChanged(int id); - void biasSwitchChanged(bool state); - void gainSwitchChanged(bool state); - void preamp1SwitchChanged(bool state); - void preamp2SwitchChanged(bool state); + void inputSwitchChanged(int id); + void biasSwitchChanged(bool state); + void gainSwitchChanged(bool state); + void preamp1SwitchChanged(bool state); + void preamp2SwitchChanged(bool state); void resetRateClicked(); void triggerSelectionChanged(GPIO_SIGNAL signal); @@ -35,14 +34,14 @@ public slots: void onAdcSampleReceived(uint8_t channel, float value); void onUiEnabledStateChange(bool connected); void updatePulseHeightHistogram(); - void on_histoLogYCheckBox_clicked(); - void onInputSwitchReceived(uint8_t id); - void onBiasSwitchReceived(bool state); - void onGainSwitchReceived(bool state); - void onPreampSwitchReceived(uint8_t channel, bool state); - void onDacReadbackReceived(uint8_t channel, float value); + void on_histoLogYCheckBox_clicked(); + void onInputSwitchReceived(uint8_t id); + void onBiasSwitchReceived(bool state); + void onGainSwitchReceived(bool state); + void onPreampSwitchReceived(uint8_t channel, bool state); + void onDacReadbackReceived(uint8_t channel, float value); void onTemperatureReceived(float value); - void clearPulseHeightHisto(); + void clearPulseHeightHisto(); void clearRatePlot(); void onTriggerSelectionReceived(GPIO_SIGNAL signal); void onTimepulseReceived(); @@ -51,10 +50,10 @@ public slots: private slots: void setRateSecondsBuffered(const QString& bufferTime); - void on_triggerSelectionComboBox_currentIndexChanged(const QString &arg1); + void on_triggerSelectionComboBox_currentIndexChanged(const QString& arg1); private: - Ui::Status *statusUi; + Ui::Status* statusUi; QVector xorSamples; QVector andSamples; QButtonGroup* fInputSwitchButtonGroup; diff --git a/gui/qml/CustomMap.qml b/gui/qml/CustomMap.qml new file mode 100644 index 00000000..db09c299 --- /dev/null +++ b/gui/qml/CustomMap.qml @@ -0,0 +1,81 @@ +import QtQuick 2.2 +import QtLocation 5.7 +import QtQuick.Layouts 1.0 +import QtPositioning 5.0 +import QtQuick.Controls 2.0 +import "qrc:/qml/places/items" +//import "qrc:/qml/places/views" + +CustomMapForm { + id: page + Plugin { + id: plugin + name: "osm" // "mapboxgl", "esri", ... + } + function setCircle(lon,lat,hAcc) + { + map.onCoordsReceived(lon,lat,hAcc) + } + MapComponent{ + id: map + property double lastLon: 8.673828 + property double lastLat: 50.569212 + plugin: plugin + anchors.top: parent.top + width: parent.width + height: parent.height + zoomLevel: (map.maximumZoomLevel - map.minimumZoomLevel)/2 + function onCoordsReceived(lon,lat,hAcc) + { + lastLon = lon + lastLat = lat + circle.center.longitude = lon + circle.center.latitude = lat + circle.radius = hAcc + if (control.checked){ + map.center = QtPositioning.coordinate(lat,lon) + } + } + function jumpToLocation(){ + map.center = QtPositioning.coordinate(lastLat,lastLon) + } + + MapCircle { + id: circle + center: parent.center + radius: 0.0 + border.width: 2 + } + ToolBar{ + id: buttonBar + anchors.top: parent.top + height: 30 + RowLayout{ + Rectangle{ + height: 30 + width: 60 + Layout.alignment: Qt.AlignTop + color: "white" + ToolButton{ + id: centerButton + anchors.fill: parent + text: "center" + onClicked: map.jumpToLocation() + } + } + Rectangle{ + Layout.column: 1 + width: 90 + Layout.alignment: Qt.AlignTop + height: 30 + color:"white" + CheckBox{ + id: control + anchors.fill: parent + text: "follow" + } + } + } + } + } +} diff --git a/source/gui/qml/CustomMapForm.ui.qml b/gui/qml/CustomMapForm.ui.qml similarity index 100% rename from source/gui/qml/CustomMapForm.ui.qml rename to gui/qml/CustomMapForm.ui.qml diff --git a/source/gui/qml/mymap.qml b/gui/qml/mymap.qml similarity index 100% rename from source/gui/qml/mymap.qml rename to gui/qml/mymap.qml diff --git a/gui/qml/places/doc/images/places.png b/gui/qml/places/doc/images/places.png new file mode 100644 index 0000000000000000000000000000000000000000..c8ada27d9b6a612405a6563e54ad54f9d299f66c GIT binary patch literal 233430 zcmZ5{WmFu&5-#qp!3j>#Ai>?;2~G&^!CiyP;%>p+-Gc>ZaS5`x!{RP)bML$F$D4EJ z%+73|mg?%NufM8}R8^KiM6v|+ z3_fn^qO)Bp+tfysXs$#F~{~K=iC59LM|@^Y&dAOL{%zhkjuX`fd+ZFv5v%oVY+~3Soq*y`9e6gL~AZZGoV{Slg=+wNHG8b zoY-#Q zO?<%`L7CG&1U1_7isv8+;UBWd(4T~HHle>zrHKAwV89C_Od8wuUgGXZ%TF*bYJkU+ zlERXL0S!CZeJV!&bAMLC&gHCg!ms0t662$#Zj>T*CH!eS%JRnd^XJb%!&7N86FXo{ zE{tL3hXGO$(78{%h5)%j1Fi*M`4b9NaK*=>>$Xu+6?o!5n@B4`eE>Jz)S)X=6-hiP z!6jNG-(X5nEI2qZ$wYHs&`$YqYd$SbcyZ0oq0-;NBsL=N9IN*Px-EC#jq19j`3R06 zl7aumb37u3<$5c!^vQgpzPsw?Q=KDyu5N|~UD?-PTmY*gUA~4WLsQ{Isw73rgZYIz zW^Hm0oSL1@WurkNA%i8cWHW8j0G!Sip;VPT4-DmJM7uXsMggD5-ct zPJra%lW=RmtF7QS;wq7S4x>6(wjiwMJIGY*t6;&6fMVd-jl^r^$q%i9`ZUKyjNf?mpH4Wy1;vp*KnGFS z?`g?PHN?sl)f+x&~-*ES5@ z8bT5eJp1d%J?&xF6ryb6=>+T$zAg_q)d7-#o-D~uju97Xzo%B}kRvsO)dU;neFxvk z-3h4>M(Y&AIVF{r} zB5_BqkTfD5c2`a!(cqu4{V?T1f_X7!ku-wfWCf2fId{*bkxAj8B@Ixn;55WfzeCp7 z7n}z%55jQWYL4#&moj-YR_RcuSqzued5&A=mf3^X1n3tJZ^#Z_hid+gXT;hVAvLf8 z@2s<KS&GH80cONym=`Y~X&^GplEi`ncPJb(h@0FO_`50o$e&b}5k+w*E+H z+3yw(YfUIK#5?)5puvE5-{6@^kv$o<_OQ8q=0VNnt&$)97lgj9*A8@JZi1tfy{BeV zou?>on-6D-atC!wS%ckR&X;E)%zD$Ns7f;(-zU1amlV}_;I^6%;l7aZ{(heDM2#E? zcWVqTurubXF#~56`gI_WqRGjm@6q#pqrD1|%$E@~((!1cXPYT~f=-?9-*aPcT%C9U zp$0_5Y;glkBqn>JnM_}Dfga}_;f<-7*W;zqUMuiy--^$1b(-tGFNs$Gc6i+@9fs@U zX^_Y3_wilGJTWpYZnV;Lquu)+=7yyf7QT}FeIv)t-6wwy&Gvq>FY8VJwUx}c0As~7 z21`hYJoAaeoT&&E!NDytlAe4wHQ=71>wudy4W-WU87uFpPnj9cj75&BjAPFl4<^mH z?aNy=#nzn1`JaTuT|^EpI`^w_eUSnGgZGR3v=SZNM`GiLe$3_Xksn|cbQ0?rmHFb6 zO$ikgCmNHdhh~O?F$5|4n75ah*bV9G6t(FRtMvV-?%%wbPL@c4^@)+jHDtW1Sn(4$ z8!=U$K?k^4n?8ti*TU}^D(-e`+>XBbo}^ft_f@EeRvA2?xC+~kr`Iw%d|m<~-Hs&g zP{Em{@!3qfaI8#HakJxZsl7hdDbmgI>%Q4w&5o zh#E}&5%D5PV^&A@4gWY~Ca6mIA_TDp08%k5O56uBmmd*{5hw8ZR})yh^zPuDK6@X& z`}u{J?Sx^SU6yUH(3>DwS|Z?ef@HZ?D?=o2ODy=A#mRSk6|`RO)GUvTR7guYe56Yl zcpxR^4Dm7*H9b~2{gyAo?}M=-xtAHg>Q6%ner-EW2_jr)-nUYGN(TC?7u3{7@tV)%cnsFj%Uc6-KJHh^xL9yLZ991my8vB6>%@BR z-%(PfPGciEr>l)g;D8%PufyHuuFZnzW!H%hNEvUvmWqlKGZJj5dg_{XQZflS$(rzj2)9)asAvC^w(;zokYe z39T|j;h;AzHnJYFOsl!w4g@8_1T#>LqGaZpd^@VIGU^OcvW(z;8~r_{JIwcHgV5ri znB^D{lG&1d`!ySQSY0#yTo4Qa)70R@oA6QJ9j+JR#$M)nnGJ*i& z#GwrGnqxyf$4|9vzH|+M448GJr5CIZ%Rhv89P~mJ17nl`jKqCd&#+kWSnyC;<)feI zaGEcXkD((5N*gaN|TVP`D@o%%=4>lyR%QdqI=We2*{KTz$}uBN_bj1S$dN zTGof9Kl-F9WurEE=&agM#_<#K1mds5`A!;^obICO+rcgr`zLXDD-Gs^eVGfW54jL` zER%V}0GLV&>2P50IrPjfZJ}I{hieIq8p5fMaa%3qz`+e7YB0QSeX=M1Res)C5_2H`;wa!f)qbyu@Z14O^`y5z4jSq z3A)wZL{=!963+}?B*W767GbuX6p6G-u^5s@G1=KVf|F~AJ&v)d@R_`g zD8XjJ(Jz;pu%&e&e;O8enU)|EsMdUbs~gMTEFUV0m0*T1mW(AC^c(X678B%z1rw)9 z=c4mpNUK*zf*wNee_h!FM=YMysaCtQjBWrNxc8Nmlgyp!&Yr%V&beT&Vfu&2t$sUj zb*SJ-Crsng+$aZc2yt#S7T5ekQq)Rdx&D7Y(y7IP2BeVgLOL9_9Q+UM^T{K#94?EH z;Ns%C%wuCwDvXLf8GDjJUU6M`<9G31!OwXAdC`f4=l|CX11-Vfzp4t83&nrgg8Vrx z-$uV?L}gaq2%Pf* z1m573g|9;moYv_dSC;eRG8UD6XusU?DkWN^ zBSXcWqYT^~r_%lE{q{ml?=l?DM#a~dey}BnGb>KwG$C!|H35Tp9(>>>JNu%CpX@(^ zSo2Jp!t=)2`Z7$koAcTI<+#*N14E0UU?kC{_WS6^3KobM+7(o&m9fldUq`g0xu9Y+%?VVbY9|j9WcdxgE_Ai z87n4y!M~r!oY(KXHWUn)6SZRrMbEx`!n|(3@5-&L^+YCN^WvuHuub0QrA_w^R55zSSe$4Py3sBFs7pkKa0W0pe=fLVJxo_}Jun z6TtR0E^pFgWfyb${$m%#?|sNPTo&2Gt8ZQop6>)xuk&ZV*46!mc>w~B%iGRk%P3K; z@92(iO9)HrH>Pjbo_R8F*9aR=mhWSipa)K6gy3!9GV?1>-t&}A47>rB^^k6M!Yii3 zTQ3jp%Nr`M>11Tp2;*es^zDn|^DvJKa3St0mBKGMdcN+3X~T_;#K8|6^w=sw$p*!{ zHs`Kzg0alq z&^Ir4zrF{t{XjSF2Fs_8xk*#3233>c`xihKnuI7O>fim`-tGt&pdnEAq-Ga1k#_k; z!uk=NlA!IOxfl2eUG(?*m5{%xKel80ogGS|-v)d>5(L>k6civV|N-c zR`U7QVjjy@!#Kd+CED|}>-CF!whQ`F4I5>owen*jkMq%H(;*zK|I5Ov?#*A4wx=Sl z#ANeH+l@hmV-M%&J8MpTfw-^T7AD(hqBgML=i0bS=N&@dEx)B7k9@Z67jf^otGUik z0`D;Kz^|AM4%Eoi}Dn^k%Epil9h>v|LCz$TBLfH5B}>^tev@!Cx_`*m zr>Iq8X0TktRE#DYc=y~CCtSkF37Y!(0^ac7wrH*A%~Gp`SxQ+c_ZfCEMk+=4#H=rL zq%;4};ZQ4tm%n|-L5$pC>y42LaAgvyHX7mc0FAv4cO{c(H$R8Nme57*rZNjt*3EuT zjg7E_y`WzfvAA3XzB8uz7h5xWb19~bS3u*5vZLT(s2AZdvF`rGG#F_P6nav4yY61P zths02Nd}7aK0gvJGewMYm0P$KL{W7tW56}b(VcyqB6GMagjtaqID`otY53|N*h}24Zou_f2LDFJ2^@YC zDl9@kVF+}cFgIwq(OUDqXRT-z9Jx$;rybv42E#lC2`+#LoHAokqZAb%CzIHD(>I$c z-=o>OEYk1#y6!!}Y=Xw~TaBJ)OjA3!0o}1Ved8UuAP~NTrQ2^*<{#|Oa7d#t@a8ey zg~E6=l)st+lD&Tz=uln?vi5Enx4j_59RpS$HnZLmG4ou>^E|!WmH$yTxqhS#vTRAKpsZ=rjCvBE-*y}yz{a@~3dUW$+q*cGtp3>J zUjjnG!e=nTJ05@w@|wm89GQB-R6!6B(djlIQ4y*VGc0VGn-Af|V$4_5N>~dj?;e2-jM0x>!9Ev+NH+nt~ zJMO0Eb^TPB5=@G9e1)cVe5V2P*S3GG9%&#np1RaOH(#}8+ews~DNO|gz*2ZEu^T@p zr8zBB8jZ(#ux>q8X4PN?^+$t%la8a#Cjv(OE2TN3UTJTP6z%p)Rgr&wiYcOh6MR+L zcz;shJDAttJ%}P{XSpSQdj!{7NS^xpfAqkv^}+W&zh89T|6BPmNKO8iuXZ1Opw)Sj z&(ishmSVH#5ve(TM=Idj{sEPR_@;4zb#CNcY@!%6D&}_Xp zU}(`r_^^f<^Xc^9+Uzc?`vvhag0j{q~TZ4Bti) z=8vU9DZyWtH*pVX@17x?Z2aN#2@X1t%@C(D$Z7hsOvKoL?-tpT%Ro_dEt>Pb7RC1K z*VsWJTg3@5RDCq{e-Xi#!GFviK>d5re<4KzYG{9gg9OCwD=NY{cNKa-o)a^2%+vot z9*p&(!-Io^q{V|tA^-OS{6E0ql8l4u`mdy#{QoNn*~I(@bF}=I6#RcJ95GD$+(Txl z#a{DM%D`IDKSZ)pG-s{My9GzUX5?Fx<*aj*j_D04APDvXnl4mmjW}n2fz-A?vf05J zC-TM%`RjQd_fVO@wOHL`GLyTW7t$+ICuM;%E^_||lP9;)4X0r;-}_FG`7nU2aYN*O z&1I#@8rOEQ%8M@3Yvkzo=NGgc_Aj)M9?}tOX+e9V+yKY~9v+58gk{pR)&kyN|J_x( zjbZm)2SPMSqY@j75^{FrkY)twm+MUt!G2($@&y|xG)zpF^Y#PhF~(BW%7x_ybJQ#z zM~BzvZm=I)z`aL6>$ijrNO8zVqv`sCY!{4SQWr&_vlE^SL|Bbs4&JwyaRFVlQ(0f^ zx6vIv2daQ+*&iUJZ>=R$-~6lZ8#QS6^Sx{<4Mbe3b8@xkZ99Neebc!TB?Fg9?u0$Gfz4NN zfJmiwHO%Ie0N4y7AF`9PTRnyao95c5=hj~&z55CjuhNKHNqk3R9+zWtP4GOt5HXby z=G+{o>N`M-xBfXXet*i{emwW+&1&u1V-aPTU4qo!waUT8#RWFagvhOgEeH%k%;8P> z`Z8n#1La5$df#nD{$e=1H!KTp)r9U6L z{%dP2d#O*cLx0Q{gO~TMNxQIyeBcigtGSZN)5Dcx`?F8$^>~iPvNOPR(eO_RD&Qky z6Ze2m;;Qg1nN2Bac(X00)?5hfLBmn8Es@&l7=l~w!)R;UYkp})S^LNee)jFQl7Xi$ zouW7n*Yb5Vh4X56Ttn?~p&3D=!(8P`o%&I)5M)t=$1-%=Jmo-Z*BY(2p8Qi!$S{*~ z1U$%_9o8kj$T0x2$1-;by&jOGca-NT%Nk#|hDU3>ge0i&E|;G@6HwoFZ|&s0Vni-z zdoHRcW4hiR(Hio6davxsjc=d3E{{z=SFAp4rS*St?f+i zQneW85guLwlW!@p>4kAsehcLAM9A9s!5ys*t$_*Z5AZt)k1_DTFFjOU^=2~e7~T)9 zZ38T^C~XpWaFQc!0vrD`h){;^Od^c6o3lF!jpd}#-C($nw8Za=rSr(~3yJ zGKEvee{8f`1aUEYI5W>Lg^ro7)&EMhWV=wmI|6<%CwEY?A5 zA-wk;IZqG=YnfKwEoUz*kg`a&c&YAaGOe*9k9D9{jhU~GtI53EIiVtV&X8t z-Z*j;;L1{Klq`C4@3d6hl0!5Q4s+M z1l&;j_t@ZCvdL`{+_MwJ)VVsf-qDnUedC{{2`^vVm}WwuToysBKK^bz0_wJ2ZoINJm9q>GOO!D!+$bzwlYHD4*Nl?fHP6 z1}5gBU!)7hp)&~>aLU95ld}7pLwWr{9T3MKtFxJm3w!?fGVED_){e`%TM;{+5R?Iu zHfYF=R(auvXcpZ~4B&H9qPc_;KA~)lKT&|y#vgm*M?!y1Ow~CBoz^2Q=1C7n6;t4V zo&Wq!6=bLfFJ~NghZg?at~dunFpyEo9+i9r`yL29{zer3U1Qj}+-ys@WE>#G^tHy0 z<#waPjmgy1wEBwVi`};$KjKendvkeuA1CdW>$ZOQhI)OpTWw*vB6)|n!TrCswK)N? zZ${@`M+%z8u4HT?Jw*5WSIa!Yf4UWF_HGaMF_fFS=-baUS}BchEm)0kz{~i!*PZ>P zBCkiePQ%T5v26aA(QAJ9>ty3JNph^6ryK}~h>zQZy~_`r)pULyg)_ApfB5UJ@&Y|aVUl+{%-m@8uO0f7__=xB3X&SjH z-t?8CJL_=THUqb|D*+dC$g2pyYxk*@JSr1XPp&!X820<)K^`R7=KD04mwWp*$pe~z zd;ncPGy;Wv`p%AcoM~EIAY<{jwALFtqq5Jm0HP~sSLyUY+Rv?T5zGDumiBcAIrG0N zDLirJJ)%KL(cstkU+~jDsI3e#pIE~dEyfHaFJ*`Ha9gb=;p30H{(n*9s13D`%;_yzT ze-N%wmIen64QFHL@u1{D{qYku*-F+qQlh98Z$1srGL)UqXbzdDSGllx#z+8K12G2ic}eW_Xfw!&cn_H3?@Y`nhLlhQBe$|%jld9c61_=UN(0^ z$KEhO$!2CnzvnfH8ujS%9}I*O(sB=h))JcaM`cJ;;TAbv5Ci}TJ9Kzs3^u_Xx_vIB!QamL@K}Npraq3!D^z8PQ&kdM6!TX4ieJhx2oIH` z6ekW{{K%A~>WkV#mM`Xb9av~--f=NYg{{m4 zWU`l~&=J|b+|^|_GQOeW+W=k4Q|J@SGR#V*)yn)p0~JftNkqQD0k^ZM6cm@qcql82 z7^Gmz3RzUc+l)^chhfUXmUSM+uu^%pWqd7=n9DWCcBUQ`(=o%XiTP&V`Maj=;uz;7;`1dqElmVfyz*^hqmj>veNWX~0n1nI+ zDhVt&j!=`t3>ct7-qf!aJh9{pL&8qAfhxT6R5}KgSan8#29t_fZAv|fn=fdfxmwl< z;YSsMMX{{84caP40)7f)vNc-*3+VV;7*j4(ixE2S6*<0q2?cwZH4*^~xkIXmlP9LW z!)_u9i-!xenJmhFD6biAEj(f*zO`B6Xee+EIQ(mca_xP&J)#!PAm?f1kw2eAbliMS z;GXmw>>G|4D7ZfJ?Em}owp=!2Pu;E8oHt;5xG?8Fq>;JtcJo%EUsjDpiS&z8?r2+c z_pKgME(uDr{eqkY3Qgh>pE+r#7#17@a`#EZa5GEdk>G5MvM`d>`Wz%s>8i#og;KV} zVz)|_e-e=xd;s(#KMjk_oPK@-B+~q(j3@gbmWU5YZn3d0DE&Btyvm{0+|t>qLWelWr)ee@`BCOjF8BCFT+_WWmk#qHGmW>%P%5nZWE*Dm3WpC?)i5u z%yhxYu+uH5U^>Z~xOpR09~Xqm5@BN1Zs@EsHi9o;n!2X+er_SnyU z7IY^Tw2wiebCQ=`u$b=|+o+bvZuI_w-n0PoOPBYW5#TenwUUZ@tyZp@hjcG#wyMDV zSQ4-HPfhn4Rh|j?r5Ut9T^1AV=rZISO?S$!JU&Xz9?*Jl*bgqfPoYbGl#Z&c2V=H>7m%3wajIk=(Q!5%iF80-R0vIuc02)T$QrvC>YZ=vF z@Lb$Y4vKSPI6p_i``oImJ%*s`u_O~*9pbNcm%FY9P=b+y*=zG>6!EkM>Yo()Dk_Ef z1}wf849;~9I~j&6eo+!mE0~SwnemBC1$!k3dEnXfA6g5+jx_wOmxy*Yy}7!*$8i@* zIXb?!qd&aThlghQngM?1owAFzs%}eY-j;@{s=n@Bf4-Ee%b5`n#l8P(^A&-o9EDaW3<3ZGI2uXbhmnn`X)e3XqGN3mGgP;9K;9oa8l*gm;{PG?=m4XQ1gNa~-^3;e(<$~@)e^{OI%6@O+ zZOT4Rp&E6?K&q~VtevZQ2Gk??16!fiLI&hDB-=*Z0;r>q@DE(e-Igez`;mjjB6Wm? zF9`&+M72LF#nf=kt_Iowp$mtO4>{8s)sYh!1%FxVatuC&6RRap$KdsVZ`bQl3YOit z@Zb=uIDwd05v-lsYa_(bvC^;aeP?dwyZEyPCi~h%_K}(s&iV3J0a~?cwW<2O zYKQ0PhSJ(ieA3}HPnw_TkYFU>bEHG??e!7YNTX6IQ&_$gxjf`56!R)~>-F0zs1Yj% zdQiZ-N~qz|aC)h)KnpJQIgqj=WqQ*>G8dEx5pSp)bJj>@B!9g^;UL3{Vb$3qwoi8F zTmK;)AF5cAg)CA|_)pl4tpM{a9qq4M{5mH@{mA{Hzea@{zBO8c@x-toJSKhqN%~?? zo~TMmY2jxJYI%;tD%D)#vrdiSpQILU067F9YNWF_Xvqig6Q@muRiNALp)Q}Ic^nIo!(J9O2E77s#yj<7 zA4)U0eZ(d>%5>oKLys#dMHwf;q zLoFQ`3}T3SnCq!kHj!SJWe_e||MvbSCoPSj(^U5RTnO5&Q<*jCH^fw{-KEnSfD67|A8$l)J_JBBI?@n)vTQP(Ii*oaYNdb` z^3nZO@<&;waxpLYqb^q9&Ug`L#)U!Z&)L3U2g`2H&mstRJWAp&KdRcPR>!*&*wwjg z_6qy&1t|zfUq2#MM}%v-LoL-mKcT~lrXT$TAZ1z1j3*)C zMG&{^F4(4 zRc9)(ijwJX_JgKehJ7)=JFKo&0)BI4a}xWk;X0z5zL^yz>2|8TmgcB*%06MQU8gn9 z7)?}(n7#-%CxIY}l#*-L6cAybX+E(kL=97H`ikwIdR`2wfL-I)L25lozN~Jn-iZ(d z8Za-)6>IFeFuDt!#cP{Ezzz6f)m;!Mm6F)Ffh&ovrS!`RS@d^3vCi$M0-8&m_V-ZV zOp9;2bir6ya9j8I)XawrV&^ooGJ``V?Nk*6!cEN`(KHA`L+yH*ki<{BN&vxUpH*vu z9=YD013mL7Ne)~-{pvE}8dFp4XquSau5fv!#7voL3l45waXhJ178cd2E|v>c?wsk6*tIJ8=81b#D9GnK#;}{4o>w<>^*K zp<%Y+$Hy1LYU$YD_j2Zl9c{uPi-O@4a0z1QHKwhhlgJg_>%U?AR^jdh|XUGFAxi)(+OPKElX6l|#ke1$7b7WkzTgFFU#h!W1Wiy?%i6`Av~wZoU4|U@kDSN3>PgGUw+&G|sj)qd z3f}k0*yaUc%q0~hAboLvT0+LcqC?J)*3ofGru7j1W1}=0qG1PB2m$wZu}KvOSjgi` zIC;+bIn`f=1o8S%)Hy>gWL))AHKlYv>;zohcGX?zmJXr|=&+;`q^lLZoRht)Nv)CE z020!SH-@$L0&AU*AA26xDK27b-!Vb2=N?Xm9!A24cfFXEqMf;c;qtUp6ISF~F6kXYbLDN)Lyj4G0^R%q0w z9JJ9Etl?efq{Q{h9+WMOk+H}_R?>{CSr1amggJ=1)qEc7{D`AT!)hZ4$cLxs&}z03wM9Cn!Zk;d_=nH(Ma+jH`| z@`}mvQ_@Cd1bWpu8Bs`mOlhZ6~0+ zZVt90n&X_;NprWKtH&Uip^}UvjuyRuM@;^AqPXr9d+R}=lDGj>$E%5uGpm-unt3HHN4UN z+@Uu;y`JN~d|uPRk|=j_7zS9dV%OsOJRd>&!R7-lA74wSWlm7r&ccw#`qat%7Y6zfryX+toU4Z9aMn-_wmMc1$Ktzhh zvN`&lOzAkF;qKLAe@6TH#X3K1ksu(T;~}``BM!tBso$F%;a51;jrXB;4gq) zW_(H0x#wsy1UDO}_M9~f0^wH14NT6 zeNO)x+CBb7KvYleWJV634%Wa$*ejn&#Xo-DU}h@%dJ}r^7nOiWS4|*{ray>wT8%4I z&&mf5$FS-EiXj7LT$*E~p?}^Cd&zop`Bh5&WdN93P<`iR-qIK7eIb|fLNp$m7wrJZ zaK*8zjZ5*$6`@XExVK7A0krEu7T0Xi5IQ)=TCn#94ss!L|4))Mh)qg51NM0 z0_vkq__L`EXFb-{ZW?}dI_bc5{EgRXU7WwMpsKN8Ti3J*MtJe z!{_dvZ!$Jxq^#x>Y_>!Jx{X?J?l$D4g(x({Bur_L=8+Me`#1o7kvW|VEsY576_d3y z=d66+MH#-!h^(TaDkho*{|56a7}qE;6Dt>zAT-;gT#lj?@XS>7>N_Ns@b)qv)v1ec zp(+>*(_M7K$7bi+L%4=vd|D*&CHBF)2C-@Luph)g7wh>?W+(#*RGBkE#J9vM!rWo@ z`ZOAH0A0Qai2}#8aBzD{ZM)^7IB)zU>x9`73DAX61yDfWm>`{y z|5R2mG(}I}kL)g$lQv%Hm%O4p_hBxHh)Za6r+-mcZ=Fai-hwEN)41DH8vZZlFPlg- z^bmsc!J<*sk8&mKiu^pX969tRG}v$-okJ-n&P^Z!Qp1I~|HcA@37dqSS<4Cjsd&z! z)5qfdsuVi?lhZ<+!KE<`niwwc3Xwj03&ciZI_Xb@dhkM3`bwABka*1V0CGZpzF)&tG@XZvGPXFH$x`{oP0Uh-~_2Df`wvGzQi9u*NrzEC({V_`_vN7<-9 zzeNF*NXwnA5v&;z;s;Y=b7&kHu-IR?RkqjG>^u}iDyg6Av26DkAso%mzfM5iuQEQ$ zs7Nw`uLgM;YNXeZ^5`yFObOI#S{Mv8hJXGjB(P%gP~lW`pH043B2#CNk76c_DVNe9 z!4O-7$~$Gh#u~oz@CO&p4s9W-a+s$A%o6ZJZHlD_sayJ%W%u&>6rC`3yQh31lm>x` zzwc!~KsxKY^f9&O$55dHAFS(inYl&U z8U6Q$vyb_*0WBxUTn3>DQYH;mGxdzVKuH1tR0%px-jfZl_Z%-_ft3}#nPNP*+P~b0 za%>gFquN|R7p0=`*rXoCIH*NSlY;*i5D4a`YX=#Wi`UpoA`56#lt`o~IQ2zc<~hnufTEmMqzIP_U|rn&a*pSd}045LC49GG;o2SnIb zAVP*r4h883$l9|T{|OqLKtUc8qbB{gS7Vu&y*L&JgbM<-fG<^Iq!_&UR7CD!fjBsM#Mz>*F z*f{wX1V&$dzv@Zp%5how zRW|o#0~)>;_b4#sR&9bidcj%=k}?E>b~ORN)5LTsBn>+Emt2lMe{mg?%-p(PpmU!e0o}si(X- zVhfJQ?vJt{{N(8IX}h4FcOavW2>g?=WPxI>a@Eq zNyZ7>Y3m@VIa=KPada6NWa`k|>`qF={&n3?__%U7qX&)5M5A>ljD)&P)H}mjl5UFY zEoD~*K1QpE#n%I#WLNPwS>Q!k^ZLJ6I*?TjImAV5@i3iCf)h<>K8=H{IA>;8ATNA0 zGhsWQOH-Mp0%rN?LM>!rlmuY|bZ)?TQ+Q!cRX<3YT>T@ST-$UYG^f4yR;bPy5PmwE zIwwXhG3AKnzA=)xT^fEb z$#$+FjaT-JQPI|I&@ufLzk9S!P(kYVDg>0m8Up-LEVV4o%jP;8>F);zN!W<_^oY(R z>wHnjE*&{m-u)AIHnEZ+il;9T?=Rlx3!=B&dnC z7HPYKgSZ&hhL)-3rGj~{DR638I0gU%Tf3q&uVFQksyA4s^fS4hNRF~i2#D|@cV zU?`vS4+#RRu>e#YJM<6vdo`HC?~Uf&wDtm}yRiWc5GB+M4#RyVeQ-FC1w86Zy-rV( zEk#SvO`kXM*6L)+@SqXj@^|J!W~_4r70VLt;~Jlbjh#0R9lxc7K#LZADTbOmze+)K z(ip+MPF>Hzmd@>>O}D>w`eY7`CM3;0HKH7udKM*UzvA~){haQ)>AOy7lm<#;&DqC~FGtK4CjOg|iy?cya+Zh|#nSec-wQ&jXiDhe{q9bg5|!Ir zq|s4VygGB-qs#L6@wq=+4&R6A_Ejk+$d*939|$Sx^qm6Is~nP3AHr+~8aX-v_WnBm z?cfvM5BySPlCc=Uzh!1{8jY$a^93ZGxMWhbyTf!@TAaf@3QV;1D)Cl7bLG{K)(x=i z&NW_D0|&47^9Va~{NvI(c1ezhJ~}x;Flae>l#BRMJtWrXK{!ghk!|+!I=i+=+E1}q z5l&Kam$c#3+D;~Q3hdCpm6oZmtM>k2nZu}Bo3g(**K({?<&DphK$8Rv{>{uY2?>2Q z4(4k!elIF)?1Mhl3W(+PqB@e|3qw#pU9nB#E?C`pCNE&vYCZs-if)EuYWa-GieZ%| zEw&|O(ahWKEk@)MY0WCOFC(iZmVTvh&;7>5l3<@8YG3#J5BEP z?jjmG2s7&f9I^)aKoZF`zQC-#F(h1CrA}UcooUXmjR-v|&0I5MKojk#gc_bNlVIoQt_-UW-v4W?r|GAli#{8d>qx8fa7I zpUhA4tDLbWa;^ck*KDn_$I#W8R3?eF`LtoxlAnpAvW(y*j)4sdhod9;?n$ZUMWy{@ ze-1Lbr)=hb7z#9)X7DAW&=+@&XvIQk4%MW4^_s;xVssquHZx%x9LYrdc}WiE^kt<8 zo8m}a0=a%!)1t=o1@$F^UI5v-f9@3K?cU-jK7m_v?f{tbqZ~)9cTR_HoFejc^gSrU zkycV({yLla{F2hk;RD9<(X;eW*eZIGyc4OG%9M}g9eeg

{6XTt|rus=F80I_+zR zQrIo7!2agNDqR|_95Ro+d)4B&Q`I8%&hw0bw+t-{3jHPBj7A2aPyuugiS{H;Yc#s{ zsruc;g#-14)BZFS^I4(?Z~kIAeB=P-Y;RG*|Gk8hcMH`TN3D*`hU}wsHK#k2zjKGP zsi7}If;J24yBCb4Z#V94^J^T^;R~Uh*0hvhNB|~Zb)j;ue)U@CBSR%z59qV;(1hmvjU+A;q)_7QSwr$D`bm#!!t(p>=Nr`ryJt~)5sH)c3`f|_oao$)SD2G#jz2fT z8A=8Gzwhpk7iPPXUZNY;qMGWDxtSZ~=|m=EZQO=UpYSh?g2`AfbDx=`=5qd=He6*l zh*92bL4d#<l`SF(+#9*~<`rY`H9;*EnhJ{sTp z+)Cc`vr9(P-!Jwf#wPshyACwWD0R)Jf~(8)Y=L7L5s6&GLm%a4vP7Dk#XQ=0f+-ar^2X4=6*Y`Rg@Ju^Zi$<( zXo@5KT-=W`A_?n(=IXbQRO;<#@)bMc;k3)2E8P;McdiA`!L@H|+OIW~b`6vypi8(h z^c1aem$C}!YHd?s4-Vh@0DBC;XGE+`$`2CRtS97)@2{8m!nq`U*E|xLnc;SGvaN$u zW2(UjXszn;ZYEtJP*S;Tw$x85F@A!6$0&n!mkYpz zBo4%?57Rw58lEd|&x=kBDX_8fj#Bjh02FDX7^&}Pb|1T$_NNP`{8jch+ZV69>gf(> z-`jWHJl@uJArE0bLQ1e6Fk-#Q)bJ9_oHmXKvaFDQYC1r58VzJ`5q@Ekx^Z>y>l~6y zV4rQ2WHu?Pn>fzKn7D?=qxD@TM#rpIL2Wyh%Vv!vwbcoi%Kn(m;6jF~h9^gJKn!=i z{-YIl9dZzvxH`w0z*1SL?79h(+fe0w6Tv(dK*H^f%KJ^s!`X=xr9k_JxB|FrhQ8z` zTdWaLz;8QT@MzY2GMJC^NasRuGgkegEEU0`At>rBRhbeIF_F7GCOPk53bC1gsE8w3HPKDV9;}0 zhV+SS?X%l3S_@4VOUe2JuUqyXd#gV!N!qZbnB+YLu`7F>3mY-7g=(B287Vwc7eu$;*^|p}B{16D7rz@pvg z9R^@^v`|KuTXV&+25PnL@;}%1DDY6Bd_8nTNGB6QJIiE?E640%vTH|V?-OR`tArB7 zdF(_@9^qvmnISe^N*>|xOk-EtMxj<`1Vk<(pnSmKj~inty`c&;s2z7BgC=P z6TS;wYa4}Y>XHl&H)d>bd`OMl{j1cEbajOWVv__9fJPO~*Rrz2qC>Hlt2@s91p-Z7 zW`nm@By*6G5}@%8NaZLAXrNZxhqz5fvs^&eZhtu9-cdD6eb<9X%y7ENM2i3#!g=>F zC1?{Y)8`hv!~spz6E@4Lfg0BYgE$b5Aa(X^C)=F4qsyV}c3VJ2MQFgkcZch?IFLMC zuj%b9gnonPu^y3zM%uA|yYdy)okQX$tkX$IB7%NbI!FOFH1;sah!1A;=s4Vs z4<&L65#&le4Y>vEhKq(+F8L_Vo>y#AVge~sx3R+LSCn1BQ`dercBgLkx~jUSlo zN@?_(n}?v%f|FDI`g;7XGj6>3r!hIVcRk*Rqj}hB{j~EnmBv_rD86;o*xzql01&=n z>gW}kGiuf9OkdrKTz9_`;Z3MQnf094Tfc(CTfZP>q|q&5a}Rb}c1)Fq1&4M88`+*U zhYanzX8*%XzLyijJu_Ner>Q89-eKN%1xcaQ4$^8}u4kV;H+~Z*>~b@DZCHJb){4+OLp^!B}7&ZC|ZiMtLS9pLYdE7*^PHywa)Naq3?;Y=9bcmaDB98zgXf zFCnZ1P*npmOHo-=5gyW6O-+JobUv)vNHpS|nX~hU>m-&%Y@>`HyB7-A$69g&^{!G% z58B7jyq^+W2A6E-A#T2XZpQt_?Y3@~8Htd0QctbN75GSqLLUHXpc$7AC#{^!$iT8= z>PVK0abG|vK0h%k+Q&(p&%SrXD>v2a+efsFJy(P|_lE*q7nKqoR|E`3rtCkSn!d!C z^{o4y_eA6d6{|M@K$XQx97`O&Xey1<@>I$*D z8*%eaS$iw8o74X&zAU!%ZXgI+kAtQndDw!Kgc6p2%={a=M3*D&ag~*=pBcz2nQqlh z+bdihD9GBUGexI>oFV-1^!C4y0DJ`Dh+r!1yxYM9hm*u9j%i(AUVH#)^9;X>D!4k^ zbjjApS#-g)<5YL(_>#fVk>Z>PZ*(UBn?XBmf}*|9-`(33vG4z-4*q?vBI@M)xT1{B z6GWJFS#inV`ZCbb!z&t(@%Cl|hz9@c%uHQ%)}O*FQv{=XE=!qCV1OyTOGcBZD#?F5GomHRQyXI7|FRz?rjwD3l&xBi0rusgd`BhZz5k zIS;SCWDXr*jhxYlHM1CEm&)7>q>9poSCvEB`W3QWfV&At`n_c5V>looR8u?hRHB3o zbnqPopG>FF;tb-DD}hP>ZJH;QdsJiz{9!4)<5TOi7P(A##gzBySRNkh!P;=iI1$}3 zSHtB+$>6Pgjl3kdrhjo%cICU;$FH=;*l_)BDv`Z$_?yIqEG@4qLy76)PMYIz*QKO( zq2M7czH7FWCHOYWFHMvlSs2q<;BAC|^uh9hHLF5O0K#f`Sd9%QatR{*#w%tKfEc&3>AGGWwXAPSXCvq{s&|D~g=QMN)moR~YC@p^mg{g4bo0$O{VC^~!{zvXVH} zi8XzNE-{Y=t^0NC^QQjc7EWgpr0S-dadOm+5q$2nW|jkr8Z0-JM)p}V_~Yk3o^)TX zt^2Z`hBJFM_8Whi3B7j@!w^LkOVSOP_7hkavNo}lo%~BZ--L-c7Aw>eT4vQS6VErn zEEh$Xebc$Unpa^NcyP{X!S72>yf=9Q4JU&>O9`2<(4IYG zf@tiY+=C_4q>ev}y!5WwmT`v}5rDPCEa3G+WnQj2weP)y(2mP5ey!@-hbOuR7&U%$Fmb zAj2V;BjA5M=K3d}^zFHg_>pN7z5fLxB7f1HON9_$gz_S&0PY zXVG^Pk!=|RzmhA05Y%zsckMVM?`f|V&9jF-`(3jcbU_W*p4(7&VtlEBZJ+K_79&vK z3)&9}OiaZv_p^AeCNq4u{1Qiqd}f7y5Gs{Q**PJLNdr~SbSjixpLDpX-0Kd#6|sWpX&xeDva-Cy7I8eK(6}YN6Qi%J@9;p`)#*R)!1T(+FNFtK(SyYT~<9+WDbG6O)*H!Sir1 ziN(l|PVWyVK*_Q9jAsTyvol-rulA5 z67{khF-u)`?^a2GklsPK?81*tyXOXeH#C7vTa%mEL{As2E7yYEFe>Bzqdq}K8G44$ z2+H9Pq|)nGcsaF&R$nAigg2*ocaLE$s-&vzdpeckGxo#dHpPuEF0Md=E zZ|T3Bi77F^CkBc$wAo>}X8|dDz2yJ>L#QMv)P1*JPfZx5Jp7H%1G&=tG|U54->M9? zEJ#r=c#BLG7v!wuiVGsAexTVY53h)oJSMDXedP`XFHvWpW_+b2dWLB9;~wu&L4EjgP};4gg23a`8Zk!NLGjS`zhwsmo_s$IAg)bWglbn z73aRizPA`shZy=Umlb{9Z7KZQD_uN9NhL&;kqC_%22Ii9(R30ZTZDB5{H}QNKkIs* zmi9N&Rdi_+yVWIOBGJO3N8BR&uYViEi6d`j&8nD^nr?TW73*MgtX@E9qjnz#y0(PU zCl@(Gzp6;fgRC0w*e7D2=ojSFg-+4Sf>>LpjSUuR>50eUMYLMm{IqMUw$LhTF{MEB z@+|k;D+~*t&0J!k`GYT_{M0o6Mv%I%Gn^kzD&1M`9ajWrxu zWm55IxJd|ErAmS8km)(jAquDse!!x!=N&aqq*;CmM+rxymGJ&sq}8`e4l?`StyKAV z?6AH_yT z`sH1MyVvkli0yWR%3T21$-^;(B)U}9M^z03;GW<${K?yW!JosgXnt3PpHUf%O!SJm zpX>Y;T#x8ZmknGtZ#nx7X+4UppHfW;>v|$5S>P}zqW+?48~-JIJ0LCB86{5OmhI`5 zJ`nt)U0^Kb8x}I#DwAi9BT|?CJAhB&xBSxU%6aK^=}te>(`!>~toFeg`k~;@^K_VCk_qQa zI;siOIy$N`r)f5-VU+0tA*J3)HQD??Tl@ZV7dE*Rm$ahahjl5XL-3a#zsR(N0k*1R z;!40t8`Ux4!)GxdVU^?zp_&$IQCU$CyjEiT?)S+2M6>UfU#~)lXBFK(t|{8OcQO7f zOQD9vdIJ!^sNzE!m>LF^4Rd3Zy5Jx+LrdPn%YsE8a!9Ow+&5l9=j5A7oJRljW1G*B zY}|k5wN7JYDS&^dfO_?7W?UGm^hFc)oi=fd%KF?mCFl3t(8mhqkxx%?+J<(Y1GZC` zWs_=Fvpf>r#~Oqq^(Y*rj7gUih39SHKPwiJ=4DKcmp<;l>Nbj|2FJrxHv4rNo#}Be{lLF-(rntK-m#hc zeOCrTsUw_8h0OMCkGnowDhAt(xeH;I2Xyn9&r3Q6L4~w`3?s{22_@(}9V5x8i}VlV>PA{KC;gA0;c`Em6K^A*d+iCq;;aU;QQgX=dx zle*g*>-2K>CIm#=y!Q7dOrd`&vZM65k!Q8zlhQ54zcxMv+6yP{{V9b@$S=*KfmcJU zyi!p^h(*e2Z?e#8io?J(G&V*mrmibqs+0M!D)B*hu2e3(<4UCg6C8qp7$q09pGz($ zmb>De{xCggW2aek57zsdtKaBZIpa?%m)`n~apUwHacE+Ji68B4H@!a1&}@_(Sx}j4y(Ep(Ch#hI7jp)aL!B@jY(eJ^A@jtb-xmyd%lKrx4NalHCyJWpy9-4nC z#uZ4@NzZZz2b84iZj@6Ink^+;Ux^ud2kdE~PQs_t_4445sYI3;xs=3}NY3xb7R!QX z$ouGL#gPsw6sbM;{_$KKGdpJLm18??KA1c7wiY|X;-XdtEAO__CE6AjiHs4fH_}tr zZR#+~`Bv&50cMpgli;yCLOX><#vo?BTG;w)O!=a}1tNltLAvlf%2v&60uJ_xZplTJ zf$yg>vO~1sA5Xdwf<6;BcuVI$0~pv=4a_uC1kr3`^DS{k1kkmfTX8p^P#7T z^t?E4#-(3uhAnXJJo_gGq9-L}5ZEo!GQ2g*Pj%TLgin^tW<~JUedg?W7m|dWI!40Y zA(}}2r@EvdBDDQ!p2>`nQs7(xusP%FJ|6MeFV^IOp(1-;Ia^TUa;6fg@Q6@pVTmMz z9Sy{&Xx-wMA|i`h0zo_+BPK|qbeyoWB1{uFYJ|Pk8p09Q|WshEwH0GmWwx(42a!App~N5 zfJufCSz&^|V;a&PWK&BK8ZFg%>0XX-nYrt>3Dm^UMP^Z3{4V=?h5ex1R5(>qeQgoM z7OT{l99b;+`xQOrx5Zc1F7ebt@{9A6*5&o~#hMZ4SyX<2ao5|a33v`S`l^C8A-&is z%L@VV%Tyjqdp6mU#8asP$x7 z@Dn({zfCJsL6ASee36HOu2y)zk6taJ|2Cj!Jan7QR(2Gh8=Fne{;)O}1B?~^#IhAD zAm!dd5g`(3#KPbeGfq9_^*9s$=)u#U)sE)8=}Mg;ld;QpQx8I;?`KCLbocndM&}Ji zv*&-lM5`R!K^&&GG30(-IO;C@pw%*S^K-^T_ua|F+3KRRBKMrb^QF+fqI>aP>Uf{v z%Px6Xw}{U<>b3oP)cN;5syE{3qX&=Wb;($n$zO16^vKJ!Dm(a60QA}F1Ac{sQ5;US z{tHvaOLA$~)eY9~19e1>3*s{_BaOBQm5)WJBTOz5J%~luG<28xr*$dTD)WT`@pjrI zDAVMp^jS%HnE>h!F8w024H3kdgQOw=f`6>bwS%#?iAegD3UgjuG?_%RkS@o6I@oNY z!%vH;!ktw;Jce}NZ2;He3REG6OXQgqx>W`gG5NK{e%xo+yD9~L7dxjpHM4V zs|BTJ-tDOCe;{q-wQ0r*hdA$N_PR)W6ryYdHtVFX< zC7XaC9oyw`(0Om2Fv^j+^n+R2JGbH4^x~myO)fzBBIX=CuG^0IkV|?CVS>~cXe#xk z?D)q&y{WOHN^|m#h#`5iJ#PF`t#S*ZITXxbYA=;e%c{I1%ECkiSaYhrpB>u}CxQj& zC*A1xNWy+LB!ntqp6iTMnH*D<&(V0P{BFxT_t=(f+uY_Rk7Uz4)GKqR_|89+%*P5U4?Z}bNxVI{n1PBjjv{#KKb_Knl;UF*?Pa$= zz%b&y^XKJqydoE37F&0jWKg%YOgr~42~)u~TQ{Alz*BTnU?*P2fnKv7IuH6XUJ*t2 z_Uv#2_az;LMWu4t*wx=IY&U2!P;r!2j%IBK#dn6w=W`l?8lq*Q(PGmHEl4|g^kbjP zCFPAPUa``#hv_fZSWEL-!p|TjsvHv@?T)&~wo=^RWAGlSv?kd?S=cCA?_w=CxOlou zH`x8e{qNstEvq+ zb89fEEa%nnX1sBDP|ga7F+N+Z!n2C~KSj5Fvo|M_ZBufiLJRL7LD&%OK0w&6$y z3+fidXM8clGHZpu+!T=?F3xIlS2Z?P(H!`Dz3KPIEls2YWvQwjvN-Q8F)vrUBV1*6 zTk;9Zc8W+cVjXUMMshYZNTPFB%jIC{K_){Rm54s|4#+@=VMi$L_@JdK*7R$7(N8-x z25qeu(xouF!f*&3+G{Hp@4C?M`w9kNfh3j{1ED@$iJBe&)O$yFNoS<%U9{3BKc5Cw zGizoWJAA~xeW01f4HJYNo?qC@4 ziCq|P7}ID}(UR@!`;b1iB(E`&^?PyymxTTFrh3vIZ6LbK3W{ZVs_N_`H{!nD>F^G4 zczBEi;XS_NHxwyWtogZGTj2V1tt@briT82jB@VmJqKq1F;Rk-78+O|r<3m3nfN8vJ zJ@qmJyD$Hl(#}&&mjB5q>!7!&lY>pO^dSwinveBH{!eyb{c)JVFA5ZG{#bVO<<1@~ zMCI?5-WS**fpf#J*mC&GJWss1?Dywe*E4ZC!p#zGZB3t+kRxcFbQi;jt&vt{)q>)m4H_~vWx|n5Wb7}h4p7R?Ur4hy zsB_v8CvlO>8FS12NC)=A#dx*MjsG&`o=XP?2#OWFwTh<>HmGm2^T&`8^E9nvv$4=4 zyYK73ASLP28-C;lm9_g9#EV{?r^n)ngxQKN0CpJDv((;?%&MQvC!<0xFkT-KhfA)U0d) zAr;vX@)&2Y#Gq?e$7uC97{;_|4u+qn8>c0%Q za>QSTRJZS$$b`&W12qyg+%O99j@#gt#(4ClmPih>PuvpC9>GH&waYu*uq`Wix*RrB z%sD(RD-woE5`@%|T-aAzVfHxPu#&Sw3R1nKzf`k+QkY@`KisK6>=aaR6 zcTrPh@cuhChQYWlaa_wN%ELpTT%NW`bSIw3RoGhB!hy+t(iKS}SID2Xt@(}J3Ro@M z-a0+1Ew@~_Gd9{(NWH*>SK#WgZAncGVaz|?(?mCLstEcitijd?E41>OSccYp+i@X_Nt|6W4R5UBF7)3M zp0C&Q7n+UFo=s04l0Ib6inbc9HgHgH%E2$r8luzHc&1KQFpj{Rnx^J8@^oUBVZ7Js zDmuhVjj>)*4!Lm1JM*yzeQi3fsj)>07#L8aqX%X83{X!fyY%n|11 zYSBiw#6o7zR5A>cOx1HaISdeU)&AB3k|*;4lqy>s$$O$5kw$HniC1UduWGjZuk3DZ z2{lTFndECdk3=e^GOlM}lnk8setu5D(^-X6CUKK)*YdfCl;?3s!Hr~+1zA<|GW`7N zp=F!=f?a}n5N`~%h1)ZYLa!inLK5eUT;QA=!}<qen7NKtt$P!JehNv(&P1FjpCwPmcMHaJj}Zbt{fU>igJbOIBVLaMPX1(&H<= z;2SyhrO(E*yb5+FL7p07?eHLNglHsLT6^p)MaJ*Qv-ZDZ!y+4-{iDIc;r0spd9nRC zex^ltD>|oJlFlLU!1bgy9DY>rC&qWt5EeCV@lF#_%s;x{&Zdo)u=^(vj8RnpWoVej1&2dW-DgPRAe=5v}?25>92 zOZ~HR`|DSpp33T49Hs*+sMc*!A8?O(WWPRep@}OD+`vw}gX6 zG>x2*>}XC)JmsUVyv;m>R>ONH?B&jqQ{CjvyLdTEN>Rp%>J zbw)^iWbQhN*2JZ>(^e9Ou~x>U6&;otLrR^ntvEUgkgq}HOW6JG^|f|;t%$83u1r|Y z+VeON4FQ&Xun0!-j!m+%am+G0pkYOYOlk7)ZG2j&M5j{Xx@nR`inv%dg;d)t(K}Rh z{SaIoXu1Yvxor6;q|i(_FF^ymz9Eq^xlFPn>IG#~|4w}h)le;j6z`X=i~}w(Eg5HD znWdirMyyj_v*MXApcP;>g$-v3@nScHrJ5)f+tSCYtLd3)eGLa5zJ?+KfG5Y)m6@eT zDy8*a{%q^oDHSmmdBKAaTg@>hXo__k>LumYSTm1n^0@oG7(b7D0CkZ-bERH+54$nn zzMt+At-qo8$m!5aAfu_BlwF@-}%ilpp}x1r2KhC*%I-y*f6I+;}N{0<bOjOOlv1J)|gqMZU18^^raCwuoF;G3-NRJOugknhJ{JmdAJaA z6q6st1}`>kh(`#V;u?r=ZK|7U^%Cn|oR(<;cAA>8VHk+8la#BZ*inpsjZtS_{uy{V zmoN4t5F$DE1uKCwBIg0`B4N4KT|e$9>!0&qCAG?LP5?Qdae!86(P8GaoTEg__)U3T zPv?M?2wb-+#kdX~V>Jt}j;Z0??&KzqDODQ!rLRw|l~mY+Ory1unp~v$4fgY6lz$TX z7&QucX$O+egqi=ho|S^0m1wp-v(aQ)ic7xjjo(Pp2^$#_^X|En34~f_ibMT@E`pq^ zsFN{@=KHrOP1_hqq+xLtEZdd75r*wQ?b6>TacX5;KWae}1(gEaUXC;!f#oy6y4@U! zo+%%n&Om$Bi)$Lc{kY#52)$SbQrRbqZ*r*&`P$3WV#1nY@eqI>WSS?37U$X#iu!U3QNRV|Kuw=EZl}$nQ$+sl zBxv|zB=hz(XeTVcCgwOd!2c+wKxUnU$AJ}K4G0R)flm}5>v*krp zg#E=FGgUtx7m<4#7q8G54eZv&75zz%5M+SCh}6c7=5!>yLaV+ME0>6v{&?>EZ5Z&7 z1DguE-Cw@6cvgKYO<=rMIM10vGqOxZzC`App{t(h-!@EdrNcjfcjC#wXZM;a(yVL zhcR$jzuu*2c(xY4r2CM*6f#_^F>FeZDrf5UlW&5zPjTi9u1(7;=eW+jiTAV-kxuh_ z=+f4$e0+Lh1LC_cPe$_rZAv_7C0N0_kd?rCz($8a~z=WFS_K+iou6?jnCBd zn}=!(=>AD*66|O4mU_<*OC_nX)1pj1HSl1o@s}wrj>QjRhHTI1>-9D8A5P$gWV&sj ziKa1sk5v}*7##92t?Y$Ln8Y*K{x)x;Mp+d9I&|UIUnkYKxp+xk;3$?#nOs)SZ~Jj- zS0~Cy^hI1rEt0Qz%5ICkKKmp*fWCgJsOyw~_>Zw~}sZdZKYKI`x+2#nr3bU4K^ zNG64o+ZeYOmNs&O^C)JqW%M|&E+UeBVj8dhO(T{YinY%UUh(7Ln3WDOZavI$QTo+=y>`^6`)mS@6k0xBfqI1PWAC(83L?@$> zhY>W?jX!qtNE}n|vqbWJ8~sAqEXHLPR#@I9Wm_bov~#lD9Z2dYoe<4X=Mv=NX{KXu z8oeYZ-RP;R_RWUVqLN`#!yK7tKeeng+8VEbZR;M(KuIlj0lD>GH#!B6nBxxm)~-F+ zc8>GPIoQZflo_W-SE#WmpBrM>(k{&I?UY|G6UG5V!+-jECCU zMMp8N9JpH;;T1pyQra;_G`SS%Wi!Q?R|UDP6Y9)tzS9Iw4E;1dIIx4&*X+_gOeJEk zC7`v4TUDUxDYHqv1*_hxmCEKQQ>hilkVUV}rl`gf`BwwZip}a@l+=-`FHwOwW$FV9 z543;01=;R>dgDIa`M8BAC#(2wH;GH_rJ2-Xhv@JS7vjKR922L+(SB8YxF*dCv zN^egKAG;&U%||TBO|um?y0oN~-p?-X%epEc30N0+#FdqHsyFsW$=PhT!kU*pCArAD z*>IlF*T%fd0os(#toee(%1O>yDmviq)}?Y2Kkf28^I_G0uuOp6UR=YtaVTM9=G z;6Bx~w1gMRX$T!D1KSMIuO;sETZWizar^7S>=5aeQ)tgH)aXYqYV?Rx!d)I1v;|)t z0~#m2O7{37TY&?x7d;(kaU!qq0R!VGqp=zq_HWhjB8DS*b?d3LlQ*quk4n z^pZqy{9|oC{IjguSh5yTuXOw4bJ%LUK@TC8llwjrs@`blUsGlY1CDmu$2h;L-t{>j z8*+XR#=t8Ya3+N?L=vja4)NwD6cGSXjEu!+we<>Eo>0Wv#Ja9$f38y?zkNJ=I6KBh zcv1r7yW1&E{<)P7u0$#;+e)>;_T-j1Fo2y=88Dr0h*_;mutY(MIA9bA(^S->F%4s~!6N6Of+l}^ z3d707`UH+n(o07Xi3NYoq?+2M2Cv#}AL@+WF2$teWElz)b_Zf`kEQfB0s0#Xl7!ot z&naliBBA%nUTl7$CzBeySnB=nv%zW1dkp>Qt$1qg!_(~Aq;e`tQDM!pv>v-(VRtYt`p}QBiU}26ox`TmvU6^{jLRYD&d( z?};9WRI!=OYU>AWRwMbSY&adTx%F3|VfuEX8#TZD&I|JEAn;mW?7^I@y~;*h)^{@P zQ3-+DDT?f!Nn(OE}_JPie$)qTn!1q z-`lgY$QT@vPKs>5SRkyHWior5WkzK}ezM3IKeBqCK!JB_@|6Gr z?>Jeco1HIEkSSxJZMn^hZiHHm9TsQEt^7EBF&bPMdNO=%62cWDs`U^H&n5@Cpe>N% z!}!^&ivqnm22$ZzVN#LE14ZR$mmNL7!-;>MGuJH{^u%( z5&TiOJ?7Z+??ei9iccNe?qmW^{i_M8a!#R&rE?q%!dPT5|4UPh>kE&h4X5&mp&M;E z%+KA=wQtXLds=Wqyw4dsX3*Psdz_&9aX`?F?)3mVXw)!N9VbJ{kl=UZL|a8P0jyJ7 z0wb21G~BO$jy3k^>;S+dqgd1A8Er9AoV4Hkz9A8EM#pyKgG&pPB)>?&{y{p9Wxde+ z?!df-_}@nstQtc9pxbIg?ExvYSJg+P6+qV5{hJyd&%=?ME*=oNO2_ny6YyStRiD&Pk`Kj;+Era{T`q7h@MMHqv z<^$E4(No9zmE1qMC}Kg+U~y-9br*LsMm{JP8>shogzq^!Hy)Rp(R0&oF~72G=fLM_ z{nlyFvYq#x{ze93E4;#)j^W+-*FvX=S@p=WV!*EsGrew>1ob9sY(jl2=fHiXa<{J( zsb5t-k^sx$K3((V&LLZ_W*b#K7sdJIP~9X|kq<(liSy}j+@u0PBVm7Hm(7#utk!B+-1-psA zz#q058hI-hd>;n*X!x~Srp_>;!g8dQv%TA{9VnJ{jnPX^9kplcE-P|^#Emmo%OM#3 zh-+`(gosV&DK{=h8Tac(3x>~&1#Z3*dG25`v~0jvbv;_a$Cja&@%)tu(m* z(q!xWu$z`2B`=cqi;$~fsQ{V#`yQ3 zgurEjzJni3=pE9!pEJsTx6&WOxi-|?bwmF;|MqC0>vdR&(7S~A2DSGm2&fzuOP9k&vIFQUCcW&@nRBd*9i? z><9Qx?;rD59OvCzwi5Rf+`DET9z2OWHr~k#JebIPz8*H{xc>KuvRNAQEI-1~-MWsB zzLDt(I4+Mr+so^(91^jFn;lo<+Z&raj9jL;j#*cKuoP0aSK zUM$4Dcsk>HZ+xm8{Y!)N-xtGnDWCh+%=>yh11qe!O|z%^eLhr9C`g_2;bjsMeO3JR zCxgA^Uz_crO$wZ*iP7bH_Fq$mrvptoUzgJa&@=2dQmiUsEuiqNoxtY!B|FQYs#>8D zVG(yl)9u#QloL<(nG(Xn7XOSt{k#lfT*{ZGj3s@eakxf7!2G6nKE5G5v) zB6~gdf2saJ>TxJzu%rVMT-$t4d=CfrpSJj!|JxI?0B%3i{dt(+-$nE8&sK?#UKIqW-!(cd@|&DTk!Q8%wi+0^>T#P6J{DSu;qjb z$+{%OG`jBdO+Lukw;~ka!0;LTy^1b@w9kaL*zV3)nff;a9mw-%t<&4vADt)}!6T=- zGW3|4lT)G`xZQpJ1}c3agSyH4UiAD^+qL|$NR%hbZb>Ef(=gheZcRGG-KzE)9mb~9 zzM%ksyrkd>`Br|o4GPb?0Pv{O%gSIGLLFtXdP3sSTTOvy8~bZ_ezcjT28>d4%##Qe z?CNiw8aoh%pw}U=0&S+>#j!+&7+z851CX=#uKUf`Z{OW7Oz<&Z5PoAyf_QhMH|WIo zaZ%slHM9GHpzAWFx(23tcG`X>VAr~flQ9;~$H;XUj95obiPo<_cMp?n$K!9o4G;}O zzx?le!0xW8+sQ(2?(1PLJj{`W_;~~QVFOt({J4#uRgDzovg1H6X+PIrAeLgn9ubk$ z$wt)F(=arJ^cxRBney8oY>bSGm zy<;2ryh;2@3b+0^*X&gbMqR&q*r5^}rbyEb#0V68yAp)3?K=D2_Y?0mE!%CE8@$j| z`@bAZ%_PV9KW|^F2>%xvV9(kPB7P=;Lq;dufDI(@pQw85c8&Yl|DqDgz=pw_nskT0 zH?+}2OE@){pa|t@3P|_pxt)F;LC3&w39~^+qpfNQEY3;%R{ELm98N>e6?W5M(#{UIM{I%AG&$(IG7XHsH-{(#t2>Z-tD7X$4SC1ea;ht;HSXKb zhgf=Ve+me5n1C|`D_0Ih{jj81aOfrcbeDw+@;Y2(uq%x;__g{h>^n4#&`&6!$?_>y z@YMrmBQx*3Xqt9oQKMcy;NJbD2S<~FLi{i!aSw|DzH~BOYn^v%GR2GVax)l5@jH3; z?8j#u+^_fBrK)pXxf-yQ@!YqYcERZnGiW)_H*a|%h;w@4^kX_#eW^?k^xk7y_jMs& zf9e&;fgLDBdY4VjoiW9C61x5`H*kEg$B+*%1^O>p7CRnN;5yG~nZHZi^BmP#>!USz z7+GTu-Q2i&nQQJ!nee+<_c+#BN9pMeLWXf3vOM>G`CKOD{7aAoasq zTh0HYLqwSY8YGiGbn|f5#@1J563CxWtCgw~vgsACTII*fnNYEzr$RSV%Q~)1;$CiT zip>QnEarymU97%Z(KgI_C6Ag?JF&?Tl&H8=zlS(_`NO7~(HjQ-A1h`7d5e(_gkit% zr4;y{&-)8rci~Q!8l%F9ygmekgoGsMIFKS}r6v_zD&Q5KEY>5(CyU@w0YuJca)CP= zo2K$!Yb!jKS}F6oZgWWAb{M1!zm(BTNWd*O?QXH`txURRr*#|@{M@HYk$yfsdu6y= zbtf*)azg2TJ?hC4l9b z0PGdw$*w3N6WFm*0c%aR1ZQ6J?Hns>HXNQ4-fR8DZx_TfHXOrsXliPUuwPkOS^qe8 zP$)g-huCSR$MUK>ltd|AD}1etC7cbZ!jqQH2>xT3Su;ywF$XI?dg(jFqNXvk* zG%kyR89L~6_Rv0J)gQM^{EOec{4i=1`l+p5XE=wwA2!Ov0hVo73nLkfCKEy$5%~N1 zFBiGveU@&t$cJ&hD_J3BQdMo1|K|b({m-T2xck-GuH!;n|7mI7X)^>ju@LAyO;)U4 z>qr;G*?A}jx8nB%ecs;hp1Av*Gd#xWpW1%bMG(LG?d|-~{yNYkk(}@GAm8UKLE@p( zU4K~1Jgdi=Q7~#=-w&rAyEv^?;NlNf2W(qxr&W2pGw;Y7#1d?a`|NulO6dQ50c-Gi z-WQyB4GMec!|j6WIbCh%EPUbUr*B^AYc)UHbk2Pu6taKE<03i7Q`NfnRsZdA{_4Cx z9~dES_|(U@pX1FSmFNHgy5~`&{1+Bu_I}VFdDyJ1?rB9pafA;xhA}s%-c3Xg6V08jqFBQ&qpZ@eG<1A!n{>@4{#93D!lwH208!Cmb-Q zwQ_hlu+p@0zmNn>5T`QCDrU~i%Vs% zMfO@7dmD@yIq!b-@A7KWFp0^JOYcBA=(9rUNHA*4E!zaEtalrV&lg09NryXLj{nH; z|G?^pUf%Twd4{fgqpFrIl-K*XH$1p*lYAPKiBlbM;kMuosIC3>2yHdO#(&|Vbu*Np z1!gz`rxorqlezZClhOO#e@njWEXfqV`_{U9(EfGL-pCcY_GC0(&e$I9-g&G?9oYwM zULS`6SGP6TsdiZ#=Zgk6Klfn&2JL?5FeAr#f!ckJx&p&InyCXYrzL%KMxyM7-uyU$ zkrWO6VVHXnN{{{XpgmljBFZ_k|2gu1P#lJ46yA2U{!~AYRKvv=ec#V^C-N%|>>eKS z5DaYu?dc5VZP%=p`r5`;-XF^cgQ>Y-f%!kEQ!;DSpk1l|*(BA}L~E`#dMV5KMf$VKDE3*pR|6wzi8^{?EdGn0^tY{pmCAA%hRzthW+@F?lohu zRCO(5f9A7KH{^BUbONQ@wP-L#?I$N`|AuW??Q9;3rx26Gg-@Hc8vau z+UMJD2wdCTOVtmpI&tqOTK9+WvdUqPK)=`CoI%KG9tC01#&Y#9SEL^f{BNu1@3#}A z1CWC)XvMCZ*q=Vit$ocwOmzg9ViNPAJHIIFeQHG74~ekI%1XwLw==u2y{e#EASuKH z=n8VCBH%IW{aJI{K%2O+-|%^WR(#l8US59WL}_Gvows|#^$!98$=o3yKrm!)?)IFz z{y>=EEqS2>%tUz(ASp4m9x2KcXsE7M5Br`0fB3y3(UaF~Z7ACjG z(up1~Cd4mMd`BdjCmi*{&;18Cj{}9!V{Eg6z_$XN?#CM;?n=#Gqg96+`2Q}>S`|I@ zFOn%T9XA0h_UEUBT@OLBlg@$qZ^PemXKp8b-gF;pGvTo?b63u`|3e_YH{5>M-5)RA zKZ`FmY1VHfA#aXJ@bdkEJQW5)0a5gyNWA?rl11r4@~psao@k^`Mf!ak-e-`e$0&8i z`k%@8Vfz(E?(KVRJJBq_>suo8R;`_WpvCcH&&zrwpKT}lR80vr8d87>#Jxf3;jv)D z9f8M@gO__dpm`NRUNZdY_Qmf}ObB)bDb8VY^rtUrsDg-l@Td3L{+cW(P!w5+e;izT z!<03b!^hi$k)4~q2fSlr#cP<*RaFGu{8je{=?7A$-lyuWXZrCho}lK=GaGD*hdVMj zb(Cj0e?eq&G6snv`ivu$Ao>(1FPn@twzT4i|K53xjmz`~B)e}t_+C6*La;hiH-w3T z&)0n+52h!z`_%-3=>Eej$<>V@7NLaqqr7_a{sx2gULAWu`pQai4o`$)AD_M8bdYVZ zm{ISD3@2I>sX;@JawN)J9A;L~d<{)ppwZ$A2{%jiRqB=MBQdJv-OxVcP*7E7vP?)I zJF3^pW#(EfSXu3iXM`h5TcvTc6MG~(;Kzu=Knw-Ey4E}=Yy;s@iG3&33*V4aujWyT zVEv&}vGF(NESt^H6C8F?SE zIfvL%g+t2rxc0Z5@f8II%M#mYye1u)!dk8Hm9zUtojqkycIU${yp*~3FvUNo%_Xy(frajOmn;Db#uCA{1t&^FVnU5j*k0E74|5a!BFMD8B ze(JW^L;rV>>pYS0@$uPr>^RBO7qJyMtwvwQ2@6dC{a%C|@4K4w+_chMjsioH1nLsg6{GYW{o)xS|C1vDom}e$0jB;3;w$C7PgD zPeG4j1v9KJNxkWU^Unv_Rn0%ip z2f{X#<(I}1-18zV%Qy{}n4J5AF$O|sR*GXM zeDCWAx*h!`=xNo@d`;cTu~Q>$ms#ZW=w?_VonFT;UeTc>RDdxF$;Gv57=it>`&L6P zCzJI78THmx##jyW7-6s+S||9Yb`{iy1oq_y?GTBU6Ddr0P>#pNug92=t%aI;C;s+S z`qR_X&79Z4>YaZ=9zziwB;;_u^(eg>RLQn#_Z^3P>E2nOEBjPsxnw)%eqjaF*Qt{3 zNWTw=0duyG15v2OL}iEQWh;4VZex>bSG+7t$)-@rlJ}eDOia=2z=(t)G|rwa+EuCk zN>PXbd`Dfog2sh)G z3P8&WvMNY*#xMP&z>^F=FdE%a$l(92PqVFNxPeE$IN~qBBsND;F9UA#l)=6P{En{!5s2A$Xz^8 z{fY-k?C5`!M8X%$zfs8-L7xr|BDDQNcfD735Br6m#S`25(|%aekf3xX|HxVk-FZf| zpfkXJQe~z$tJn2)fS|#md6Qcoai$?o_XRY)HUW|Ucf|PJ{IznwT>F43I5ch@$v)VE zz4(w`y{jM^@~x~ZWIethpV-scIcq73fsHG=+x_ccFXO`h)~5y+5arhSM&iBCOfpc} z{cNw)FW6!rLyeefvOgulambj=ycd|eMals%BLF@pK*`gFXyg;{BbBfqR#n_pNcL&t ze|9l1KQedb!a%=|D~1U*>~jU0;IrcAojK$xLaU0(>6kc%{l3B!-A9eWlV+BtGf3mw zwr3enVH_gTXa9R3`00IH!g#|AYmkw<*L#M@u=A`^0x5)anavVQ6Zkn$ZHOBdQVmeB zr>VI!L(E}(h5kKL4jit71WptvW@siz4XwItK@L6kCx-H2>n!_SxRj5340<7s{p(!l zfU-U1l%mPm=Zzt23lSNZ0*%cUj9iZDTRC76A(M`q0o2LLP`z?Rf)OODr$2FnSz1)X!fr&U#nhu^4Gd0ndb0}4skwC)opu(UXqDs zyZJ8sTi*o%`Q}#1F^Mp5U;Fpd(XEGi=d8TqmICI+C~@aD4$t_~X86ZfZ?M1##R?4y5|A;}XJv%==Mq6F-W*{N;CTNb}o_)3jNll$m zCl3^E;-A{kvEI@4X{nn`biM^G-xOlZD&-vw;!qvubQy)qUa`qgiq$(IO9OFZ7kC$E zCdi(5z8T&k`T=k@zM%^9`4Fy$`H{Tay*@-n=^b*D!fO)tTQz*66s}mlMkA9%BS zHx$>orNf5iv6+kyESkGcv&YXM%(vqdYZCSh8o@61=NrF_F}+fySU9Tw4Ts3K2YkY# zsSu$vl+k{v*r|Ns(#{ckyuJ{rJGLoW_r{LC%YkE^_(FIWPhIhON=NpG8TX%7Cv@Il z2-$wD1B1wRwf!8hNaUAKCV0ABrjvPo3foR4el!-s=!Jx?cG zm(MHT7+77i^VV*!E`#j;pfKBP>3&*;&K}r_QsRar?XYgYYZLyb+tFc@*i5_SKSUQ@ zB%yn>@-}OKR3_}U%FOiAJ#+XG*Prg&YdzXvXC^P-%$Rnr=SWC=9|VR&f^E~{upURd zeSvl!GxC7bpx?T>?oqI}JP)Ssp4c0!Z&{wX2u|xL%LX9bN8(TS575UwcRKbdhAeWE znm?GGHOw>61(ho1;+R1WQ042E?Sk$pWabR9Hjh#t1Y3TuyQ@wEa~1fnCw{QY7X2^7 zVac&iwJ@iD0kOLtRl9aX5B_Jq7O!AZ0i^ymM3C&~pDV8MgNU{#QJ`iSV~hMQqQThW zFX;y?HlL*BD~UuaG?nT*N$8NW*n;*QZLwISmH(iE8*3rDI)}Yw`*Emy+PFaV3~ta$ zM2jzW%ss+12aK#y;nDT8Uxbc~q9{P8JL3MC+WcA|c;fY&fx3_yK^Er+*W$tl*Y6Ww zVmdoo@`4PPuVSN^B?S08ENH|B6Rs@b2hAuKwSwUHGL-&?P40F8VrS8kx~3p_ETrkT zV09g4Pa`7-5felKu;KeA4f&OUhPS-yTFN5!1}OsnobbC^IlL>N8w@pEcHgbo7%~%j zkk1mR54~Bi*|h7vrxbj78cOE=qEy}zWEgyq?dS4J@-H+>vOmc1&>%~Mg6H`Skn>(& zy~(%H4%c5t-s(T*6 zXUcp@I+^(+eZksA4$#TS8^})BNvKJZ>qM7Fgv-$%Tuk(pw2WcdVY^btWO~! z3m(#qnO@$16;(NojV4z_31fuIAe$wN8eI_}@9lQ}nfh@PNu1dm{fl?;_21c6bjgQK zmgNU>bVPih((?=}rRN(ykrgy(6bc)sXA0%M$6MOSdkjT}sAy%>u!i<4Htq9_kC3YX zfP8U1>T;m_$?G-f#V$;e5+b9w*SEPUtD^V|2k}YiBhvT7?t1wX<^BNMOt)ZO3LReU zvxE4!l;cUH=eL0NH6Qc5`@s}SG5!8eq|FjFiT98$MwZAv91rW1dCTDgqS0IAiftGA z#~yQcXr}EW!J}-QO1Z@&@5@Qq(EM-t)txTlt=uq>`f1q9VbD&LYswUK=@xE(gC$Rs zIfqo1eFKz6aqOdUC#kSmQ)UGWha%iazW1N(SLkc&Rsg!!Gr?sPo?+M49V9WZ2`szt zYZ3`EX{7X=tOpqfiv0`Q2=ZAcT*&lDiT%(|=06l=63Ru0b5Dtd-D8Wn&`gWvt`eY` zs+k{8u6I5~P$)wvFUzqm7AK<$_-;H&m&o$(Xj7Xl7|OseF4rY^deAt|x8lBL*~U?i zZh9gW?y&5j*4nVOAlQP=*O}uus5teVcv|+Oi4BZhfOaz$wzc-kOkT-X)9vG78+gWI zFBj37&D-0iV7Nk^242RsBak&xvJi_O+xvUuhXIpP^mS({+JOn$%u<#vGD2FH`*OBE zRRqx6Y1aY&^KFfNgt}t5PEA0&-vB?rgpRgoSOOt_zyO7JQ*{O^zn5*!ijt1h3@g^i z@Metg{gjzhn-{fk{bTc`g~y%ZoaKC=w42XuhAD&E`HdQom(0;cznBuMRLEq$(iC@v z&9(tz8I7I_A8AP;mxV;ro@*yHZMQp8&y_^darE>;z$U8b*Tdemogqiez@OQ~W>ZI~ zR#XuPHJ!&Gtr--XR1Qh37zlUUIGxQ1WZ1)zu}=vwJL-F&XZ>rCpzQyXE?{OOehj*^ z#SK5x?v+)3AB11yw6$k$hgTo@5Of=kY~Tyz=a zgm zSq^;3$8UbGRFL|{E86?z$1@v5|3m`?r8HJz=^%8MXg7F+SG{>f!^GrFP@<}9-L>8) zX4M_u=xk(>qKa@dw2LQP7Hax{Q^!$Nxn$EWqxmgp`!``RQhW|@4K;1UcK&bf&1yg-FFL32OMhD$Gmfu?kQEyS?=KEP-&x7a3IAyl zQV^a~n7gX&cp#ORx@Z!@dgz(|RV}c+rlbrgwun;>978qz3#?%*f=VmaEIRE~5}~b> zgE~o)KY=^If~-zR7+KQCUklq@du}H?3!B_n>nrW{%FifiBA+5HKg+sU8je73-QG{< z6&wvUj`P+oq->-h$^((beBvf=^xHi_)O zL3RS~K<71oL!L=_BDZx%!jIQxq42QvH-xNZ^DPDl#m{-2O*Kp#S2dji=&U-tz^{4? zL9P{e>+B=?80^6kwg?p~`HqJ??wxNRuSy+`MZE3*oFZ=4E8Xi~NKo&aEOSmct*~t; z12;Rq-$OFtuXfzF-iuuX z_}<752v1+RLS>oQ2hG>&6~M`2ANJnDP=s!Tu__%X?3hP3X9oAnj63l>@sx!yqGS{q zYS`l%_s1@1(C%c4Qz))!XoOX+kS2I|RKc5e`^wDPDkDQr+>k{;cNt9EYko7qs>P2< z>};ENrUF(&4_T3!SLW6GqMtR&J9Afwne70_sOV#q!-JqIo6p0XZlv<;UO|0Ik%o3& zW$folhUPrmkDD&q@}CL{*Wqoo&{6w&ozVysud}Ym&ormsG18|11&7FH(S!+7|3tdmDdk&Dri6^`AVOVjVW|#FX z{Vksg-fg!IyM|A{_txoxeX;xB)~<{*%Ju+JP-h<0_(JJWl@@c<+4|MB=agH3Kz4k$ z4fu!dCwPp`XUSQviJq5BW`BHy1osBT&l5G)5X2ui&)XqMlyb&+8Z$Pp@e?_PDtDi^ zw2{YGPJ9BIjU?6HG|b7ANIzKdaIhij>C|Cp3-Zz+oKNL1EIE$qObXNORp}?EfMdfo zUEVyIZ`uIpO3~3JPI%9kV_%`heF`~RV~IFDDwyvf{ok32!FIMb5yBtD&=IY$=RpL7oA$V%MA4@AXYouVDFafrNZ)4P-0xe} z$xZ8g`WrCO9xB$#E7ogEUz}26>KVwvfbx@fsyo)O?LP|hZ7z&MEUM{MHrm5~{?6uc z>IymjC7%ev+QtOF`#oSb_#XI$J`Gx|H{WzU3u}&YJ#`ko3ZZUa;U5wTDR^S<0kw@0! z@ER0r?w^ z)z3VTIloy+l+NMOXm*#t+g&GgzQcV48$b%3Cj45kN$XCI`>d4N+v%)PVg_-W&lWdk zhz}*--R!6W4589`aGQb%U2n)qoBMG(Lk-?#e&vtZrtygCz%%%-v4>f8fZ{#X*v^!6 z+jJ50wgC0&Qwjy;j+3*89+%Hsx-t<~+FtIb+7p|1Zn{5NqOblu==bTr&Kb2F4ax(^ zueN2?uO|66pjHaQ>w_*#S;8+#1$jC-y&m(p3yu_w0pjq7l;~5oOOIC%ulRybG(YA1 zLg7c;)h44D&&+GM-LNGJ1Yb?vR(%km`W+2;nDRxcl^cfbTv_Epho^ChO~}I#HXlV~ z#Y!P5R$jKlQyWeexH00sh%zV6p9lUv903QpJ!fP-5-qnLMTM@=B3J z>7IdQM04@pdvsrF6r!u)2*qBFu|BEa8Jf28gMQfOh6(E2eoUm}3fx4^!0V|wt!0^+ zwKAnc?az>1zvdq*?M7L-%X^W>H+>^Mujww}ph1pFH?dBT9?t4vk&Pq{I%y^IW>N3H z2SqSw!)7g+_uUArx_5?D{(?qui0;8v+3QItawhe`h`ApWUCYFZy45bvtqL1(xtw}u zdi~z443NLD>3$Y-uch5dRVKf5`!IIw&&#RjF*eBO587jph{)~r>HQG)U zygk1Hl<&Diknoppmp^@<&uZk8d3Kc{JA^v!*0ryW_XJ$xTe*C9)HkB=nDijF(mskZ zSMOmP(JCis#?q=BwT{-==bI%PC4~%BP?hGFi%szIvhfE!t@XMbnM{DWo_ZW*`_+$q z?ag*{;0oLzR_Waca??qWqRmlwv*n}aP8oZz#~ysiQD}zD$%SZ%a8@Z4@go90pRbtI zOzeR>WGEPQRB~}6=&an|WYw1_dc_Vl*A-P07~nJqX1Dnd&=v{gSt`~m)F z1^$9}CO}c+xe6UC`ec@@v2?htn~j_Wv7e-F;3XWh-VbmmN$wP?{k}6|e=ml5Q|P4) zlB|$>H=Ar#21=Ue2fsRfjI>6S>mjF>EH*hEd_qk|Xz2$ns6^N$JR%?hgk6di0#WP) z8x)l>un1)-_PG+#jI2Vb?yD@5T4bQhbLSEv@UMxt?@{21!b_zD)T3rvp>r(|7g}(1 z+4IOw-GUlym!M=R{`BJ%?`;Wtv=xnyxk9c?mhxF|HSw?EQ)`cel z1}nH#HlHv|{;uXGC4AD&`e)_{j;AXoxyIg>LwJs*a1!^1xKtf;p~bG0v?`h3%YHwGK3VW zNt6Y2Tq>t_jP9jh%Yx&g$N_S4`aKp{U*ttKnowrGXGbIkC;$ZSF5coJV$je)qjBP_ zAnu%mLQv)>kL-ylOvV*mI&UK_bhv{?PpsH#wl@hr;sv`{0w9$$qf~d?N`p-Wz7FrR zf>Z=0qpiXj8}Z5h@%eAuxc}Dz*cxX1F;enft1(zc2apdZ;BVzVdxD+@ToNKQJ8%WV zK(e{q8^P8uJ(ddMsksEus52R(hcazuUAua85{W5PE*)u)1sUJ9mGhF;RLA1y9@^t9 zO`)LJs5cLf+a?k)sy4DtR4}0e7~^X2nRSd8`Oo?ve6rR~x0mp$dO1rpzjokDYBp5R zg>=J_#@Orz&TmWqISqLBUaSjl8Pq>iMDl@m>~W!S5UFgh7$ zO24R)A~CJh>h>v=h8wSI zMR8S5d!>a)UHadMTSSN|T_nsPpGl}iOxTxTN_&)uDUeZ`TGi|=Y=-{l?`K)Ga|VkF zl};E93%%2Y5E>_%#Nt7yZfX;XZft?P#sUTW`AJ@V7Jk7J&P;gD-iBH6x>S4)L+Y)w z2t|$V-H#F|rDp@}o)WlxP)vgTca$Eb3VdffNuNe=Bw8G?EylcHr9QzLKS(|e7B8q* zvVvCLs9di69XR%>7$BAs9g?7tLZ7bCtfe{5MY*gOdUhs=0P#;IH-EnAcXZhmqbYOs zU@8&sEyqBE1Ts$YwCh`b8L!_L+Ns%w`*qwpj^`;jbEq0?;^@zT0%SX4E*+uE%hed_ zQ_iq4_q^Lmq}JPmm|5h&`#4Flv=rFtDW0bJ0OWCL)~%AtFun0=$*(m)^2v#SvEO{6N8kSJ9$ge<%<+Bf!0{?l$+&Nbjy48-D8ZL24%?| zITcku`>UEV)?@ay;J-B87R^hHk~s;puP*<(OAL*Jo6ubqv!k3kcb&9ut`*Se+=NsJ zzdOl2Dh~CtnUC}M13@_a-o7BlP25!%Q8nGpjxKn!$$tZyr))GYS6&l3Zd3N8kW4_p zH5RB`iEAjbYrGo1OZkh4OFBO<0a~vn%{Z&aNi}pV1ZcLIsF5r}y2qb2RG z`SnuBgeE+|hvncR{ei*n&d~`^I zYYXlUJ*n0fqp+W}Y-_RiMayzuB*DioA}lXHp_bCAv}2A%~4d`{ORxqzzY z2-wgH!fQA|x#-F;l9AltfN>^q1U8Xm-u$OI=Do0$+|2>`q$xMV34J03bvlk#g zgN7g4IE(mG8LiFm`?MCEkh$_w)hEd9#q^Iz^j>9RfHLWGFl5x{Q(}ygxJQ;Xe@P;x z%53JaBgB+Pm7RvuOkpHhve+PI@0G@SZuymF1y`usivqsT3`TWcK!aNjPZYG3WVSfl z!$V(WWzl@CY~;B4%SoFCceP!kLYMvn_JD~0VTgrB3{G=Z?Id{-~x?{HcO1(Lcx{lUS~;?HBoHO66hNh zxzD1Aw?oqAZAd&$7at#Agb&!%wd+1h?ZBTU!#Orj4VH#dsbIy#iBsSgqjfhHQ~PXV zI?`>qqXAO>*+|HZ>T3FN$$7;ds~}QY6)C7F?EBl$v!;PEn_FOzZB4ESkcwCsrD_#9 zeBLF=;4+H)uVDDsKWd_1hh(b#_oLTocM^qsbz5F6)eb>ou^6OX`EGw#nanUt?!n=$}} zoN%U`RLSOzprE)0K-g)HZw{Z)H1{@k) zee;}+S>l@d#Tn>BHp1M=`!;H1Tvj!N=-N97GV_tYeNJ`c(*AshbP4l*pUf%r(wTk` zS3`@^7OEEfOJMhQy7e%2yo2YyxU7ukRW}ii84qRSoE0NuL@mLsHH9gR4xlif2@gXCyjh9niHC?(Wzw|p`6mYVGx&V{#(C~NG4By;vBv4C z!Dx(O7%)1Dhi#$X`$g-I`dK(Qyot~@Bs1889U?1jh|#3v(B!k=z@r8l3-SWgiR!uB zcIwUzTY{%QI=rx=iy}vL8nMT2l4V?vJw}C4WU((nK?|p%GtRee)m7eqA+hPC1;5bw zh5@@%)Os+cm+6sh#Btbb=UQ7oBi4LYPH6%TRCt{2`w9p!#FXr?{~u0%%ltb7^s%AeVID5~TU!T?L_yo;$C%MpqJxC%6gWWq%@yZcbAJBWlg7 zhwJC$Xm{_)(s$%eS zzd8X`bZSep4NmX+mUaX!;8*+9qABnMvG!Vo%% z5xR_km>3no=s?Z5Kdi1^?U3o{sqbgQWh8}4|xvtF7*)E3GL8IR+Ey)s(?eq7jhst|Un_vA6VWqaVwK$E2`9i;HEL&DJd9x2fF~?NGY0gG~9J4$_<216%@` z4>&5-B8EKcBbD`gk6$g32i1FBVbu^cupn@+*IweXC<9>y(utjt(KQ*eqGb%F`kky9 zaG|^xi2~EllB6vwKguGiegSp7jqt&wliNJDq|_vGIDi4P1lu7| zNG)@HHfD@HXFoWATi5e|s@^SC=X3TdLcccK{Pz8x2id!3VE-1ts}rEi0xlLG)g{@j z2mi*Ye6R_4qwTwojlFAx6)+*E)R`E7pBQ+5$I#{@*QtL7e}e5L;CKiPinkLCHtuIN z61GQQu^FSn?J)SEs>{wVYv48d&k^3NX3fB&4kIUIm5dGsUscqcV6H|^7|D0K+VD_NcJ<&W|(yPF{MpEj$K$R0Y`Pbs@ zm-xXgE67r-?g(?~)&L}!ic3@?3DmVn(4>_s>nY0_fXMlQhhhghu`yu9P0Jpq= zZ`$uxi{D#KgPoI-!hg!$B$Z|Ur!3QjRKj}K8;e%ItE4WHikmmriULI8OSLanip>~lz|K8>Rjg`)R91r}D;sc<=|&*pJz05KYY=R`--1 zT?b-|HbJ*@@aP~VB#)Faj`C}ZmRsU59qV>dLqnvNdu7eLgAfaLjydGY_$N?a!-^*L z3?i-RkdiDB;#kC9y2G!(?N}x?-*zy9l_B(-+5D%vF4b2RAuu;zNu0PCgh7rv_QHi| z+xPNJY`u`k#Z-1^fK~=*SBH$iT9r@xn=#;^o3Ebz$&d{u6L(R3IWQAT${8e7X^uq} zoO5QQH^6G0bMnz2kHtD3Vrn7SkSvP_(|h0EoPU{IK5Bvi^1X*)U1J|7#SWBePK zzlWlm5eY}wn3+PB(?~&@VPkz-(+SnjdBNERao<}>$;mgIQ0i)LTW#}$WAWFrj3YE$7q3kL3-o7l$DzQD zQ(+k%TNs5vWweQsZ@}kAXcHTk^>*TKpSmKNtgF3!m+Uv>qFIP3Ny4W(&gYd-+qB!hisyOmOqk0Ih1HO9nff0;gLua-dmm3<0&&E8Fe7 zNJ07RM4FKeNE1ay@Rlt@^T-5W0tsJeIL>Cq-!5H4`^F&Sd36%s40Yu%=O0$YC_026 zC|>6(afNNxEg*2}`8pLRvvghZ9-V;;EQ{<9iTVnWPh&UUme5I}!ZULZ-^vi=*?rxi zms!q|mw?!C*(C}xINz+GtlILjRKAxQD9IDl7E96E#AP&|VbSDKRc7K&!{2sdnb;Sr zih229zwoJ(!R0t=Yz9WVG!&%e?d_@*92RxrOehyhtEL6Fwcs+_ma7I}p*3@!5BQ&L zuXxe-2!=9)Itk=f2Gq{5vQPY)uOAZkk~HaODIqL^=Nl%F0<7NK4Bzs#ra6;*N5-D! zQZ6ktR!=At=QqYI4*@Rxs4^9f8fLE9o*o3`Z2>v~ta7th6?Zto&nXU$^|q!^YN!Lhj6zJ2_$#Y$6v}_7v!wL7zCua^ z2Z(#fB+}s!KC26d2HRxQ!%X(f_B#TlY_5V0yN-;F>pUt`&NjA`AU0=1CU zoF#HzSnew@~H1>qCiwR_w8k?5FC@rMaAmI|o)j z!qm{YyIxJXb=5>j5*fcdPWG|pP>}rMirbbVwgAVEGVBx!G7P8anYvlN+v|r+GcczS z6LT>(JLXCk@OaDi)WdDZ8M)a7OZE?VE`(K`n8TsNY)ImpxbIz)%m=C6_5wv&%*Q=0 zw-S%ztx@2f#4rElsRJnKwkWYJB>W+gc2JBVW^@$9mWhymL3p#&F@&|?gd8lDK^eY- zYB&~0DaWWVFd=bp!yx#LvpkRkPkexK0U}TBV=3!=oUbLTkgaEDbjz0dS692#UspL2 z0dKxw_hsTHxtD$%g0JVz5ImQ;xF9-3R4o(3RWD&0q3s7g`xLH6j+M)>uMH|Kj)>%oQ;DO}O= zBBzm~8>@70MH?otJHTww&7R8F;VQKTF0o{Lq*0Lf{q2q`eMe$pS2XDEdady=Os0=Nd`I`Sn1w8A0g{Z!Tcce>!yD zg;W#MyFx=MKkhusnD8pXbRE+CGFrA5z>c-)Y1qHh2Oos*z(HaUhaNkU4WG{weIkb^ zX9!H3xIm2uXIQ>Uol56=U@5ptW+b~{h(EKCRmghb|+w-56L|4u|)*FMPh(tvF=Cfr@BJ$`~?v7QA(o;=ou-`GR*^GC1aj zs!xgw|BA)`=8ZoBn02D3ET1*>Q6M#$T#Uta;`}|Pt_Sdh!FaTH)UAp6{z*Xo?w|&; zZca++KPR%kj=^OJ)BwlQ)0VB18XFZfGkLY%ML_zry-67*tRE-*7>xxx7*{SL(TgDm*e=F4|g@oH_`RCOGoXOH3PaEIkssTS?BnzmH2z+Aeb z5CunGb<0T?>Nm7OVmxqGR(07BFlipWgiW4k5+5LP+}`b0rU>&vF7oT0NM9Vmcj3o3E{0g#Vy|p|ttLIEeNBGGRmqc+SN1@q2u3bGvxl z$SNYshzY)O2(`xNCFGhsYckN>Ulr}=fgOdDG>m33HHiL}%+Tgr^~%M(YJQ5&kI`zQF|)94kA}V{#D2fy(!Y+_R=b7t9yv zyX6GCZCUgYR#5iW-PpjX8%yPM61khPnI=JT6dKCxjC?y4P5NOX1ch{YkG1z+mv`^_ zPKGun1Ihy(pjC~SKy@XPxH>IZ8GHukgwPyiUkX)u zgwT;20tPC;%gE1caq{8cJ?vX@r>7MrV;Yb7@6cM#*r(;rSVxDvq;7$W&>#hMRpKQ_ zeq#&gQ=59jC8r@if~@wE@gU(}#=B1=1{sdX|5(V1;EWI(U+7zWZ!`)nqAtI`(U4`p z{e0*GADBAe?DFKE(B}iMtFps98;Mvty%t?4A~zoRmhRX#%^(!2I??LyCH zTR%%M`?N<1(jM7Bi=&##8zqV|IKqM>VCq`!4{@@AKzdGThdV7&wAB6#eCv2odN=eJ zknt2v++P#(4215ffQ#dsfBe0eQt|ZalrTz3awbDX9sU~)EXT~-?Q+Z&;UmCo?-@MEx| z^HG(795-!iTtF>if0_OTlTHdwo@Rcp$|#6%aTpqs_mE&qzCGFNs^QA1gpR6vJAoxhX}5wUAy=8k5namx+oZ>Zogz&02z)%=2*GS>@UyGr6e z@cqYF6lWQX4K+;}R8^MT85zofq_zxx{jSB$h*3_?CqC~3d|szSozbI}=hZf2`qe_i ztS>sOVIjMKR+yDrMq1j#n3>OM)0{%>s+-mnwHSNVImJDRf``~sAiVEiT&5in1yn8m zYBl>&o-~~TAK_;AO4rqL*SkY}%G#sMxoD5Wvuwh02SiKQnr857xhq!5P1+nJn(s~b zPvWs&@&683tI@<>IyAYZAYI{uJyh*sxgfn`DD7Z2v%f{VyfQ< ztL#P35D8|;Qzd7Z(7C!wZR+%KPKTUQ)0I@GnovW7WWSeR#pGzq{a_M3dh7}Z)u1{- zx6O)kGHS<<&$O^P-DR#_ft_>b98JbLDX ziOLve1kmv``Gi+>(l^P8U(a;`Rm#q;l-7mH*Mg?o-SGgYQypRs_K8+Q{fPxpou$gj z!W?(t7rPWvR-ld%s5i8l_V=dOLpSt6Y{-c6o2zeSmIGkvaHCG^t?!*c@%dk|@l(*0 zC`gh7LM1jq5*3XRrIW{+-+8Hm=|A($D0fBr%N)p$LQ0t-iC^n#Oe>BMR&zsYx)JFH zTDWvdf-%@5>jSP~PVQ8k-*n~%InbiuNM7d&6U;S^kU?O5u;nrLCv~@ZXV@fVN*a4u zkC<^$-Q9vfc{z;OJ~*xj%=;3%NC%Hy{J}ES83P`{`$OF9m~3IY2YUuz-6U?kY;1E0 z_DClrt@^`a3tnZ{++<<8O6%E<2i+VdHZzzL^d|~NC;U*4e7;QSmXtr|rCsZ=nVDWAe8s z9b7DHw(_&TjIO%%rq~4XonX5G(g)GJ}}mY+Z2bO6jR0 zgBD<^2mwV#ZRSi)yRA?~Z9g_1AXFk4kW@X8(LgyQcmhHl>XkC)5~sl|!?42jqcaUlAqx!nq*5;a7~ za0?iiMe7BlxJTYO%+XI9L^M|YK4gJPSd2D$XV3Zqtw$gbC7118tRC_gHRI-)UvtJ4 zDxbOzY*d4{$dVk>$87s{DouPHUptI)-4e$$iPA_Hb3|#lxK8vX7Hd%wT{d-i3Wk%L zj9sl*x!kp$7yqVL9$86_kf}Sr%01~lbff&}xH>nJCmy$`OH z4$LgE8TAqY)&g@}852n9E!Keys7z&`o5EE`8I0roiXCPDdc*yalV0!0J+$`z?5zPg z_v)}mDPQN8t+29gbRybvE_eU5he0u`^tb>I7e_rdHjktF`fKfbFXUT zAQRGGH0L04U%Ml^^!^lW(&B0J3G$q3IEzlz)yDPJc2Xs#P1EK_@>)Q$25C{Ucq$j| zg|nk|yOSFhNW|uW@L3q-j@mplV}DJGMrH&7(RLex8{c|;|H3qs5sUraAtsIpZ5J?w!( zEYwvNWdOZfX*YvVDnm2?1uDD2)=dy^CbaXKFca0iC+z9HsC)6BbQN7xFInJ#X5*iu z$A|Q~N3DH)cEM~8NORok4lQNiCn&lXX0pY?~JHZ*+YcuNt`~5z?V3 zDH_3lc?&vy+Po-XH(x=E8j&D+^VL2!?*Zez+R?8ya?cmohR&x= zRGjI8&&!iVw^a6%lbIp;BWh+nbr=d-Arf+knu}VstAoGH>;?xV5!-AHz`(6myk^YU z&_j1%3OTuYIDReF5K<|W4WI8nc!8YEY@J|}Z5a=ypV=ZPNIrM6Xd9)#c89FJdt;2_uQM`Wof^uEx+g ztFubss0V5Oy+KfAwk6OYBrQky1_-e5iX4a^oJyiktg{+9HZfs{RyLBXomXObwP(o@ zfK5YYQY(rv0iUb_MsKH9cyj}kCA<7NM^q(h?br(Z5s{aRkL4&@ta@7p|G7v%$ zwAV1~?M#%1@~PUl<2RAU(NeEN)yY-IDv{tCv3C=(?7esF&=jz_((F?Ft;nyhYGbAe7x#d!b$_O6E53{(kayBDMD%?Ict z8p3OIAULaC+5muexBf9$md-UUr4VD=DFDz73$_=)FqL~TA>>#RqLgazn_Uch+Y6Q7 zyoPd5SyjK1QUXhcbhsdJZPmff^BgQ=_}sNWs0erjgc1-!KnTT?`M1zt;ph0nz%qgV zlu=lg+WM*NVsV6?oW3K3sybqElh*0B-$x%rzW!hErR|>vpt5KHuX!d-sdlJ_^(yR+ zbZnk!A7swk1B`~lmBG1$5FDC&0etZH07`9Wp>$1(T?s3ie%VZbW-J9Eq&maSRB0hw zk_afy^g$Lrh;^Jj-GpV^h{6!BTvaULM!d-wOfLcBZ)CrRj*K8_+Z*E|(_ZR4+*n+Uv-Y2)b^-4Gx#RPFjVRDY@mS z?OYu8kuZW*(}$+%h@u#tqa$cFkj~gXNgukgxa0wGP zj&GcRI@n2JRd61q8eVrssg7wnUEw}C@wf2^mgB+kfgK+&<)xhG{F~L)B3)v(|$T zon#ui>*`|K*&D&835NTTYCg8s0AS3)HcWdeI8S2oMt_I@Ga!^6ddo-%g*QSut;@|HQiXqpbU(Z*<>lo|{@mf%+S=k* z?!A{kc;6rK8^8YV#-5+Y<^o}0kV+1=4YgW@EX#QILW_!(Edo(CROzTYxNs=%uQPg+a+hZAHnoDT9 zhG7V^#x#xx^e`c?A`9A4QBYqwI`JaAO}=}`7D>?kvMf2!lwP^EJVJAdqX56#rd(Z` z*tOmpimG9irw@W?xP49joIo*f;n4b$5PnZwJ~gG;w0>%(FbQ|2%H1Y zrD~05lK=GKkMO?tz3;MvGr;olGJp8K_wkP(`pCrR7Xh$lvrU>ytgedrh4u9&rm~p% z#Ncy!hPBf|46Mv%O~j!;z^{4HuS54kmPL=tw9Aw#4JwUQN|ot`%AxO)#L>RN8TM## zWK;apCPk^zptXHr>TAPTX1Ql|-s<=xR_D5D6ZG_-lQ^Wg`5fii^3=PTm~wOQ+B*lz zOr7cyZfARJtCHs#-PV>6ebUBj>HSbu9kW!%ZB6GHTTYeM)&;Q}(e#04c3)2;OX7Wx zVCOkFwt?JFEegn_@pI%R^KV#=cKHElIOb)|X(rJL6;_riR4Za#WLbuyC=^AnNjU#L zdCAAP*K}asabHRprcD%jqW)-D!qTnN+}9f3c2$lZX;89z;C!(~;Coc27{+>@Hx-=M z*VieEg0;0Z0M4I3Kl1#MBS!#eHk-8DZH^r~hPr16ZFzZlYUw0N;+am@X(r*t8fQ+| z0NB~-lBFRfV}IB5BHA9a#EbgTm#3XpCheCdgz8O1$^>EHVOXWHjL0fgC@2n0@)s1s?#xL#Y9i~3U!w9_=6d0es#Zg+RFdtOXz z{$O+@X2m>^ixL?>(KxzR#kNf`4Jk_lW(ok3IFJ2WUH?1|%dH+HCT&go%66aHcq<tZ9TQk=5UAK)m3P_TOQl(BD`ZL|#`>_|CFI;RB&H(3G@zIZdl;8TT-{O_8d?mm8 zyT3~mMf~zF|1!;{Shvf|%Y5*IALNT){35^ko4-ktB;0)S&HT>q{LVnmb6%u zT@=s>6iyry6Um)+7e9zOdh`%pXNNRR_LX7IYs#fbJU7{l0uRG>i2Uwuv#$5wULckg zWg!XN%N?T`^g!EmIzS6iA!Vj+M;Oa2H^idqbbZXB?Afp!0(U%9O`@R3dU;N9>4vUJRnyT8 z3suvRB&Fv<6GKr9Efkf_A--mo=M)RK(w_fVB>VIt8Cf+sdAx?EsXeJw3D=9zbroGx z*w}1i>*)xsQ^>9A=!Q9T(eyyOr?Jhy(I`y57j;(zM=B zjEw+Bp*QnD7O{>B5}CEKsJU%718UapMWE@%)b45Mbtu=DdkS|dX&fFHoK4#yPm_H& zKE2KkhUMT?m&x;V=47HI$rxtoK)!{0y&AyUkY9W2x@2yi|cA9ntSD2n z)kzxBo#rN$#-U3FXx+4@COT2zqNp16)uXtrt+CRc8!A*PrCo4dZxICt17{HD{I`Gm zx4G}W`$&fde2SvrPyXaj*x1aoMZF~cmc7?OKU7U0xX^= zE)c7lfugE&abliQ-t!gX03CRPL6yB>muquJspC|l;+QC^isyQ$@~)AkRjSPFxJ$j^ zkt7NQm)df0s*Qmz^&;Cs5ElnX2X+<7^Nga%CuaJ?A$$ujk2{9oIFDYa59VjljS5od zb{yvzS~R+UZBegR$g_-d z1IEVeonV@b()RK^gFGW+_lBX?^r_dMEGxa;@9b+OO(N`abpd6&`HjbEA zWpAR0#@+(ErW+Wxm|vgA?F|x{qrK)}vmFd32m6z9vwmMu)xpK2s6xrE|Ffza*yY+_ zv^ZUC0QP` zz1kb|bUG&f&Ly&NR860&TsOQEHLMbLxkj_uK~W8{<0uN&*LNTbC|j3@vN;?<5OD3a z*K*~RSJG;=a9x);j*%pZG)>8}Z1COfCq!vMC(2TyR0i4LP;Uoy;bIeG24my?XjgUc zF5|6pHGanG&_lwJqs$-ZYaTF0nF_tY3-g0JV&(Is6 zt}PGhi^F%nG>!(%2SriQ4IACCNRo&o5_M)p)zD4rzwU9S z44iphfFEm|K2ZlrVso=emW(qthCz96q;WJ;X){ft!Pvj;)Yxh7?yzMUki^_V6u4w* ziX=&c*Hy|Uu`j-(BF}NE4K_AgL{UQ7F|jR;Bo0VpG4^iSWtuIYJTpe1TTx^jTb{W~ z^F!ewTC!vUZ-2vaC&yWEtJCF)W+T&c;Ig<3#{)-uo!Ba2o+Q zv|Pp5xoh9lq~|-jp@L;utghBavaZd|7Ov}wnq!_4dV-3Dtf6Xxu_4XSfu0qTEYID+ z%$qs`c-@`%jR^W*iX#p5ZX8pNOEavorgC1uPOD(;a1}*W@%@Ov4=J0M_d9;ki(a&A zUaRZ8_r34s6QB45vMh7YJ@=p}3cvJAzr@HVoNeFxZ((Je&cO}GL`4W{Gb2#2dEE~ z>;P`K?j*0j>&8K5J?U%z$R{5b$8yh2i=4iZ7yz`Y>KL{|k!OUxCfF#&No)aVN z_P{FVA^(0{Z*jWKA|S3x8kSndRvcca-7+vMkYxq0vqM-UG&=#6iiM`CB$>=Car^IQ zdy(?RBH8dqKmE2n8FacY z<+0(=bYp6HLo}7`v8Hmguc*i?N zem;KuIPZSXjh}C>ioSrIgE6^?Wcti>ez|uf80N6x^fG zN4IQ3Z!x3CAeLEbSVD-X>y2d3B3qb$)RH9px%M07>hfU1FNvc;vrRM_Z8XCoi9+Hi z7^{Jsw!@S8cX-x+j3wg;%f=B7nJ3XR9koY>f7t&tZEt#sXHu5D7np6OJOJS{+6_W4 zT9U|mPBB@Qk!LB9?+q4GsnQVi9tC1AB#sj-OQ%3#s)^(GG2&FB8!D_Fu2FV&xw4)g za$&uLW29(PGyNWwDoN%xjHbmry=|c(z5jAWmZr$+!2nvH(U_XlRPF={%Z&=ADH>20 z)?1XV47a_7Q(YqTyZd4e{Nx*6$G!L7`@BpOZf$LG@4ff(rZ>KR>T9~8LalBI#zwr$ z*qD?h-yi+mRFLjJr|NSWb9>NGQ&sXTLdrAlxb;f@<@4X-!o?OxRt$;>OF@!kws*Q5 zTCG!dO#E&O$5OcU#*;*WPnISl%|X-DDY9sQW<{ElB?# zSple;SjAbkxCX<1Ll^a7-t@-T^Q-s%_YM&EmSq^0jHan{y%1K$t*gx5bl?lGJj$Q__5FPE(_iD% z$yJtWC7hC=_3dqvZfvyBwB5wu_>nr{1hM|2xHO>dCwS^CXMs5I7b9n@B^*aW)iiw1 zN0E}j!RdxI7vxn<$8xFy#1<@Zn6`tgsI;~&;8d4-rHtvnTjcpbf>bvwQDdjczqTGG z$aV|&w{E{;@bAR+vFeq5HPTGGjG}4;UYp##v}RK_blwfMpw)?}*1&NLE_6MN#mpWq zd$^%+fnQs#4Gdq4qF{5gh3EMLj;q_+p6ITg=Mq{^ha=5$A&sqbM@WQh8*}tC~L6RL*hMX`0G! z{QAF}C}uP%YRgB6pZNn)_nU*qoa_IP_RjXc)EJ{wG>BJwjE(gt*pFPzj5kY$-P3W-CXD^4u)({FwSpa0T#`Q)d*imEDHcg;!O_LFyvG@<<<;?F;D z|KR7PMumI-?L8BbxJSsC805oA?mW2?jOzwaNp_UaQ{b$V&n$iy=EAAjYis8#Jje=g626Vjw| zTOYTFZxFJgqU+{h0(qYG*8W#vFEri2w99ncI}~V`mPH&#gi%bbN3EMx-sp=7`R;Cc zBG0m(z|iC`!zz`LWMy1Yt|$oH_RR5FNs@7@4ZiArie@}|u}lKyeq>RMq*RcL$@NS@ z4O}Ah-OK8lp{P3Po^7qJ=J;MnwWiN4bMzPdyhhBTkz``{oXou7TKN!1$HLhjp@^_z-91A9JQbw82BA$n<44?1_hgTC~_ zg%XWnjSW@R=(M{;alSA(PpU%?|6CM>VEyc)S|dp^s&3#1DN&TL)ToT5vtqX`qvrTvBxd%P#Yo=HHPPqglZ$aPEh{xkKsD5`I2@VU%mjbX(J%RSp`erj2Dwirb&hBh9wr{(03igGUcjRLtzx579qK;Agd~x zV)Pg+Do7$j+O6YfJ(td=} z+S?cU{Z62;cDOQNY;0_GSt=KlD$65@)T}JI|NOLA#3;6Je7oK3B1;lM81tov9;H+= zIdY_q*E<$z|b|0 z9IDSu1RnnS6C69TOcZ!iZ+es1UaD@)2k118DA$C}u_VisDh(pv9W*U+KV6du$zKu3-Oz?J0BQ({UYEDP-Hn-ob<{L zyIW?bHd)4WKOqEMbiv0|wLxQ0RrTJ8C}O&(mwk3Gx)aMB(-!}%PWd9?MGA^$a&oOU z&~MK3f{l$PVHnJ`T9Oq7&9KHY$h=^%?M%`fRmn(`45pUSWTC;KsHmEStf;7}MxKvz z=IwHAkWB2y%=Wer001BWNklN0Kdyq&ZVM z6htqgUUzUDXP2>IXXJSy*bvpF1L@T4jd@0~SsbG2CacReKKZGK0a0VV>daAo`b{sR zNK;|vtSC^x>S}Eu;hQEgKmO{Q_{68b#s~iHvjjoRk+lZz{MlD?XvrZAJYiTY!HHw5 z{M|o&e&n-ny#6#RufBn#msC#Lc)jvv*P$DuP&)~b9ks?4&JC!tMv%G4vAkG`BTb?n z7udpUj{;IrfUFJybno%u@`hEah~MorXSy7KFt9aDn>O!q+W|BbzFQE(o7?pBNHsUvtrn>kYByg48xf9jTS2L+(8Pb(x5YmAyi0% z=3o^qH2b4fQmzY<=yvC6ghskCH{8J;3x07nK%E$t>igKl90QNLch0@Qn4+C|LIrX zH1YG3IGj1r`mT4pijCqq9*rMnJ%4KK`6JdDYWfOweU*#hGd$jUgxlo1i3t|3K^ta? zZfpEvD+*A0w~f3gka{Hu-LS~B45Mu0yKMrmGXTz6ktPvN^)N~lPIWH{yf&s?p1NHK zybkr%qqMg#^2Ow1W6$pwocqy!>O9Wc3fhvrkmsObl?DR-S(=a~;-ZVa&de6CqG}@y zj^QwMiDq}V%yDJ+4!*){fZlHwon(UFys}iGR@-%*=yrWBTx?M`Gjw(Ku0iNA+QlVth*iC26jRr%$aHSsJ>X5I)&)dp^BYmD1oMOu@Y$_@z)weO#s>xF z;czc(VyAU9O-HW?-u9$ByP^u0-h+sI&)UwVkxQNnnazHgLqfV_ooL;(kyVo<1znM; zEvx9-ZoRJA^5}GZP8_WvQIHooimZ?qAR&<^0a4&n6a}_Z5p`tUgtQ zw%MlbAjujx@Jcq~r`d?kQBfPn(mlN6SkBdE%%r83XX#Y>)})w4@eC6g&9G?HMRRp) zr;92}SenF0;w4E~PIYP$v$tuOXDM!Ly9d(S2X2U_NeqgOY^;$-!WT4izk{XeV=mrl zF5yKQr%w(sHsWAvQ!wp0f!j`%yEu5MZN5N%G@_!nH;O#J9%aP0M$1Dpq+y}3InX4J}*t4pL(Ocd8P5)N6$XQr#|yFJU`_0$wL^1 z&Yds6PTY7UiB31*x8M60{Kl`o6~~ZA2!s8hqGvC3`1=oifv2Cjh+$~lbmJM`_~S3e zGAuDfP!#;deGl->Z$CBmH@)Y7`+0GkiprmU;4>h>PrUs~{LJOsox8ZPX!7U(^&j{@ z{@0(IdY<>gg`T#>O*4rg)j4xiWSc<{(QI~Ulv1oxV?;*RsWk9rlq~i(4aIThbapl< z*Oq(c76+phCUJ;by@hz=!{U82k1RNcrkjJ~8!$GG3dTme-J#o^tg*58y^ErtTwfsy zynXcs`q39gnzn0A;;5%JKN*CRIGicGbkOMcM`ksoOO*!KB`>9suAmzh-whw)E8Cx# z``!=cXQuQ9YKa%$aE!gzRX?*zii9WPZ}7DD9j@$jKGzyFR=v&+rtM%kRVWIg zz@3^Y+T~iW+%WmT<0!ze%cKXaNylM`>0ARnfQDWj+P-}N(49bGZMDbP@O?J7+`&-N zyhxLXZgUgOu&6Xv2fFWzMjA(`x;Yh~voygfm8T{)QQ+ZJ8w)3Zk|Yfpi&F3ZvaAdq z%k!Kf%X$U@+00&4XXhd%Y*IBQ3Ot_6AD{Wzj#{H>?eI$LEt4;6Sy8Z@#RQHDL^cHo zw}u7oP=VLMuu90Xj9spgrHPOmT=G-b%ln}VFc zYva4^Uj4X0)eO8Kq1o(m$E{aWt&~__jN@9txk*|kDjA;ps>7L9n_uAUuaP> zM%~Lp--V*+HNhr-?}Mh{lQ~w026`F1s~#*TYts(_%`L*%GmWWZ5?M>il)!eq@BTC&+`o5ZBwc=M6+Hq&`lfD zE@PK#IMpR8jaACEWlEJgrd<~NYotLf-S4(=+d|>fZEfLon*?5mDDV~<#h-Lt_otLi zrNn9HdS1HxMqaV}1`b8r@a!KW@0~T5BnhXoG?6kC^)lAsC<>6JzOF)!v|ugNZSPQB zIy|z)%QJBjo$CCH0>CVlNs|b-vpum(|NR2z;gA%WTr2R}+j!k3imFkruV9wS3-NM? zO$%m)E++(`cwMbx5GC_dXeU1`fLXCwJG{ivAj$g;{OKJ^GMzx^6&HHU832T2~#^|CT& zsgHq>s*0xJw9HU5EEH9}JVe&AaNmh zk}q{WIzdNca@-&N-9V{Q)5mo+fPr@NwCDq*=v_!X`>Rpl?Y6e?I-|gw?bFb9Ui3j( zlXWhb=XlA|J-qtR&vGn{Q7?QD_glXX=l_bL`%Tn7v!cIUb!y8~w*kVJ%Nm)DFA8Ze zNi)oYo)=DSiB5BK?5@(!rc32IUUzy1?^KtF0*}vyAD;O94+5M4tfkrrEwHcuAuB3| zRT53F(4Sg|Q`E(bDK#Z$r|DBJm#}SO_Z6nDVr%$c`5QYh@mPdU8XS`Hx3OP8Y9ih=1thun>#86Wj%gcm*cVA_Sy-Cz9)}8yRM+aVK zuyZO^dLmL$KpcgFAvC29J!}#yNz!GJVmL@Vn4d*L;;?m^Tdcb{WS+!rKSZ(dQQYp= zDbn$7wc2fNjqrxOPIG15GM&yoMPK1 z=>%<#a=ymW0GLY?fH|bq@(99+m4<~3+;Ht_-ud=dp~w<`5cAjfeU?vs_M5!+&g%xc zypkmGaQ*-q`8# z*0KP zckJ7Hl*Z~+LyV1(l9ADEZemy^oN5EV+ddG3MAzpFsf`?8ES$Qd&>!3wR87Y$m4$zFF)-&4*Zt2FvAFq8J1Vs( za=Ohe8i$V2ZEh{p-10g*f@i$7PL@gJh1gDJbF`c_!=&WY#01nF-ewYq=%#2WWN9MC zeS5a+!x_bG^4%kM<{uMKDQL-(HLPAkx(roDa@3B9I zL)8tCM7c*UQW{mA+i!g#AO854L6QmmF1E8fKx63Az_B_@(}^XStVnp_%?-Zw%@w}+ zm2b~Izj-0_jmwVB@^Wo3LLSEvK@j2j30*HjR|=v;=ESiEwrvRNU@tCQY+|Z0GJ{~8T5ql)tw;Cmw1&-~`>x;t45*iThrWK$ao6E@ zkVh9uT3;qS_vhr{IbgQshHM;0F5iqA1>d34cnRIsHku(w@blcTo$3N$h=ToDZuLtbilSoJWfV;l zE)q#NP%)bprk>Gk`y5)SVCX7QB9Ue)FDku;TFt>SM^AB8;?H8$*W$-*3$v&7n{8Hb=MQ;>i`6)$4xh#;zJ+# z5^sFnZFpY5Bj0$6BuP1SYLzS(qUvcTvdAz>F-;p3dhQhkmZ5Tfz0F^K@H71ETVBcP zav3*>dGMjfIDDuv@xl%xK-#T8+Lk$1Dk^}j_&Hwp#_Rb{|Ia7L^Mc1CmA$Te@43Iu z@oL5!uL?MJxQtU4+xzY97Tc{5Rm#xR0$nLscEmZ%&5UQB+u_WqRWz-auw*%|8?jv8 zy%ha!3&V0StP<_*ixbbku*J%0Z(qcAsv|XMSy6hPhOLoWtlw>6In|k7i1VT-3eqG& zDPK+6en|XX;W>&t#1Ar@36rBmQQ&pOSa_weir;OId_U71gHGW4(3z6-09+L7(r)lk~u9 zV_B9G1s+A7ajy9_*2>pml_~>01d(-*E@(}GFcLtgs={{4af~rw_Pmg0%Oy!tYGn;e zp1vJDzrM|X{G$&Iem;I|h1b05M$$wy=hin`Jn-2^`R5P&=(@_CuezSfk%DJDv0nVF z%bBYV@yH`j@rh48%tt@@5aqJX&;RV5lr4p=W=N$Xj2)_#67T=B(Miu+Zh8T4yysTd zjx2NamB;z34}J#E4^b6`6USG1^BeEj1H2Lsf9(k#{@SS1`G5GeHxK?T52=kceKm%m%cd1scrn&85PEafa(V*+>Y+%}DWJTct|DR@lj;5Oj zniH7EV@~2w)S(Z+wLVBZn4iT~%N#Z*c{ldP-u)T0I$1+4zZkiC3r6i0k|-n!eZ0*J zD4K>8241n3u^}r8rHbGc4_^$nQzMCkk#X8>SLMtVhf!pi$DiDwW`!f2dEKy3H3Q!r zov5=)6|yXy2-21M%0vx^z0tor-zMKpz8Mk4;=K&rp7m?bYpAA@${ig_ifZlGxa~xsoIhs;nJ5{34A8XF) zrj4xVBc%sf0!PJ?(=W({@Pn z$;=pClX{bcWwx^>$OSw3v#bYCQPGw-Ub>1R(#SNQ_dR|b081)(nI3bfYH`yM;jieq z9_QBEl+BFa+uCg`?iE*xQW<2MBS!=SDM_<|%H#UQCQ0aFPnfprmpu9z@-&?pMbW4( z9ip|fK2UeFo!ZECHA`-H(NJ}Ra@oN9&VLv@rY*e+eeD-`=IINR=TPew@!G>n5GKJ+Bia;#GTADQRnSvaG}>743q5D zI*?#c;nq}zJeLMMPr-Fo#=sdwGh|XGU8>aa7Fc9IjNlBAhB2LI*3liC%F$JV0l#;C z#F9%CkJs@w!+(XL4mY!oDgX?#~=fF28phW ztd+fTwZqZt5fb`cN~j~i(N4B#_mh$UUcLHdZpvRnCsa6gxJt!8N06WZg(E&zw7MCj?%+DfA3Tx&mUTnRFRr5IA)|X)YpK!b1K+1gJ%9-z>l&(T9 z--1@V4HTO!iHV{}e2+yzn#5vfF+_k+XVo|ZuY;zWR2zqgLT|uV9tml8qD)m~@*EWC zxuX;_xBGiR+O*4}aWZF6V=p+v4<4BJM(p~;kNTMP3eM6Jf!m(D^)&SILYf-GfSu=8 zk*3*zTm0OG7IEld?*ZoF2))isv8hXmop_y{Sk$9eu~YVix`Dj8RtIE1F_Byr4zjW%QvReKZ=ZYcZwJ)>-xD3vLdOpM;J&*oMaT~0W6 zVTTh(myua`MC+?lHVJuOs8q~rcF41A z0X^t6CiJ^#hKX)iV<0_zPgNC}ER(RE3Tc`wL>KFWv|X-J9thn&HgzZ|v(p@7F9= zH|@*nSOcIGCQH$^ELEzUT0RAU+jTjAQPhleW5J=TQ0CMLQT_;mm@o*bmokDl;{1gj zjvZY>QDjaWZSdsNn>3tc>~GJql-AbzSjoewHiQ<=1WKwb?E>^H-@g4u9QhdK>jwZ0 zLOiMB+{)%g7i)sK08CyZregEb@*D8o*3|5G(Y3XxmPVRHsJd|=&5!=EEE#KDXTFRz z>l8`&ENSyWyl4I!MRZ}pK>x&}-ThbfE>JW&&CRLImEq_%H!0Va@w=`00BzZ2Lf<6{ zeGJPPt8)#TBdV%`B0CcsTC*Ywee7}#w>w%3pZ3M=$HeuACH##YWKE@XVudV?$F}FP ztPsWr@SBtT(S^UD?4;jqQLe2_l#tyUmjcd;s$n}-BuOSt5{%wWC@%^WWif=do!Wo} zl*Z9zQ6;m}RhFacSX$FK>>Q;i3bwafbh^UycG}J3z3WwsYx6;QBT8f($3oY|rL?it z!Ra*wEj`DN0?uF9;mBG8T~|4Fw88oF+cYNl55j2414)!|rtc_sziUl5XAXAlCz3d# zv~(@Q+9GNDVa(dgh%<@(DCXQ)ymV$gc+%Q>Fh4tSEeTze`RhAPVoFwNUjY4JewM1X z%+=0IIBcClN;^c&FA<&pTZ-VRxu7g5{RwM{z0#k7*G4z2g}}KV-PRUPZFx38OOhmp z4tiUKC~#3!ZBO^P7-WQsBGc)5NXGuQ7S7N#RX-L11$o8zk;tO^ktZqLCoZ7bCgo!* zM7}%NF{qkOH(KBSn@Snk(1g%_*q@=_y=<-*({7qsnhYjW(@a8D?B3%AnxWxDuaYUL#`*NQKsKr;Zq#a}JRE@G$BZ(s}tap%# zi0Tw&HZN27gH4B@uZ0{pch{U7$y~7}YR|40k|hz^5Pi`$a=Kx_`bL|>t5r(2!OBXN z?d{f7H<~!~Q8f)svu4)W6;-2LTj|+>?e84SiY!gY3klggK^}@}(ad{HaJP%`oh&SV z6CaLQzcUG>RaHZ`tc6NlizpF3n4hJjR#~%7@e1?Jn396O^8o3^e+KU{Waebbl8jQh zrPu7c4LvWoni8Kv|+uE89(55{u3)-(E^~vdJcbBVc=qkxR8wo-mdK4gL zeQ|rgv>!E)21xvn_G9NTst)DV6#}n~qG^QP{nvygGLj+ZjiM-K>PZiWW>_R~NV&Fx z-)&CJOc%NE7TwW^DMGO=kCTKvjqu&^l9p*Zf}zlDjmQr4C&K!5T18QX-(;x_l1v(h zB=KaxelS0aT39TF*RoWraB}Gsu&1Ok#f0EoXz&*;lV4qNDJi?48YVK1W236#GP=0g zndmZ8HZ$6;%a)?ByyQ@;mWZN^uHPM@-}OV56(nTZ+oI$lNfK$2kfpJh-tAp)aTF{h zXm*fDq5!RaE71i3&_(8x2hUP%7#Q6uks@{w2La|qe{b(=ZVT@wO_PO83WR33JW(C+ z>(UoEY@Xr{>kZWOWxCs+hOIv(?0#b*QAowP9;G6heR(1gwOzbNpPK#)l8mbBGws8s z#Y})!)af-!-))ggCbn%3ws)4L?+c(c-5?HwvHIF=^4*wrnSXKrVeIiq@uLXR08!f| zYP;Acmq9HKrd2CtBNLoOA%M%UoDm_ay`h^nSsD)pWo)NLo@e`R9PX#wlo!%~Bb=uB zm;tb62t(n}>k_!_x#uIxQnDZ&8RF11Q*d!*d5~eJNz99~*V2q~mJcf&>XkIMOnG7m z001BWNklKLsKME3lG9v!dU@sUZUHqfeeMzhsH(`2d@ zn?tJ=o;jD`#{srJ`gdAR1-~mkuU}5oO&d)&(F_Y!)kah#pO1*6@v-mJ`z}k>J26{J z1AzX1N0uhItu0E`$%1bENP6<5{W8Z_i+|y;b&A8*X=w>GiMHHs|TcX@6qKpUn_FlSCaiegG-n_)#f$1zE= zbgWZ7DKx{H$lEMc8bpCR(s>`toMmNDekt<&M;4?(lo~YUfD|byBTa|TbwL#RM4^vW zs$j_Sm=c<-C}V>HzS~08dedN?7HJyK&2skJ3lLUUJukvENAE2gkp)+X0&h_2QZ-|$ z#Oc)c&oZLS8*G7PSrN^mSVPhju0B#mQ50IyHX9dRER?Awjebl6=OC7;RZ1v|LQxc4 z+~`d77aWdyDdplu3r$t9ZG+=S8+`AnO_Vgk=wU@r?XH>HjbcFZbq%X1ld?4YP)nVxFqiWN`gh6~WXXNa-G4)!BMnmXhY`Pm{b$`>LkX zwK`O-HLmj3NOvB`oY=7rm9{OyO0bYOt) zTgh*?HweObFkW2b#X>wuSy2b-X#Lm=&eOsym4zci9F1AS|DZtnjF}HWdcUEnI$nHm z3Rynm0*wL}-LMAi8>>_yaHn(AWm!g&RaWCQPA^@{L*279<59pkD2ry;EH+C;iEG+6 z)wIe}o!b|QD3S3Zm7{AF?2=7dBs{bE96Rnd+t#)gdIldOXSZ1l= z3~HR4TU}Pl3+iP{0;Iq9)FxM+Sw&G4&YWK1drxh0bX6yqkQoZz_&6)7$c3!yCDMJT zMjQobwHFTnnj$0Ze4W+$3wWlvM4;@y@paG`2;1Av)Y*zB^~X4AUrkx7kzV{X{<*(E z3ZI+X?2}{@xpE6?ls9D2 z14;K!sdGaGRWmq!N_girqb)YpJ+^p~j`{A_3KT~{H=gGm`;rPTyXH`FHBv@99Bw1Cibk*em#*#A zMrcfF_De0A_+7jZM>zm@=l;^Zs}@U)fm=FE(OGTy+RI2fK0pF1MCNvT2mr~cj;f$f zlz;MBMjzSJh5ogB|0^IE&!&MG_v-8e?26(8bDooL@ahYmlYEVmtR{7eomlm{RQ937 zDa&7ziCD=`oGZdI2%j9ya-jy?7Xk;t+!&PX^2FN8bTH}@$0)8aX@m`NJ|8!~va&xF z1$5zFD7|FBE|w%yZf>B{Qc~oEg1I_$7suigxlxgl6vsgrJ(p71yr=VkzpM#vQ-d%E zk~P12-tUZ(PuXTYwvx(RH{mq(DridN<8g7OX<*qw0+N?lT$f)w@0-@PA6bx3HwjgX z92lm6aKK7ntY?5?++B}_R?hH_M|yD%oiRE9C-#TTbpu3xv#$ocVpL9fybUcibA|O^ z$3+lwe+f+}UB)>DA>*%*@ay$9qLK{uL|nz)WobmPhCjQTIf|~IK1ufJ-kpD*f2Imy z5E;O>jnZrNdOmi?d}OK3n|58!WYUKlJKy~L;FxUYW4E4 z!Fmq0enrPzy$U=m@HUsijfG3ve+}$kgLHn^Ai7xmfC0E?2?IRObRulQVtC2Wy_aP{ zX4}%f&f!la=|b_+G_Z3e(J!y*%-)oK*BF;?^*CF)O6BV#M>5Gd{>u>IRWmOIJ@QPilj2>`gB?s_mD?IhBp8{X$#cnw;G~ z{VD`+{FT!9^TT}9!Jm-SLd2{+ctsbeX_a9zZszi|*1#M(#2@rmzo0CS&5lSl)ms)h zpf1k}93CzrCbK8a{r&2KP*_02OhvVWpM*32da0u?$j`S z4_@`n+}`81F`Hl&ttOCenF3VBqS~6*cQU#ck=VRhFBs-~BB ztTXFh?_n9T-XB>rgupzm{U=14Rs|5CDyW!23300(LKhAnZdFT_fL|vV2q4l8Zg}r4 zFt7?fsdqmbjb`uS22@&V{$80Kaef{iCyJ2p6T&E9MH)~!fbJ_s=D?KnKg&;M8EiMm zCRo2JA7D$rQ?yOvyD4r}yz7m@RV2YO`3n#zyIA~@@~|}5G|K@?&d`r*Zn806DU}+3 zMrs3WS55*mYz$ENi-kl7b{e=5Q=fpWgB8D?DQXuGgen@lhvH{V%*hh)pf+cfnj8*B zb7^%gnmTcsm=%sMZ^Boahn%{Kr;iN92Qv9F;e$KgBC1~=J|2J-hmc8^I>T4j*P=j` ztSZoU((D{Dsc0RG=J}Q^u63iQEpii=PDT10)Y|w)e?4FBf1BiVtI)dZMOD)`5qCQx z(2{=k!|OQzTV0MGqxG@=TBSY(1_j)E5QqmEC79g+p0&3jt$Vu#E#tWP-)-NYkOvN< z5R)GK!N?SXlM9XoWS)p_e`J|jQ7kPc^FbLa$l6h1YdOQ6(37J`=AV;4BZakPx;A%V z2M1+;oH*(fv#&Gn-rCQf+Pm*)*<+{_R4a_ltfFpaV+W2KYLIY|6vGAzoj45_>m%F; zMAQ-TGk*ptrQ$0cwg#=(vPz7n8yRZ_r3G-h_1+2a!yTl5nRa)5V@;>;-HTxw9UvKJ zDi%_&Ym!rMJrz2fSzi8Kk9<(eId|k}Ant0DpF!hmbP&5|qD4-*wsaba1@}K6|F4xAp>$yv)xQHDpi<(S=<(3!wDb-=L=meMgvrLi7kj0662b!?mC2b{NJ^RyDt_jFlP&hs7ht+UTqe~!$rT8DxrnDkNNIbE{E+`wLAK33>1=1U3#up9S zb1nR6K1^^-lqo6u&GGT0^iL>JdX;|igvJ?7nTWhVN!Zsfc?0{CV=K+V>8A}H`0aXK z_zkAY>(3bTd&RDF=E{<;XMLZqq@JZR2C$36Ue3{tgY`7O&X}gA=4en0ccTd=5G3no z%1*)|ez;;4I@O zFNPh#_n~m{md4-(+cDC1{_=cAB=5Y*K}T5xh2oWE+Guekc<1)O!LKbOT8yepsRym$ z@Q%k27ooES#RaFh9wfBn0Y2o~yq{siaM^wAx#SqZnAzkr*VJ2llyWqI@yd;ynR6*| zJmj>8yDHMj&WPhLAOCT8Wjb|}v3B?^j3>K<=^|Gbyxg1{xpoS8eku%9ap#`*uc2D`;u>z{Qp}G&B2VoJKW~kUW#WDlmj-F{ z-@wGnm81}GODPg0Fdf!ED<|Wgh?`Mf-@D)YP+1H~>$$8ko({B~`nIQKtHv;Y^ z;uLUVN*oBfu+2E?{>i}U_MCX6SVfXx^vNWu|IGHP;s2^$Y04IoCwBZ zHChx3*p0`+W#dVA>Vky~F)p9QSjX+`XHdFvauqAMXy_M`a7EQQxb*21u(#M>glNYo z6hQu3J#tS#WqntM>l7Qi8mU6kJ0Qm-P6k6ZIJPb`Hfk6*am6;T`h~Gw_3iem&80Kk z?GL3%r# zsu;nF?I9la+8RnY>~#>cdMO7OH^g?_o@h^#FAtMfm6#KN2jBlbU$)N5*C3#=9 zJc?8b^VH0C)D71a)sQ{KFCFEM&stUccCb6PhVL5WlRdv8)H^3Ta$rLA)sgA5<>_Js zf2uh()sjkh-LDgAVv|tVC5t?Syg&R%k-0-DuPpm#tRU@E9nk4a;Bq)8v4W099@BL8 zg(vzOzTMA-s)>3y0*pJ8!RVBjTmJD*JrGZ@7L=0 z(z^+)MqFo#RhT#VXmwZCf)JKb%`{S&K#)CSr-0<|>Av3&r17ZC4`SAVF)8&5*GFGc zCaUhl|E=w>N#S?10e;t-o)i!C>1bE-ceg~_#jbX6c*~unZ}3z12AeLri;Q-(FrR3q zmiDq}o>#2v9bXbghE!Y#{u~2q#cI^_qlLedFVDkLV1QmHvGu7z4_krz(TQ8bvE2`` zw;mwLDK^~M$eqq^`WpZ7?ZPwXsOSW1XVt>=$0@g3|uNLbg4YeDgQ}-Y9j9W4G4x3 zr%@94Z?5;>@tQ2NAK;P|Uug}|$cji6&>uCTsM~)!;!hREU>Q6QEjqK#BhM<(`-T62wHK#F zl%NpdT^a2nVS#09O)*xLbDS#P3NY&3Q4tzRV5wg(`I#5jZ+>F;Vxi3np;&?pB2%iBgJ_)sn@56*Og{dzJul#kz zMXTDU@yf=h*m;p7*2v8~et7BIp;9g{BQz-=<3qV<{ogyuJ(e1>*w2s-Gg|H!*6-3Z z#upUDlK$SoljnNg=cKsJzV%PDx#i}nX3&o5?>J_AwOgQn88iE4M)5j0YfkIM~wH1F{sGfWVe1-_G zJ{aK`KClxqKaBh*<=p>H`5biY@%5V)jY|LC%@QpP{B>2y4TvxSL5Qd~_>c~{nqtig z?HEL!ib@fZzFW*hrca-?{^(O#`W;i$#N3wqXCyv~iBZoorDZnrq`vgnsz?f(E%W z9B5Q$WE~WE_1$n4_V{}4E86Q6q&-y!g2+tY$+r4PydP9({B}@ z)6x-^-{1~um<*?iA*6){yQ|;spC=u-ckQ73ET31u|A4eS#MDc1J(TLxgA)39yt%-R z8nCS57jTRlO;)AMgm-BYP{erAb7;Wuz_xHmm#Q?UUpFm2N83g;m*~ML!W#b3iB`-r zSH31u*UR;2Qse8_HP~d!CwJ7V`Z7@0Lbu}xr^x>A?}%4v8K#$d=SSLXSy&D@XG4aGLBnS3|xd_ z(P`AV17J?X3gG(QXaCsUXDaf@$h)<(Kk!K%Tc7+g{mQBAVu!)T&SXX-Lf&)H3#A_? z@?Al8G5=mLdM78jl2izR^UT6Ew80x_g~F$AO{WTcug$}$6N`)6rZgzkE@VMAwh+_rJf9f8tSG)<*xpnpU2FxrVx9y?^4Ho*UcWXL^ooRy35Y9tnxnoh ztmi`lj#p(nd(s@yb9bxFi$%Y_Eo^}0+hnjpo^-g&mW{jrRDgByjH@2z<|H<5C&zI6 zM!sSgJ|5TXJKsTjB79>QNjr!H#hdNUqf5nFzCNiMnTXlc#H6=oEd)aX+?zky_!WR_%z#P$)bsckG^nWqC@;?8J<@{l*26dS*ytEjWN>}?&!dMlpIv>j*q@o|};h&#U zO3IWA#+nY*a=BE=*cFci^?xwvdx(~cM`WNO9psrr4X8~{a3L9V762})KbXR%=5X{2 zWK7(3xD3j$)7gJiFtus&N={a>S=m~ZBIZ>qO(sPnceuh$CEr^M zkqzA38+FrVy`(;Fa`Gi5TeloefT77=W2h`9}uD9@)5*;*PNPIKyAC31vKCi@cWZ(#3(oT~d(oUW_{a64AJ*R6H z6HhnobC55k&|;=>f6zRLkxamH-x@zia3Ltj1p1ih2zT?Mw+Rkf{WRtPCCVLJHW}?M z8J?Bn@#&)GnHTDnkC`2iFH`-L3Z zTGsjvzUhRQ5vOYS{fpj(kp$HrrvQVgSdSVFZVS8J=UM+(@B=>^(@9@t;1`A9!op|o;yjET( z9H@+R1Ew3{JF-Ix3y~W%-yU@$)|bIkksr)l{(a;+*0b|O8kPHKstpLct@<&$@qwUH zenMH5u8O0piCUq_8jE!suci#aNA9LL5Mgdv`>YR~xaF6&K)b-0spv-ccWyte9#;|f zl2x}+;428sy%JutoK`$eKu zqUKv&qe|Y6rG#JGzSACh(`k#cGnVvXzpSr7eY~4;8BqplN}&}Dy=(12nW2QQ@V(#4 z@LM<&u|^Gw&vmj4!gyHMe>d>;DVQUVfp;<9bVVW7aaDmw zy8~OBZJ2@fuUcaGh4V=g-F}Gb87AY-nn;5(&Gk!Li&MD& zC0o;E3y|i8*=v2~Mqjt?L(z=Mq^zD>L$56ej_l+d;4 z%jm0GP_*R&D{w;YQ)UywRA}RCAo?acA6*D^6dL_%8)!Y~>kl~9R4Uiv`UL5y*RU)1QVnKrgPBa6=N4i|0zg zkb>xP#;2L-hEoCI(l+(8!EY#02Uxr*hT+(Fm-`YE5j@2b%74yZVnjBm-!2?HI$k83 zq6;sRJ?9@94BhGe)#OmF`h;$*=ET@y^O6mqviz*>fHSI?;&+R)X@bmn_9>S3ILmsL zwg1SR4Ju-tg<5L`wM?9!pau1J;=lWonbb&LA}d884JbLK%(%)pX>&S$m8bB9`g_eU zKNISzmOY7%Kg1UDXt(#M%$b@&QGfitYq2l=f+0~+jVH~UeQ4f9?2!cz1Rmit0QV?s z)M}*$_LoO1=MwG)RU6)9E&WoJa$G*Q&v`bd3fCFO!$$l-HbYdLIjb7quVgvL{c+yl z^Znc9#r~rzRKDNxYnt%@B*CN3Y2KNlUv@Qj){7nUDQq<52>l}O$XY2~Q_=qIuX`^Gz~hUHEJ6Km@T-?xaj=(nedoK4NwUc6Q(!GTMc9w%Q}BE3#^x-C2O_?%nz<*G&Jv{%@{&ne64LuZW9j({86cIFat zg*gA+j%74@K`1t&!W^4?0viGX9JzwtXCElme#1)JHw_KL=;rSiFZ@~*d#=hLV4uLRA`L>Yb4M0;WD z5;%r@jkd|~AAn9py*KbKb_hE|KVfw%?@44fcki;(jFN$3lOTV2YZw#bQ+%ie^tG(& z+W3KG1Bpo8HNXU918d;-FeUu4tP)qO_~}445xx9m+cPNjlMHV_TG}dO5O9d9cgxwx zqM?z|)YhIaO}^S*IKFMRuZf_f8qx5X`ZRSPlx4p39`gpx&Q5!vKK!6aG9C0C7NY2c zT&_eLmLGQ3HTtAas%>)v@@DGDNp=k%J9R-L<5b|D@)*OVKbqOgEz6woz(n(G- zg3fZ4_5i|=rjvWgRQjI;CM-$0cnO~JUX^70@SnK3icwV{i1^%XZj-BIspG`-*Q@?< zIIiBq!Ya*audUm5{o#i{X`EgsCgj_D8FqWP)!+MPZLJ!J)-c0BIbWgMBu_NY*S^yA z+@C)REk6=KzrTC>Jwb(%bry7}64+j0a%{FbHqe90Ql#3m5vg?U3q***cD7LR6&6g+;sHCOOQoEKS(76!mjsq88bx2pOgVQnjV^N+uLK7^2 zRzAx3G7u0tcFNPaugWo9lc5Wn6ag;jjZX()`ZuQkC5yQm|G8`B;u$2iSXHdE6HrT= zMx;@=_dCa(k=b#5AdAgC{dm(VY%^HIi0kgmxIuimtLl;tnO1a6Hf<51G=J>RF2JhI zGuFma#+g36S34PAAeES^t3Plrw5`o!GDR#qg3skm3tZMVN&vBE4bV0%yZv1B|3q}2 z^XQ?O|HU5f@7wF$^$>N;#f-?yjOQ}zg$KwXu_0(uv-|YUEVz4XDL1xdpKIHl0EM+_U&wbcTye#Xi*iK3Fv@p0{iP)xRT$r##g&> z@Qk1n_Jk|G5&vV2 zhLQQEs`7Sn@xZkT`u@*tYThUFD$MgBvrT64OrgTk+e4-_QoCF~+-UojB?8rA9_$&QbP#{aY$_+{$Omg2xGL`QT3CJ{~%fY&mh--HSr`qXK!i=pH_ zr~6!m8;)|6fA3B#R5FhZUQlALw7*&ukZhCPc*=BlO)$^zjmQ4VbQ#jdK_*5A4F;LX z)J7_CbFKCLLc$qo==A$4f%Cn24bPydL&=d(!FV}p?A3Y~vq`A|@pw{_Ehf{~I-e^t zvMsHT*E>wHJc=0TXUQP3n_A5Ii9tAbWaeqMjLr1eBYmAy#s%zX|6#bd{ z2$L~9SaDbx@v8m{V!L9%gj9~!z3`nsr^Wb1H@Z*kUHiW9^UM01aHH+DKYsf+7-$Wq zCtf0;2&K>I+;$1!0+{RvwM8mJWqq{Kb2IiUppbxI?*=XC5@%h1++`(&w(D?{P$)8D(TyKxz8w^shAjoI5x0r#{y=?3k`R6I2>_09r@Z(L!DlWN!#sKf5fLSh$9HpC~H z?c#FnY&OseOWIj?1=yxertD0Ex=*=)gy&uciqWgU+nPKC=NSVTxyFdOXP3Lh6An?F zM*>#|bJZCz{Q7z}f(NGKH1{Xwbgq22o50FS9%;0Fx#YPy4*kKOT5N;PYURc1eHM{sRA`n-Car;$k+fl1{66lFCD|w?^xbp(C5Wi#p2X(n}q=R-@AV z4hdL@yLyY)%>k=5tbSCpTKsieE=6Aj8=v#RWY1GE zWEFiGR3Q%4qD<_=tOR`3g}Q9fZ}8nMB5RxbahSYhMJo?Tj)zHn<<)eM@Ozj=8Ia}i zF3bLz&lI|B=psYVn1G&RF9>p||CMZmJMzKjJlyNFj_J$HSeWaz*nga-MILk12k9=x zM;|MOCLO5LZBrbl#1YaQp?9TJ;Yz;({ml&LQ{qA0=m5L=pGfGz2X-1}y3;cRsNt!M zX9bLE(G*=RY`oU8Vvq`qZ& ziu3pMG?tv)Lw&m8%bcNPJSe>XWtQ3E1&PuL^pHMfYiqJBd1C!W{r6A=1oJlXs&4*L z>rLMANEa7g{aeQyuBa}2{rDsoRgjq01a)*cAv9uEz*;I>sQo=_v{=3xkkA$1ZlC?l z$lo9_Hn2=#b{sxVeo#}ZY&kJP^Yalz8OKJBF#T9Gr~V~0n-~q^sZ-$1EhD&w@@>;e zl?vs0JC26iCVwFJmKy{qnzEd+bOq}^>2jb_9gKP$pZTsZ(bb=Skizz3%Srt-DJeC2 zd#Q&$!$FU$;MEl}^)*wVkft5xX+@vJKaE&~kc1F%tBwsxhBhn{I7KG8QYl~=P@Qc~ zU6{1lwZp{}-d%q=UD!xW-cw|eP56Fvmrsc2K%l5_WECt)66C2Ust|Cx2n1)J>L7R2 z)^glER905%mkWunQ=@%BN-}Hr35s2?P5@yB<)06DKe|B#40Bf5BZhR)w;IVL7}`m^ zZ(UNy1q`a|=<2|dmcV~fkKg8p-utCDnJQzmpx?*SP#C2|c02krgx*odY*0Psr(5*a z;YTD`iT$@qnHsi?Om7kLrbN)8y=ZC0P-<{^Rai}QOX+zzc(Kvn){tc*Vmq^5pOx+u z7HhqnZ`xrvUDb%L%6j(K**HVp!zYW$AorUlf3xd3y0z+Sgx)i<^5pc)wnar8aU{V#J%e6YLDta@3*f z#hY=h5zKtOBNkp)^PsnLzs`EzYV-A5e+zhX532mzHI%V_)7u8iC_>B{F!$wX$sWb) zlrF9b^S<$=LmtQ0`z`{x%TT?W5Qy1wBm1~7c`#btulG3^cm|I;p#n7G>-sWPv8E5< zc0T#L*$yPed_kojP!mAjbBF?AS0VyqKey=-6!z1pX`BIYc?(cOd!(?x$i)>#GK~@^ z&)_twgn^PKxjyQv*2v?I&Q7_o*9p7+M~Oos-R&>{S-GYbV(q)jH==SBDd<3etVktA zWRQ;ZBUz6g|7Qc^vG+V%4P2m#m41CaLGt1=@9bpCKf+5l+JjT_j)`8#R~o)XxE|Wr ze!Dk0;4KsydWLnC#tsyBmAv-{6|J0Z^6@Zoe_D?LUbPUCy9qc%_;IJ5berlmg3tSs zSPf-Bx`wj=X&}keY0B1a(UY7^t$$t_I9?n}8rVE@+^6)Fr2ECH#WRu7nwyobqr}me zz`$)6VJ1f|x+Se)`X!UcTvzd}gvw3&6_dKZ zl#R)v1t(0j8^2G)SU;bUyEX66RTmteRgbSVGXMQI&wF`h_B*FT>KfjW#Mm@>!hzQLuas;2@BeoiTIL51Awl1w${c-LJY|z83$kzUt1xtFf zJNITUDYO}yBF_$>|H2SsWw5JQ=EWMMG-8^%#2t~0NJ=`yPULM8Tm-HWR=}pDBU>7; zt+((PT#K^BMGL1>`D3h-2TGfJ{Qiq3J1Xwz^yF;6Oxp$+M+zb+d*P2U5rObeX1Oii zS)=e9@_h2baBXA+{x$X_d)4YsE3TiTcvjcuNB?ao4~6>|=~{YxZs$U2A1>U^#A0RfQMKiKDI{%_&dB z97BD1T2M&4zecCcgSHv?DYOSCoHYB$2bZ#x>F|>l@Yx(q4@GxriG)>#+-qH*@(;Ff zE>DHz@{e9kUy^ALH2kDSrPXn{AU$q^Y8q%;?B9XojwV4*6V(>igSdjgdp{%j#c7S5pQ_BlSbc_E8W!z zD}HJ$5L`*3p|>MtReMacqK=u|2GOFuKN1d;%fN!t8WAxBR~e@=B&Q|(tIE+;2bb*G zlacOdWM}6{FKriOQA|5rWlK)u-s&_qwPiNby5$P`8f9?(tGQ!4hT+xP2>Ba;#fEN3 za`O;oJH0UB$u@`Xi%QRh^B<@nx0LK%6<09?R^EmR*zpw?Q(wKZD}4e~JC+J{T!(%L z8eV!CxC~xv8Pa1&A^P6>NxL82d{m3p*hESfM(sSaXTAPCIOer029^2_q~N}NZ15*)p$d)lAVlN|^(YF@t@HLj zEDrJM`*}^4%URWw?=ymm|0zvrlnzTj482{WvKZJ<1d0>%uihSI@Vg!>D+aCaD4jn% zk9&#?Rlhzp{ZgBjp$TJ3c<2y$1lzq$Y1+SB62(_++zBA4(*>~a|L#^hoRUg@iM@{R z9Is5$ocey`h9O9sJG95GHTYMuxJ5W6Q##E32iQ^>Ea{n@7H>umpnk#XqL#~SO#pIW ztcCV3%y6LV=D*9mkZ;ZmQ6LK9ILhb2u<_4|_3k(g9=u6Og2Boc2KA=uGy75#KoGl@ z;#-@R7s5^6l;97*br-xY9^GG#Yf2;>1_HXNnnR(AM~SD=qyOv4Nmp{gYV{d#?dVl$ z_)*4C!Gv!)o1vQW8jfLNCR>}x+igi@63ZyB8U|KCc=-X-q*A=zJ^fLypxV#HHT#iv z39ww3rQ;wY$GWEfY@tKEVP<&b$U8S$b;L!hz>5WiY1Ap;z~fY@5PnOBfMu)1(6NHz z>jfcl@quN8?gchlGBPb4CHv!~OgGvsIq?K2m1jO1D;F6I;vDxZIJ=kGTzRf(U+ zK7Hlli02!qmnVDN!3XU85pG@AA*G2-*`Mo%b6)1)NV?3k8fZ*X)sTBr zbKaKP_pK0QoqSn2I8j%tk_}#w zE3P1mkE5}MlwU4=%^J8C_c_Bq6Ls1+!Db=9ZyUUS$gdW6_)z5&W+FX*zt=S3xG-8B zBC)k}y;35+*~eWDa+ti^9;YE#s~_~@KQT7j)0>nuilA!JI5U0vbDr<=W_H34ahOE! z1ek|({%>x)H_H}ajU4It$a^T5iZy7pFksG25J5d($zc4r5DtC)6zh>pt_09pyPFx=0zrcUh;P>hi0cl_) zg!aGckjZiX(4HSmqxQ0MK~W;Ku{s5p0_pTx{7RXzgtbg2PUVvMhstaTn~~y!G9?Rw zfN})2OqAmR#)Nc&N(fA#ExJ5z7e#-3^5ddMwy>>@9Tp8cux&crDFEsKl1uZf8H!4Q zF(IzU4~>{CI^Cb6mQiBR(Q1_3_@uXbq|!L;<20Q2$(4s=z?-jDKOwM%GkyB&MZeJx zrCVX{Oq6x&;66;cZ8XLwTYfZQ-t#@|Bm06BsO6AK@VYhjJrPi4)p>hQXz=|QqG3fN z)YN-P&8?xyAmngF@+r9*?y3>?pS~(2KK1tSNh=l(6M?DLsZ4-)=%d908E z=*TUd=FqhB;s=f&fsug{+PY%NIIbGw1mXQnowwX)t;gniFI2>^tlkCv5VNC9kr|^0 z+925K&OAQZX3d1~u&~=_bWm8e&o-AdTJ_Izj_}P$Z&tqr00b!Utxra}et-0VEEWxmK`>)#W)5}0bmS2wQndaI_{LhH|SVgD0^8*VNhAK>H z%G`Y{2**F}bJ|6p#QW(_l*5{QaE{6K>b3T!@)FK|z{&zs@A*^WNLJ$fIn9l}P!ngJ zv*OV{8igIkv@@LK91!-$W`BpnKJlfdHa^BHqQ^^A0>@tPE|RxwhlVA~i=&Th6jECt zj#ph%d-6*yZPrMSb!WPe7D}Y-5|8-M!+r&y-0NMM->9~e#`!K?X0UNgzZVZcVMe=; z8z*pP3{B3xrM~qT1#lLHue1=y zL4L?MhKi4>asi4qy!MFF&U4KgpHQ`5=kpU+xpMANNqY8zgH*~OGwKb8`oc9mgQudu z{2LkB!|G^}z}P7+G+i`3QvJhlIADRNEQmGdHG|T3U%y9+hBWQxl`^CosW53ZcYHHt z_}=N;w!LS&1nCp;z9a+`<1)O^_vi}X)$hGVpYNw8E~oJgCypG$fWt~G4M;mU4#=K| zK(o~Sxb=Qt4^V58Mhzl-fE<_+W%tRw*b=Bt(1EM3b5 z{EUG73|_?~{{IBV?D7sn28m=_$81lGlYXBwt7!^ZZVlW0fn}G>spYXrB*LVtI}z?~ z-l&dWXLh~ecPd!K5*M`LFzga+e144oql;s#&TDpMRnFXM%Od49Ml4QT@B%<#qm9jf z%T7+L5#qcyT)hP|t3AJvngJ;wF$X`qEH{lue6BfzoG!X&6w>2Gzp0}ASv0-qzJq69 z$1uzHV#_5^&*(+Ttb*44he!Ts{}@_yoKou60DOx)=KZ@{sSvBeA4P~7$q^zR{fYpxn}}Uq#mK}CUJ_`+wri|{&vzCdHrG>V-9KOh)5st!p@=X%4?_Zo zW|2Jdg+bym%A|^^jfgnJFs^{EBnnd{J7+$JF@f{%Px=JuQsq9FW54c8$vts%d~Py? zZiW^tc|3uDF5UGTjw)dT;;?@lWWHNW`>c9s#ywzTm%`fZI&+yT(ejD6s49lF=7=o` zJtv!_YVTvHBAG}i)u^7^6-HUn-7cL|-!(Puf#ugohW}>)_Ef%<`@{j%VV>0!(GL&( zOUaT~{=R__x@^^vY6(Mc;mT9Vki@Z&bC^oWD%aHIg7rcTk{JM|4rR)a)p$mU`<84X zWXuVW7JO3|@Y>G;-BCs7Ea1my3tv%Lj@sIn}u-46iit?pUulBIz zv)E2#P6zNDh_EFoZ4HgvvQwT8TZbT?Kdp(6s*Dag5sqtX;QP?4uh4#L*YQzAo|dij)ZtNBJ2-mwf{lPUfcIaCt0?k_Tou zNW9Dzj&_`1AlvQ1fP#VJii_8)+}Fv|N0QI=k!Db5-P;xjNPPwoE(R1`va<4PFzFxW zvBy!&+kV&;^Kk3CaH&?j$FPsXYn1H6= z;VcCU_NWy^{HxlVUF?{+U~D4RwUcX=CBg|Jqhd3pQd{qefbM|%bC{Y3&A`ZU ztV9x(WT1~De?SLBYUn9y`P@cN#)$tLyU$vg;9#cW)$*%x8(`u zfQEZV;-)f2e>#Gqu$L=;RDvlXg+|V{2QR(@C+X*s6r)(Jw3FO^+XQOQu^MfIt~2CV zF2R99#)YZU&6K6>5q)gi2JvQuohty$-HGR&tl`}9k7qp3>l^fK?=^k->zI!_{o8mB z^603t8y{t{8pB5(mid~~j6>%yvAB(mD|)_H6v~M|!P9Kt0q3l`O#5Tf#CC`81*T%w z-<<g19U_4X$2*NFrY198(ngCZ zFMQc3o$bZjO)!Ii^XwiZIy3pFgSLx~Ln#T(_ti~ewm^+U_3`a;FJbC+m8K+S8v)Ml z>9+0)sfI@NV1-c3tjO2q7mBIS$OM`fV!whP1z(QP?k03{2CTh_GFR9&3}cK*Ku7^W zH0#~_6OY*I(!T3ymZTq?{|AlE>j@i_w8rT&ppi{FPlG6<^E#hY|E2)~TAGch&i4J( z*6ct6z+Nb-%v;fFpI`?)h$Z3r6=n2digvE_J33xt<^rzU-$3UZTmH-~n2$D{76^}& zC7~N~jNDBe_{*r^bSlGZgF^`Zw zx4;sZ4C$~vWhE@^@4_d>B4PP4YSG`{b-=1DEM#zyX@gm=7|xad`&d9R0 zo~t9Iocm|&#pLnpYQZq*k%XA2lQrBROKoRk-_o_No~Kt72obRz_E&+=?4jCf;KF!4 z=3hIEtl0CCnolt27mPNEY3moz4*Zl}&C43@+E$EVWoyNC)Iu6bidQB`$;yV0b(P`T zF=ggm8E!-Jo9`a&W{wxzRz&94Ed}UhS1MU_o=#zjh|=ok6M@ei`!86(o+n(=?)De7 zRd;N{=g+ZhQp4^_FP!)86dh4#DMg6su<^=lEOAS($0<9fSL3X1VA-p;^>0Pdm>4fN zhmOfZI7Ttn{y;S7)8`j6E_M3}{RfO8iqNG+8|8X#vX|9`Ar7E|lJ|~I90aHbmLI*2 za;q4x|Ie|Xp8D~q)b=RRle z>s#KL8u+VqO5v9934;m*Re0@a7_WWp&*9 z?tLSj>l5>=?PyV&h}=g=WlEVTM#5HVD5fgDO3}zaOshXc{Pu&8Wzb4bXZkJC&(G;G z^w|H7)4i$lGB2|$OIi((<64WkSE(*dF@ePw@28(5D za7Br~u(}*JEwZ7T^LXcd?zMSSNyAOElPZ4X_4=f+?3Ww0<`K6_e0l(&6)s}K;7BO3 zWLh@5M*=`c4NaNkBEN@4vy^R12K_Amp1g$)R?8~pytlf+|MboSWDev4q5K-(T zEIYCKBXBP~;H9g7f8u8LEj~v)hZ-g?UJhsh@KVm5{n)pR{&0JLif}uO{)I3}W zUDTgf*MwklD18Csa!1ER^NGKSvz04q zzEk*QhUai-83L$Ms^X-{yMXQxp3u5J+&5kOO$y+^5r^jYOBn z#e+!58;=CAe4$$WZJeG5b!5UfGynb?`k98~&EJ{cQt+OxC`GbuXnNM0W3R1Y?V+?> zTwR(Gs>S+FCsu*J%WuEcE}l;T^iK4WNz%^A;)z?)!2Z6qQ=KL=Shh0CYQ8e8tP-pB z``^`H21&#`&hftuPEm2sKTyTb;Z%tpz6+uM_500_Pd*0z|0+94P<^e8%KXY{NpI=& zj3CT~WvZ~aS%MI_ot_cs} ze#@ly)V9**1q&gws=WXHW*t8`IIR9Gr|f|yc@GV}$`%h$#9MyAG#B99V8@!;et0K$ z!yKK^CQ<2vZgrqj?Yt}h8PWAwov2cx$7i+#ARV|oCiX{pMl zvM4CUEqqvO*)|Bs{J&2=*?GQeY1=H!Pv0nsSd?PzX@WU%dtYJO}7_(QVL%~%PD(7k6rhneHU>zWpw9cG() zuDb8TsI;o8^(TZoH(h!{BdiZ06m;_2ui~vWEb4yc9g%C*Mbjwt#0pqRbYVuP9Pr{{ zUr-J=inV-aba5??^INKvi6bMbcr!$h&OB> za+7tiIOcbG8H2hFo=QT^t)ExcJ@#Mpv?i6Gg;e?!M^=yrfaM#!s-y<_81-7+Q3kU3 zpfQ#eLk1exiqC=={!A_8=R#UqJ%K)ywaC8|YB-a>rEeT3zt1i8Dzz(74pWzE%bW3# zYYs1P$?|I1{IzWPUGU7j-ZJ_rfV1WSVjIr|GI<|!!#`m$8s+#zQge%anCkL{0r&1z zB~7k_?H6Kyq4Ob5ap)iL;9RXdS?{3>V1xJwM`R%wD~mr3Qlb8U3FvecWi*Vi4lz9|cZbfK+CM;#DIDCh>N zZlLKoMfJA+bMo4aQqM3K@P6I|UWC@obX`w-7L$>+qC5IubY%(vno4qve8#%X-k9}jxoPA55vYYb3SZhGj}9)Y5SB_xRa>u;qyngBMJRtFkQd6 zMP;Jk^yTaF%a>ZLffGKD3X(gv;#CI9W&CjumV;9bwxz>;5xdu(0@*0Q4ykdY|0g7? z9)9H>X7%9lD%Gblg{24ovZPpJfuE0Z$d}r}FzahVJqz^7I#Ialdt=X)Nn{R&8wIL^1{yK|y;>`axi^CZS zHoi0`qASANE@v3-2p;k(D(WzU>; zr|3t;&VMJrPe)uxQvBW!#d!Cy#w_0$uD2*saxeQEwMDTCKS`u{Ub#1~VcD#9_`R)0 zS{cFeCiiS_&y0mHlSb`MJNR`k|1z=5zY^o^(odl=_|SXUha7;dzNXWfvM(+-HYI^X zukoR7*HiM5_<3yYncVVH+=C$S)AXlJ8_)o+{`^PZ<0m<4#jmrfX;0fB&3C`gJ)Tb5 z+7%z?w6X(PD`VlghHL&VB&2~UlqFZqp3a+VP8}%ZjszYg)`vrgF}9`hDGc`3xq*abLRDJ+ zAF_hUA6RGJRz2KPWE^Q`+jq??y}c9Vn+~l7`+^7g4u_Gjy*wR=C>L`;JD;fuWXM#m z!v28y42++$&n+-wqq6LK!~-Nu(_qgWXDr_Fbfy)kV>jK`Uox*9N0|`+s5vf2kYZwA zTQj)}FFv2lgojeR7q#(5r16G8pKT9SCYR>6%~Wmuv(NfzM3q$J1Lufdw-*Fd zeK+BK)It_rU{$A(7_b?sK8~bH4kA)b%qk!0b3>1gtp4Y${^)gMkmkCM z-ukaA!Sx_n0!JYl6FAYg!fb)Z2e&~cbz_>_`j3o|2`;`@9vex6Df3Gm=VZ=EZUWeL z)94aSct6}E zuIF?)SXI(w%~FKn=sr;QZ&yjFa`Lb%q^138Vog~OD{Hg4Q+6oXTNxGjPvl~i|D)@c z8_@JfX)QR#h*xG=df={LIM(D?n{XY*j@x!QupTOMb~9?kj~o}$T`w;6RO>Xh%9s?` z&Ao-3Z@m@e1h*1A9`*Fb7zZU*l5U)OyH55CkD;$kY34w*-Ee*D(QTZ=IifnP%VR$$ z*EXrBtE!aPYkYNGB#)-Stt{4W!dlLG>RY6`41BO&UVB8T*~XS;<6ERAD_Q>iMzP5) z>IVA!U#I;)lB0oc&u`zFQhywNIQV$jUL_kLdu$=S9?69PSud}=;68M+CDmFC`q*g% zoppR$SHTSwMR?(N9r5PcA*ElTo64y-Fw;g#$=rw}8I`zb|5RKwVOH&B6E2LrvRpGp z|4dwQ4&#kSSDdGGkf6w`1&*-FoE(sGaMq@>o-@DasG!@*{c`Wj%zHCJ25{UJTuq( z%PYx>H(__)c?;7_c)eg@qv*5IC z<2~QoJbg$gb97xro2rOddpCjwmr)D*i$guajMxldO}gs5wbqY^PoQ z@Z%B7NUgvpcx~O)cCpXVO#W1hd?o`eJWe@w z$m+TS)Q#AEN76WOtdP2tDj=H3M*Qa{NC8erY)*-iAB(3`7Z{N2a(vE3oKgc0<7zj`^4p2LvUKqoG zLo6D6zP;LF+DKcF@28}%$`6 zy#7&jjz9S2gGlrq?_{}>S$0Oay5dJ8h;J!tjid9>qiHy(Mffzyt&pqRX&num+|g_q zeNriH7RmW-S7c>Bjq&9b`F8z)pib`P$M9JtmLE07L0K#wmM}UTf9bR0zZ~_oJ^#BF zZev8;F=6p}GPaX3j6sAt(OZSt=XpxpzFA-(R$Ti$RH08KZkrC>X7MnaQK?MOq485y zIWswO;&&q()0^)vMe;ah_%MH_Y?b^Oc;WfzW^X1;4YPbOhWQxq=Rmrs&zf!z@X2l= zYp%nEOx-!cMWpX_t3Epg9AkY~utEY4COi7&MyOiGh(`1p*=hL>c13RDO9`xb3w;fi z&g12Q-_bBKdOX(FYuvn};nPTZvUy~GnxfV<+v0r@?Xg4QamMViq2qbMVt#1Db4V$x zG4vf~V_nYlt1NblL~JPA=49&gPjv&vm2A4z`puti#}b-lKD&$jmumi0LL4LdyxBqRKoGbHj%u@atV zW(0HM;A`J>0bIJf*%8q@{37>NB22=*8yTPhve#vkd;etHE@V9(T)a*|U-TNh{+>LK zuS9RX=Cvj}dv%?*6%}yu>Jz5&(`nJ@83OHi+eyUrnrj2NXd*nHEIb~Q5?s#@PLf0r zm7A$H4e50)dvS?*3T*F#`2|et8&)<%p8E4|f4h%c3w(Ux{^=f#~;{eGT6d?iOU+xG@|2ma6 z>zG)i?|x~P$FbjCfM5xgs4_B~AEi!$qJuJ|>+Lu*9oW`OIfrXDHn&~xqT-q0oe%{$ zFCU*N^qe(Pmc3AjDk^~HEKns*X^Xnl2}a=HE7J3-Tjj@vY`4iVaZIP9&`a-zKnYu4?wpXD`Wy!b^wqX8kaCP<-wrI{SqCDs0} z(?0LTnRAtiSnV7)D;t?`+l64aJGq@JSG!4r(-{|KkQnA93?uq0`j`l=l;*C$+m;|j ziie%-(FT9D1Y`8PD$NIB;>!YVmq4F2P5kAsa7Fz2i+0fn=(~y~gyKokkIBwT%&Y5r zGH09eX;Z`W=k&fTimm-BZ@<|?+v_D4MKh=546rPVZnJdRZ1(KIxGC4}^}TCaKQ><*^Qu7iT{Cc%NqNmuc{rA0JBpMnp1clBhW$B5aL z?5tuc!5?xxeZ=V%gre*JMmR>RnEoyZewWPn7|Rti-g{PIr`D;YsJ0D5lbDXAb=yl( zl=&Ew?66B;z0VR&!%lWLMTS+k9V!0849{@E+ITyE?_h}|6yvl0X?;r+R~ce2YviX- zw;=Z8>9PKOxX~zDK)Tpy!it_vOOPpQL-h=-rbXIVbDg z*XV7u-XA9m+qk=vu3STYvB#I1J879cDJg%Yf7mr+7T&8k;T6v`c$6X)10Bnx!leZj#;JRn*2iB=GqUi`VvN;7B=jq%9& z)o2w%@OL;CrW9^4*q0`D22)I@$Q!VFq%HrQ+!r+P^nm(+n6+v-*Yf1^ z>I>`Txu^56(Qdo)7D?lh343#g7rb&t&dw6}jSg%b+}|I5M_6mtUs@SSq=g?VW_+0W zDVz7<^QuHFY5ikWxY-bvYbnjRP+t^q#G)$!Z)#H86 zQSA6Ss+ackRD#1Xfp!+A2aMxV4j8}iN z*V1O1O};|RvPPVzrEZ0KH(;^ZIc{lbDcAjsPwsfO%4GCxy38xC?Y^mPgV+0<_cmMP zj{50B@i|uS`BE=^9`|hlns4-EQ;)sv@!g>lYKk?|2%6sA1?7}mqbpb1(6RIZAtd9w z94_mERuawJ2_%GR!=Mx9qd4aH4H9Rf*1 zmkB8X(;2!|y}iu%{hi>JKHJHl19{4J63xskX^8wgF}lBdV~3aTm$zY$NxrNNx+ zus8qyk{yGM*~H4BU!x*!R^EMUY8JfMGh-D;Z#`RZQGLOvJ>P>9|2i&qp_3-6je}3| z-D_&O-p+CzBN%`DhE2m|68Y6np{NI!<)f#Iflp+2op$Kvx7PzVUM-W6G?~RoMwG02 zkU4X=YR&bpb>P(VorS{_7Y4!zg`FPFy){O|aLB*UeDC`GcHD$6#>5Vfk2y$6A|-{Z zkQutkHjLzelUVQ-iL+$X-IS(a=pC8^(p8?97ZHbmi`G{1b97yi5V+9|36|_L8^dK2 z!%eXXBp}4yuKTB#ZT%`S%I;VSB@nnc0VhdQdjY+9Vt8F;OnNSR?QB7FAl4w|8L!P@ z38{&WUsfNwWQ%bE$)EK!jV@Vdm;K3AvTlY{-xm-91Jc*>F8muz7(vB-eH=lZoq@^j zQZKYq#D`z~zZYQE$P%#3p*%`Ys#e==>%H!+wpGx&*nh3=i>j-U&pE|b{jyhs$BYj< z7(qFR0hQo~Xo!-(o?(ldHw!rcQqq~^12SpCU#?3l6**2ys&Rw!dE$<>{{U>Y6pKmW zc#sWHo^3EFRBv?}>_AlSn(4PO=ja(nBMAFb+k)C| z>b5Xm-D3BiO4uFU$S?Sa&!_HCYIpzctg|aIW2HfXAbiZxSJMG)uu#4?Ox@TtnufxC z38@>?N8zEzf7;tVlw1J+^UZF7c1JZMQ7S6iramvB2=wU_yiQ5ecF(X<~WP zrcAeGz?QFzEp*Q?WHhN;JKW2b@B6bpAJz!IhIQ&wJC+JCRhWX0UO0s9UEERb^2P9A zN@nf2nvW#$^f3m_^xZ;H)z6NqM5B|UPjHoUdh2PG1x7x?<2^k_VF%fyZ%`T2{pRQ; z6kcm*Xzu3Rml_N_9}6q<*QH65<(#!Gu~w{N35M&S3?#Yj)*a=_-LVr(+f?Stb;7<~ zqxG0IFMpL*Hc`RN>FMl?Viv3afa&Dj>k2ZQx>gBIVoPrEF=9-y;(SN%u~pPjme$M`gWQ31~4A(0?}@5e}#85(??U!|m-a{&&z1Dl2~O?hYYhdbYkB zNbST0evnRXEPPFu@1N=o$;0oIf(adBUc83H^A553DOVXVGfaPre-pNS3iLAZ;em#G%P{wm>G7Pv5dc8waYEJZHp>n%NUk?6rf^ceoiQn*Xih1@P|U>5;)2B!Ui zo-6|a0tq|WcIt57z0r*|z0{i%6Uqd}AIlx2I4*mF6n~o!^j3xco!Fi{i+~Pi@i2Lr zs*=Kax$Xa}K&G}xVGR;~&OyFOj0o@!GGkr2#utCGwIrgo&CgZhm2fZeFA-l{Jg8jR zJMVbQTHe++3M{5y76>%3pVuVxk?DDzsIAYX?Otd3y7l^WObq9gwC$ACu}MexEGpvP zxybW*oOhAWt_KAfw&@&yxH5eh?Sy!JVHcFoh08miS47{oRziuw-VuXt2#;S_^|WA1h60 zQu`-JG#?+?JCqk`4Fb{(2!F)>cew0iA15?q^gP?!X5vF#OApt1lBwUOpE$w$3sl@F zuJvP`gatln)5ek8rUgd<9c*{Xv?TQ(H_jyu_L^2|tgpJ93?e>Lb$BUb>Macy|MR3@Otco1nL^m_pO@T+_$mAGw``elaVE4r zPYy!(c0P;=O?u*VrDAL957GKpHUeX`gh~RE-rglNeD)HjK%eme9XGhR>+qGM3p3Nc zNCSNy;=?A)hl+^n@TJIm%RC&!||4)X*>`eTK6n}Pd03-O-G%j~`ck6l;HIcbX!M#k{@!wxuB^<#Idl!H$*wr3 zkXr%ys;PP&dQib#tG4|4VhS4!<(ELBaSCal6(i}22FdjYvNN8XC__V6@=F*6vve>q> zeqf9=n)gp->Jc}am5W>m!CN1*CL=RI%yU2(1#7Pp^J`i6?6l>dtxtbs{ivHJ7=Ls$ zO^Y*$C--7WV|j}>zG_N43@=F%FvTKq#&Z(e*V0T`8k`n?TC{{_|4_M-#6%_`$+uxL zeEXBgHpxw#f*R*-E@=W)G2SCB>=8Q;NAl0ALe8>f?4q1ruO*>7hkMgmVs_D)6dSna zK#M6q`_Rhsvc+y4etE1Q}^N)HU@$BnI` z&;?Sl!#6TMItEbjjY@w*&2B9?WkxYEz;ERT^O5@K(|UB&u{WXl((3F zTO9T^JlGg%WG3^ji;LVY++<6|sk6f>G@$6K_pvL{fq$b}$j<{3Xa-mw_~kWjHo+{R~q)uXBWjOX&=<8gz#J2Mkdy>3n)ysw>oH!^QA;3AQ>6t&a=js|_14ja&s zhl@|a1&v^p-x#m&Uw2mb%D834@+FDfjN`OMM0g$=K3v&6^N5^tiga?03U%5%&zsCU zb8jlq7*(icQxHC|id=#cSak5pOo&b4JXj+!C+1gz$)P{JZ^TZdbTCKofogKHM2GCo zaDOt7+xR!tU;#JMXT92gmfu1IJ8R}>rtZ&?2ZQ{9Ahk%3GQeVl=L#>7v_A^T0z?gY z-r1QsUdlsi$gaPW?857EvYZXR43Ke0bI)fJiE^gj;9;drV>_?4%Yt{stLmklhxhL# zSn{q0UaC&!r%OetwlnMf_M$w`&*td;#1sf zGq8^@0zm$~k1hrWDftx+sVN(c`Wlp1UI~5Zj|WDV9V4rZiUa8tWnpO6Z3b`z%n{~SV7a;tX^?Cg{bieU9ed@J7oP25R+K zHld(T&x|vYgb0>Z1g5}%oUSc+J4>a9$+res}BFtx8XWJ3j(VR4!$ci&Sd(NQfxq0`YHkO0z4|+wx^z!9KY%n|AZe1P$KS z2*R%o%=2A#5u%|`!to)723=nHb~@sbqwTIjFKz$qVeZ89Eo>SpgHFrJu!#wqyzR|z z6Wy^5l<_en;H#mtzvJkaZBymf%&7Lp%RS|hd=yimysBF0=Ot;vwBh*79Wwtjs(v1u z(aK7tWP$e8YQ|*txaEs?e;5#s?vtwjWk2y&EZxukkOm5SWeW_Ej-+4Bg`e8;l8ww7 ztN#_h?W!U=Sa(?G`^3xzM)sTwMbjk5^JRfV8Sy0_D;f%E44Rx+dRID1-KYj-v0be% zY78UX34y+GqVEg>=WhM!tMO6)YT2J6@9=nPo0zlK&`^*EYBYW{($xNi<-Gs|Z|O-p zkB$h02tK*r9oWV)RGsX_Dvcgr{cqr#sR9?$@F2_ep&@+q9rtiO?e&3tIiv?YgUCri zqAb@9v03e6eRpF^V85jq;b5|3G47`O2{O1c-^HaLvnj@_6YWHO#>94?q!xFQrT<6E zMs+`BH&4FI;j!z)y(rRHqCmTJwPh4>D$ltNF;r6P5uugFNVE8M4!#l;YxKo+8_%C^ z{j>07cQ#U~23hvRyuY|de|&);p0HK7K1hL=xA2dY+uOCD`aefn9` zq@Ay=`kmt9(^v!e3VsSoai0|jNRtu&?fVTD{;QdCp&6M9_il@>-r4P(s`$gq{q{^~LE)W}n7Lpv=v3}g4}|XO7zOMC8?(fvl72Om*gk+! zsU7~xgWuTUzr$*a`tbJUr$}Fg^rcA(eS%h$C-rSTKEY4Tw;$wAaNB*uJ8`4C$lQUL z+HsH^m8H${YxnmGp1{jrnAS>1xppk~c7&>ulc8}#CMW{V&pnzGTh}+pO&*Sgi>A&? zk^v}O^)>GmO1RVB33?q^G&%Vg0$`=Sle8yGAA@zflkTfn0dB!Wyl#g5uj;zGZ_?b{ z9@aIT!12nYAw#Uo;4@|%Lq5ro+5|i)O4jD7t%b{1(XScvN=Xk7t8ae0*PaRmbVkXD zs04DN8xeNCyBG$^m|9zvY>tz}iZTx{^@~}I^r#{Qj_)s`GVB5*zXX)UD*aq2{XGAI1c}nQ+|xc^uI=A~ z4SQb}htfhW-fp{B!@Wdifq0nwGVOQLW@)5w_SiFn@4~G6E2jt&M zny=IHB*=VT>+q6BzF<7C7z&(g7)U&;YGTfMIFu}F!iJXDIh#tT#WJW4QaA(a++nqq zSaPEB=lM@lm}=n0FPhm??YHvyw0=di?#e|)T*H~#*aTvGSAvHzc;c!pr+n=hHeqTJ zCq9v`DJc6wSZ;eV2??c#_&4XYVAbil1#{b#TymhoG{{+VqY5I%e1*wvICl_9#}52A zowO=aNQTMnQZXCvi~LGeuprS$>RBuWm(CY=8C4^OaURlQ0?NLtP9bQBT>r)`z_yr z$pKQX_r#v)V95%qpA!7$oIPkJkIZgMGvHCdo8$tCbP^iP5*ZpBeK_ArfRy1MdmDI7 zY4u^ue2E8^B-S_xQDPHH$T=TZZbM>KJXsN}_A1hdgIm$^9^0Mzr3jG4U0a6~zde>L zYr`<(DBeUO8Y!J$=82Jo5?|uvr++5Hito`TGH|~P>%QU@)nz1z9zJHM@O8T#pzMSO zva{HA_1j-zzT2iR!c}{XhO{asaOMEJZ@Fl{WDTIIS44T3ZJ&92yx^oXkXXcf*Zgl? z-rv`a+!6*gJC*zxN1h@&nf_PrMSRtCxZb9 z?4Z5~&~EW^{Ah*D(XEOsmW^FTCOokS-W)=I&B&9Q9Kwb8|4IN3ivoD7eWQ8yD?NwI z{3Nbg6Cbv~2503rV_eBjjt5|vo4cMqnNIq0eY{ro%z|hXA+V>R4tn*jF`&O1oY9)J z9o|~KL}-5syOWkkfG%W=KL!e?9ojp9TWRuBz?x)jAy*MELrLX!Qcg4e$3B z4=k6r)CuCi@@zFe@i7J<2KQ9T6?d-)FPkU#L`zy@Sk|=T?j2*NbS9|l78L9ugkXN6 z!|+G(qCi@FXX$(Mrl~aBLUH^ej7VLcS79**rn)eOX_$QoV^NLb=fz^N97f#<+|k2p zcl*i<#@Mdbqyu4;TP7H|cxMMejhjhfHKf>&FW}atKY0!1l*^v<}&!T5|fB?eB-5&eDJ%x0IL`M=D7e4X5je5bl z5}Is%%DtowJl zH@8V712K+ePu#SlgY~~&CBMcr3mP)V0FNDacQUezKY~M;3&@XU_4#3dJSSPyoj6e8 z>XDWY=(#|oLh+Dtw?Z+iM>1B?e9tOfJB(EbH|5~Hi_Ow!Pa(*6-R6l-&U1biSEx@O z3xy&42hF&7LK^IUZyVe*@r<+(Nmaly$j5V|p#62$p^S|whU~~Q&LmdS7u*QIZk;GDcSB3c)B@+#q zmaC%#G_(}MsYdi2o(R%OEJQU@e*aQqw?Fi| zWp;s)a}GrAXFaboy4lDcce=QqMtoeHaf52XKpK(nIbuTcbBi=*YXqkt_GQm_h9sP( z`NAGYb~L`LBKX_alD>>daPPvGEv0xuva$-bYfUwk6wMd|8$G`7yvWd>sod|aXg?Xu zeZ-T?S67dNIZl$`lzVy?goY#%i%9KVE1LX#+1vNwmXf@1@XFbNB2R4Jz)(@si zgC*7!zh3325Li3id%=!*@!fB1(RmBgS!A|5YD-)R(r?2!t)Nv+ZdDN$Mj(4gtjyd7 zroiai;P1CWOu;gVWZqEq*E?pMdFymBgc6}HHsv?i9IyF=eVq@qFq`fPBv?qM;(a%` zgQ&d)+yqWVEV*90?<|CUjE0X}Pb(SQh3z)BCrzRnyepsmFn-BNmaQ4dfFTJ&gzwdF z!ej_SdA5apS3C0i{RIXHf8Q3avoC-5)IY93tQHfpl-$Hwk~SUc7G#c26;^R=n5AzGlxr43I?TpA1fmPax9siV zavac>$oeT-o}z9r=X1yVVN1s^i0@`yy0N%Gqn7syl`QNiy6YnM-J1HzE~7{&!AN=u z^&rPmr!egO2FW_z&|7pdB2k9m2^n@T7&Pcit0~fHQgaVweM%F>mt~(l?Aw2`Ea73J z_%Go7R3fLkp+1y|ybw`J@eKhI!uryGFd?$5pg5MtC!QK-egKkenf!Lg%HNlA_S$ob ztCu~PmcbXDRCF41AK652ekc=c8jAk;-@gBi0OJx}dqcc#2I0!6H8OKPg~CQ*JrSrr zOl5+t!0AS?_tB*xFB(BIXU*cJ#41T%Jg}aUx*1fMJa4yCW#neyS~`ohXHg~iJ3n{u zq4cjp>9brEd8i73DmC$CzULny*$zX7aIp&|m2Kk%2MCR-eVeYlke;ZGWUj6IGqH5pPUycNdjSBKwyd%q zWkY|mPAtxtA@lRSPo{;mXESF>?X&Uq4_-U_U8=?RTnL``)-nE-%jm=KeR|O`z1;3h zD!vxTg&jdC!hz{-%pk^Od65;KoN6HZdHDD>j$wOy&I+lm)o3sG`M}V8ITQ@F(K0ICZ&6jQvl;%T7CnIFPOD3Evds>x#@}(Zc>?_#dMHk4S^B>d0i+5 zn(>gBL~vODgb`%b^rZy<4;*f{G{oDjVm`PQBt|Z4J9zd@2eH+UWOzP0{2SXDer@fa zD8n|3>~SJv%*pn0dgIVeLn&DzTvTeuPPneLs^LI+Z8w)DK)x3Az)9F%Y9d}`^S~@c&*80_lnp`4~X5uhM zZa)@b7xtjR>8n4LKeK2scL0w2Oap-%Fr!o6n|chp4)gpVv#w6YYpdC_T&4Ncs%KbIe*s$iAN*We2Yn z+b>?n=k}+(4bC$ED*q3gojS`FCG*eG3}~%Z_0qAEN*=$trBn@a@{Qd>Zd2n|I1 z>C2cS=G*)k@o3`-zK)Y#%P{gDsi$TqWww24*{`1pKp2=}`H@Jjg&inC7>K|)6ahBA zs!)9)7zVs+rVfOdsa+O(+xq^vx6J+Vw?tplWm&gWaP<3CJkucFWMu`I5>L2aAmH}L zrL8<~zC6j~X?!&g9h;R+qbyJpDfsFWKHXKMcerM(I&Sng^wK*$gassGpsUV~Va4zT z_e})$UH4CAlP@VXbtpB-P`8SotiPc6pWCYMMpERI>Qi$5?N&|KwFIJgCdv@;mf@g@SPkH30$cn5x2mAx?LPcUW*ZalqtK!F+34>6 z1j+w<0jgUXFoiJurK3Z)W)w{G4 z(R01?vO3G0G*wQXSGwoxg_*rdmXZqAQh7Ktvvj34EMH-g0LCHlC6r1|XZJVIcLJ7R zy7au*KTsbt7{N?nS&v?Tp-fqFJbyIk9nX2dI;UTId8OMY;iBPk7x#0Xu1^B4D?7%GdLD_iNm6mkhJ!);1_C>MkC>>Rem}4AAhVk)$o5Ndo)R;G zos)(2{Yw^Kw#*+TqtOrTl(kw?(S!z0c_034?I+iQX#EX`Bd_8I)du;a`V`Ylav(Cq zbc?$vK&3tj^9-$Q2EP*I$97}*!pb!7He8$NsWHw8_*59r`7|@l8VVZ2!A!DPl52lk z8fc2Pro`=eJ}^aevU5*Rl3g-!BDsR3ai|x6z8yUMhqh!`{8g{jKFN;?%`7$~*r#|-9RQQX<-4A8KeT+g0iRl}ei@A$u`riU!8~n>V zmZ+bvML9m$6zdY9um{HmAC=Rr&1lY9zmk|#^8E!(9JlNUU)ugLM)M6(H=K<6gSg3D z16v}kWH{W<-9fGpeHsyC9YB{@A_zRjOj~^2{Xs}jn1X7m8VA7(su9-V1bR0=k@Y{z zIp%;IN)xp7`&}SJ!k=Z(6wW}yPsFxXHdE&eiHWr3>MFOCLvDzCj{2?cIig)t!7lRg z6G_OKZ1j*m7hja&wb;Ues4t&vLo07aoROtf&{-GZf4&5K0%Uix zFXVSoAR5+>i9>4N$Ci5S52U64czHX`ZzmS>j!uMCIv`6{DjB2*<<-8LM#ToB$-Y=% zvl%pzgQ`B1--+eh4Q)IS+EfVtqLGayyc&V9jHgT-tXF(2@0&Ae<6Ejm|C-5TOoA%e zDzwvPrVl)ZOxi=aQu&DGIe)1xc{ud+YbfAjB3p7LyT32p_6!RvNG!R%uLM#OU;Dp+ z=e>JRpKQt$@)gr^$VeQh$-%Lune*FRwnT0~M~wSAJJ(MJs^Vin1jD5g=&$F$I;z-T z6I}4FxL9VrUD=L)TJ6yq1I5jsio0!;6Rj=#C^uxjHaurWUQiSYxy&%-b05`zZz!%9;oR-kI-hkoQ}@QdCGG^Ep+bKk=cvMVIJMmAR{gVuE3@=x;hSca zv2u(ENf-fXWs|tGwFb7eXUG_Z98t+eNz~vE99m{eIeT~$tW$zS2eB)8tumZlX#EduVQN3 zRlcO-#vd0vn@kz$+0F1unwKlJJJ=lC2{6P!6LDCj8^T3kz+bd`PdQskVSA_IV1CzF zHTf0#lg#;*x${W*EH3x_@zaDn;A1-VSX+|zXVl+^BwrIkZ+}p(#7}i z24Cqexh8Uv=qK_RCxx6dQnZW;NJq;Vx+jRblvQ#;^IM<48#_<4$t{ za*fkllgtm>iE_3o+tD^rm zrvKzw$<~ZIPq#WHcK5&7t*OYKF!8~XrD%)s3*r#%lx)9~ED#3GboL)N_7M46>Y@u? zp48vLq#WLl~+q_`J2UB}d;-Ddg8s*UDR!0Yxf%iUdDr;r{ zYuXwPc5lwjR*0%88rhO#R$rTTRq!hVt|o@FubK!!z|1jcRyMOZgBhbgM;#JCQ^=>L z%8!TMs2V6abmqb^`lh9KEzrP)0v%HC>np;7j`(-1->p1< z@0ot9qCKjMF(Lu8t(x4J-?^^m@kk-A8dz8w&av!SnaTz{{pzDw=dQESYT(di<4DT@+tWyBD?6yK ztxLfC(2a92daX?8sMuk6*(_t^&{M<-m^SPZXk><0+GlBt0N>ly4hhH-2KqPY0IrQi=&ZW@pHkV;0pU1>pVr4Q zRtB@tz5cRfZ@u)xd+7`?j!7j{L9 zWbSwU_#RUxjgRrl)bapVO8*;!uuAN=+-Mzm9Eb^=^1qP$6vHa@PQ2@HagvIv8+v`h zmdh^Ey_UFjtu?1BU2B2MPp3bH>aK;6Zzc7Jol&vE8E^n@s-y0cSy&zBi?&n{yevtO#RNRVf*c19aQk;dJqe zK&3aquAFwxFJTez2${*6_O&N zD=#QS0wKq_kmwY}@|bs7mZVvMVHrzOvASua>c+}a;Pm|+4>6om zoi)k}M$D2Vqnq}LooBK%CK&aowRTR_VB7?z?J^o15cxxFufCB?Y8Aw!A{-E|hSqOKgzRaBK{(l2d%5Q|w_R)~xwO%kM;jANF75948h@iC}UL7F7!xfcb`%@}80e*?6H3!x)(qBr$b5l?A=c0Z!W}kfe;~U+QxAU3IMScVjya7thID zzS0wm-$I=-4o9S=NsubsdvR;7&g=UT*KhW@X?>YUnWrGmE*y`@@5XX!tYhCSmN>*@ zp0wnn8Tte2Tf0QTaJnNbN-8OK0G92{F;z^<1xY%#$!)oHF%7szl2wxA={+{7W#6j8 zW08wpuG`om@;5WHJrwVBH65?nCJsg$XTyrBQc~WrG4m>vMNT1$d+9_0 zdZLd}1zFMXqs`e2X%bJnplL2qACGq@X@O-bFxKEu7q-!=rW1@W6iq3J;sj0CaUC7i zG%*d0DDdZs_f=c*P2e@Qj}6YVpGQ$O!YCt5WDL{b%&voJS>xX)^!h%%L5Qsvm7Lx* z4)L1p`5R#&KpzfFh?$c+x_uPAD?yTf+1(zWyixxLAmSo8a z1vrc2*sLAlRt(L1PBl(fMM7`AVZb|M~(wavK&QS{hH;+g>vY(;G~(J?d`p%kJNSFUQ=k89Im z54P6^W$dvv3GD^~xI9bi0M2V4APPoX7X#H`yc(=-R}(^jbLF5H?qps%=yk@m^>mYr zb3_d+YFV;IF(pgt)HTfsoN~N-G!9^Jl<8#`+0q4@pTg3(L>Q^xciIm6gQ(^anYYW5 zg#*|P?lfoPNq}L%0A}OldKV|x_hDKV(j>v@X&-m)ULcDD>^bYv8UPRnXYHaqrOtqtSTocLtukwFf~oOyWwYmtYuj+&t;PFlO&amgRW;jh>R5;;Ywm z6Rkj#>>5z^Xf$2*KFsFc2QY)5RxE&Sdmo^zVTw@kaHzh4dVg%MwRLn`O;ScXLCHv2 z;!raZZyu*|I2nRce&uomP&P2JUg$TCLrjL};JN|F@2q{VG{gLJ5f2ce0MiwV;c~HR zC1RboO%7pKlB7D?k+QC}r8$LJa!O352_O;#W7X|no@|_7;WQ>O9>++N1eRsO_iTg> z${Ol#$j&-vl&U)SuJnURPLbp~Zk+7l+O;kWQ*lQ;eAH8@fh<7B$rs8Q>nuwXXodx^ zy^qep$$~&@l7yh7KwhR-u45oCnw{N8T0gdSADV8gsXwolJ-DVrGt7<7`R{*03AF0| zzukOt03f#ulDru$LATXi+ZO;-*+2>bolA7=9H-|~4Ei%i$hn4FCtans6EXAyj^hI# zt~2}2q7ZoPjUH^hxHQtF$a54Thu1k+35xPeJp-ogZLAHOwpVi`i=x1Ec%jC;m$D$G z<_%0oJ(#wmILx<{HQe?-;&8IFI4&(w9B&r=!Mw%c1VZF$l>7>2SoTheIdL#SI32-q zT4fn((Jb44Qwh@6nJfx$qalI@)JoWd=Ae{qX|P@XwNlX<0pkpuYe;HVeHC^(a7+XZ@q0O#kk>rENM z$@MNY-9o$VpxvHjHd0Ew{zeZvQ)Q4ZiQif&wQP&(vm{n2wqe0`=j-Lt06$LG(iC!zM~@PFkE!d%gvG|2dyy)DpOqah5!hz9k(!vSmP_6r7^;ZqLbWI z%F#`GCkC!u5R4;^TQ}O^T*JN58+dd&0!NIN-K^-bi%BV!bk%gUl9@14AWqb^Hgs)m z1ih&Pt{B@c6pm9$n3e;#y${`*(L`2}^RV{_`$tc}u-!(!<9|3%Jj_FDb7^D#+#Xlc zZ&%BbxMrD~&z=m^TB&I=D$%xcj3=e2XIb|rgy6=>9*zzcBdR<1`hd*fnMGp_{4yn% zC>SG&g3=+V>}j%vRLZoy#u9~U5-#3*2?EQq>XJ&d7Ky=1>8jqP(HGSse;HWaWi8KA zgyUhYExC(bT5qznBF|KbQ%d-q18BOnb2jm~CZ$l63)}|{621V}DzXewFu`Pafncoa zxm+_~yDeC*56kgZE)HWH-^%`E>yGE;<$-dHvS6@nwdzj76gsQwtE?g2ZdOya4T14E zL=XhfbpywT9wt$Oau;}OE8C`8J^LPlQOI!XMjN_r;Nj#R&MroHMgJ^3 z|M3*ZEA^5*&sLgtoaP84bq#clAzw4BvaUSC7)M%`Hx$`bf+(0E824-7{k(GyrUP7@ z-f4{Hs?x^yc0YZo^V``yzZrg9s?@c}XW5f(+Kn$8DW?vjD8{`9y?R1z*&d!MRgbpa zyog`69uBA}xXJKBO}9d9WR+x`qgbQoDFs>K;mEQKqDVn0gWowo_vj|P)_$omNy_ik z(C!{%+&|k{{%hVSp`}9mch5m9BN+D;9^cZ;%h|9_4wjo|ouSDqZc ztW~%Gesb*L>|DvVE5X;r8(-v#7Edv^U6e#R25hfAi)f`p5MK=!7^eb;sR-kfB!lCq zBWsG-H!*{GR)PBu$9U>V9iHzYj50(?xR#(jm<;MM=J|S@VOm?&y`@xx3OBB`VVV}s z!iP9Lo#Nd33Ph3PjNFG$yi2ioRc5;_q_LVXB803ok|+@f$_Sb=x^|jy9js6@tVTkt zs{TChoaZBEZD~>VTKo8+k7@9OF$V0CFTj=vy1Hs)?%$7VSrVhjGWeZ?wT`zk-zqSP z6WqDi!xK057n*Kilwvpv(Y7Bya&EE;{b0LoNZCvbq;UDGJjqh3Yq#7a%<}@2C=#9u z`lg;O8?LV=Ie95HwF$+w$s{D0rmtN%-VC!GUr`cgX$>vpngO@9w^lug^4;|&H`(rl zO^@KZ{WWo6VQ1kxlzI2mHxKT{ZGN)hI3I?cvvDpEbz zg&;5u4oaC)?`G@k&xF#A%?C=<5W?xHI*x;b7LsCp2>>W@tw{{8y;_$3_yzc=RAt&Y7r)>b2?DU^X-vwwYk*PVc7V)zh>YogAC8z6u4zSzw&*X92ME-bn6p(eCIsB zNUH4V98wAx4cXJY*}6cQ6iBnhYh_zHZeH^+3^|zwB;oDPwtahYDvYUm1@ zCmMx)g(P5vfG!oG^L$1%THQ-26@)R3Ll6Li^9O1GjBBvHwi@gA_h8yCxMpmnO;rev zH@`tRZ;Wf@2(g&^S|Ol!QrTsJq?p9u&uvHr$1IcY$_>)cXiIEYf{b183KeX zHRfhkWk^rlXu~o!3`ZfR(^uK!&b$F2yQgec(e9qv5o zx~l~VRr-<4109XVV2tDB*u!w#TvJ=_?k`)D6IuC=1}B{r1g5E8ph=LSd$14NZ9zBf z6~u_PittZ(!Y$9 zuD&p@O}_?XN9;A%ba357)Ih#6AMI8z6(a?*GP1MGW(O@rvG4*>%4+!FvKf}6B*^B* zSDT!3W&h)6)Ohz-$!`Eq92$92FsYm7M8O_x>nD1YNh2a^>HhM`IsvdAzQoFfXxwc3H#Ie_K( zHE4g=nyzORxc6`jAq3iO1tm+C(JBpAY5O(VG+}TY8=butgedUJgZp^IzPd8jTNx#E zXB>4k#k6dk>y5Q!MhhgVay*u$HNpxjD#OZbubH5{B0btvcVBkS#tULaF(u5$_;UZZ zaKn0b?f1;=@}-M)A`kP%=Xpe=EIEJI|4p8yn2s*sc%3>5I-h8`ak3B3cabD1-nc(P z+bPhp3*5Os!elZ-P8g<%r*9r$PdR~cCM>rX7WQpUt0k6FeuIb9jUt+(yX(JA&$WrAH^QAg>I32>W z7fXtU=^&2Yyn&fbmPFItN&8E=Izp)mnivCRTydVZ%ly{V3yCtX;UI)}RthVaY`oJts6 zpyT9t@Mwb3aF%Ikx{haWUc+_vEV{|tH}30kO(Bd_bjUTuPcmOd6S7H*P^ffy>5@CG zRoSw~F{Q?|>Y$YXzyTQJ3fg&v1;Mo4h5OpnLkXwDg=s^}^}nn2@XMI(wM!IS3s$Ml zW0($f(}J#BupCc`6sHv3j#5vT#S|ib2&!|5G))kdBh%N9JWS)+P2R-60jLNp$S>c~ z%yI&^q!*or=>q@ryh$NY(AmxaO^`M-!@|iKZ!` zD5apx#PP98VO}|X9cTG#m}>Vo9)m&6og?VVNl>P0XO*RK*f`=!i9l913e^kQpyE*! zbq(5byvB30z4pdQwPojAl{Q|+Z!~Uy&3tmVGQ`#`RyU+OM9`XUEG$A2K%Prv1woQi zL@7m(FiawbVaU-BIC@hJqu4-iT;SHtE}Rnbd44egl{s`S>md}4N!+zQkF$#@dcE1A z#yH1~lP+$UPhk{(cVJiw_dHt|<8XpFnAEchfP#MVB^a0zi3DUspAb@K-~X;HoD308M~J2)M8Q~bN{16AL>)~Lj0dE6j{>EYd+q%-@~mNd+uOS{Ua;3K7nZW7!1g5FOb{w=?8G`8)&XQub>+fOGkfJ0R zg&+oQTvI8>Yv-@yEWVGi{`%JQ)2RiKU9JX3DOa=L1rL!Ecdl`L2#2)k$mUE>&C;~IMDBOKsp+i6~D)_b16S4xFg5K=iMA%Q{? zjPLg#q{8(}Nug;3sVu-W2PUWBOldhX#=sZ@Wwddi=i#FvqA*0u&KJrSUlP9sP~bJ| zw?T#{CL1Il@==JV$@ zaB>+Ff`FB4NqYWi zK$y)p4>{6^tT<@K7^D=9nu41+fR`g@&UO3)5oEXk03ZNKL_t*VU($hYh7Wdrr~cgL zK5p92p_e?sx5qEx{q$oyo$ET7UFCQy8dV_(vYcQn7$#|iEad>9;G9C|6kMY)O95TZ z6iE={tZayG?m0*)m9}J>pvVQ{RKRmhOr{CqIKffZteauWR*(d3C&xHQAkT(4JZRNf z-O=G5I2)or4AHWRjT)1?nrh;%FAdDt{!H){9uBb(K`*}_Z-#Bs=DTbJThR+7;q+2u zWx8P_i4`uIm+(6&L^&d^N-v5(yPVKFlv14arf6BkR(0-erknOoPBqVS z(53985TaJ|cKkgAqvpD^rknLRd_{Gdm14l#%(A_*xxZM3YE(m7V}w%JZVN@8Uugj; ziX575A_~TE{Jjq>)_gvkBixKEBuSCw z0%=wt&4hB|5MWe-5~wNFJO+UTqkyhSkcObn@lEJtRx(SX0J>q}IsZNQ*7(cy=P%Na zgAfYG-@{~Z4&MT%af&zY^>Fig2V7H&OQ++5F@guDQ?#u7%DgNJ!LYpsTL_|HtJdPl z2_eB5g<)IB(zvls?06j%C5mcc--ZQ$?+D}m`ewM=M-D*NLoGrS<#S6m0t_lscy$$^ z?Ao_kHbqIHui&#cnOcP6n%R*MQqx*glgw2~^xfG18ngK46AvW7uE6+BG@n_tB4Fnsb<@x{-05!QNPZ-aep`M1ewj zaP?3%b(1}_!2L&KJoA(V&vOyRIr{wp^ts@?8c?`-y$!=OaT+|p+1UhV)>k&}f7uLb z!Oc8G*xo#KTivw~9mch_%@sx^@_e&{7NURJ zlB(l(cgl9+jH25%R(Lpyya3}2hG8`-oM^gwznWl{X%f}-?PxMufwuu=`6Zkp&(eix znK2ICa$uMiOvgi>rO4AnL2An=TQ@8iCH3i>!6997V&_+s?o-?}i{b<-v+&F7l$KF; z{H8kWv>@oX7V^QOpCQa%bx>YU9!&b@bu_&kC2E?6gRYH7rvqHS)`g`rj3X=nAVv|# z^&=&L6h{$GABH%yURn|T+-Aqt?X7$s07~J|apTR_3=47tOpg#C%?ec2V&AvX4-&{i zKtQ28CTR-BTo}3rAtlm6D9D(lfiVhNjs;Un%m0%4T2@%i%S=NW`s{HMqEI|8MS-Fy zkmmw;&>njS)RdcYPKEm^O zH$K++tC)^@@Y?&Bj(RKi%rOLLn&Fi@ecZm;u9b8gSIKC-c6SIVv6dUA$xPebSvfk+ z2=)&adk0cV495xDc82kwIc+yAcWr=BLFck0g6+1ziq(L@u$;yPq$qMk(-BBHsaQp) zRg}#%4dGb`|nzx&hPn)R=jm)=~E3@O`8?g|2f1Wn-{1!rfH| z4FE0Az+jpo2m&~cgX04a{ee=Su1q&=oJKFLKe46g`F->w091LS)lySG%k-j}Zq8~! zmF}RXZ#{X-_3I&wBnoPNjkx66;F?jY7Wa{6YTukwh&fHaQN(c2_29S;(lo&<_s?)< zzJ!8YzJc(p^)8H~ZFG??iY#p`-!QI0H_VkqW}dt#&Inv*Hmq>%XuBTZP9`OUlx1@< z2c;AR2*M~uO2!~k!jLU^u7N1dlp`(x#t8a-MOKsL5`-x9041ulP({9`ZNaq+M8N=L z&4g?kRaBpwA$iMAw^^-aGyn85d<|HX(0Y-697UcXoQ}{rxQ@y2VlBSi(iP_TwYx*y zzC~e{C?(Uf@bnW(MoY+S1x3_kTr)r@L%Kr^IL#HOx@|A=UI#%0Mun0NYcR^#Mudc> z8wg8yYd9T2H*Gk6rNHI^ zER2HYgIedD0YDN1wpGFFQh0L@YnH~y^Awt9!0{9`hEleXgoSZ!WnxT-qNZ;2+6O3# z48gb$LVzqQ6|xyasilcY#L#Jb@LL}8EW@k!&M~yV3C;ix7g4c0xZdUMt^BiGGeEfp z#yFBV!n~^?gur&&E4B1_=R8h)Ts!V8=;BpYH4dee9is}K8O}4{LJ;g*--bj1P5AK74#8RJd?6u0&}lo!HjvZUuA0Jx%r;}8 zcg-H>&b9tKva-oWFTV_5TXxQsDMjc$Y_DDOFf^H|3D~ZO*YEam{m6x1QqSs!fhTY7 z;qHS0rf~+>+>{*=SdO=%zFdk!PuD zW{sQg^D=+=CYdR>)h!Vgk6$jZ+!i3^chxyJ@7Krl5@?fUOEQY?o`Zb!y9=N5_Ir@^ zKDX$g6}~t`mc*bGu=N~g7h_yI-oxR6k5^vLpz~DK)v|9j?r@WHHVhk+358)8$aB?Y zU(TQ_w!Acnz!-;ST1q9@azH7sp)r-iw%yj+2U$viqR19jbSV}3fiVUl38pcF=R4?h ze2AjJD-R!HV0;@Ho7Imkw!4!)ww^>1Zcsli32&w)b*sO3u<*jW?fsP-KJT0-sfXK7 z9xjv<)HXTp-0LALGEh(mk|QS(9OBh}OGS7RoG}=>p>*+>1mWv_nAdLOpL|nASs!i9 z?)mKo)P}|g*2QCPtBW|CLKHc4vssI;GP&mGmF+6>|JsSj1_Ov ze64e~9ABlfWkacgrZz>Nj=zUEoT6>#cz8BJQAl(;Y7Cic8gAX_;^D&q#!&*_YIa^u ztGhs2waFyZOYXXh5owm?7)?^_d+QxEp{#DoEjwvKX(O6J6gf5y$S$k70 zcx?oe%Qda%jq3(nf3IY@`}3U~bX#2nZfp+L^|_@LcQU*{t9y(j4i=)a$~j9Agqe-Q10SuHk2KA3 z_kJIFo}=xnXjC^eu(6H#oM<8apEJ%iL_5HlC}ntPs0Yy0wnuc!FNu1#mYPUXl?!y! z0%Tb?ma_bB+1M(}B$Tld_M|UuClvt@gsfoe z0bn{(wvZ+9g2S$4w1%S)c_Hd&jSzxs$6cJC_c0tRc{EBSbi=AuZg#ae zqd3@K%}9ph7>3sTe(9zSN-2^oZR8sVl!Lx3R|lbVMJi75SFaDb<8TVEb8smK%@~L6 zcMu2T`dT^u9z;>>BvtpgR%KMXM(j<#H5UYFp`qQjkzFj6H~jZPiUPzq0_XaAaZ1WK zTz?N~(Zi#&5pJC9quXuc)jQ{~v;#zJR`1#7oPn8oH=yW6pFG(|n#OgMylk6v0}ab< zWPr2X7V^1>d*wTcqF>Z?;N+U(mU#8-HJm5+kXhx^qU?vF}ZQ*D%3;(O<}L{Sl1&rJmx&cNMd2Sk6jDbrqY&3@0ZYHRrKZ-eCSa zk>@#xb_hDp0X%P9H(IG#zP@fRP;I z!MTFPXgb{XJ{-SdbW^X{Cj7Ie>no9l zAw<5G+haQH!ENtf?w~JWnqh%bc4gwH$|fXWr7B!1w0qMb!f& zib4@@4=>7syMXPr(Aql!rK~ZER;%seL*};jkioQ*Xw!^iC>4r@BeILR;= zhKTID^|qHSYgBe<-fVQhv?Lm8S_mm+Fl`UvbdDft&N+vfjT_hZ6!b4i@Y>x0Tw_)m zQuTD@Kp6#?oLwt6*O)1a9C0uyxpXsdO^4UshwZgDszJOmbdU*&7tGgoy9k7+&U_ND zjna3DZOVJyMDq7j12kIrFRnj1(A*A|y$M zhmZO=J0F5`hG(BTM3iX=l9@x(4GWspLQYIrj=wPGZkRT7%K-?%#l;907b6Tu>eeW+! zO(tb^-}ZLe=Vh##QhXdO!Zars1RSk)2fBQS;LrXpvf&pO_tSbW(l|m<fOQm`g4UdG;MD|QCt)S(ln~0 zkNK5aHQ9y>kqMycbCa0isV5Gg>#OP9z54?U-LLI*{PppbrJUt5$FX%A*=Y6Qaa!HA zV0^dTU8qkjIOp8O&65r++d>k@xN~m^-^vzv9Vn5=v(iB`20HJcIbTWj6jzCAY*kT! zZdmmLoz3wS7?y)Usv`O$e?8uP-Zb6B=;GmK9_$^Q>P(qq-F8HQHyTkJOEu^k#i9O2 zHyuQCPHG*8NS4NsQmmcyG)xDCkh;%NjfOAdfS0Z98@P8m#6SJ#UqBEfpp>B9a`4yx zqfg+eC-?EKSI!_L;M)>R)9~rfyo|5B{3`zY|MpX0lp`;tDU|SW| z7})Q&@E`ox_rc@}nwsST|LCWG1wZk(egJ#^cI6`_mZ5`dS}o>KM$Lz9?l_zs0Aj8cP{-@fC4oe@#YA-QpRE0-j%V=ai*wl z9ml}6jswRrk@a4I6sr{i=Dibf5~0X5Fy}hBW&4<npZipf`%p?fTgF z_A%(CJ3Hu1P*}DNDJ9~hfZs7Tu7(vpHP6zz+pOs(yjB-N3Ps|bD6*vKXt6_@6$C-T z;JGHAI`V7hoaY55(-^K}f-#C%gqV-%t{Od4!muX}5MuGgbX(nWGHUr{*ia6$#p^ZQ4r})Mw z#*3}r-{~3{rUOyrDoriX6&2#5ilRu#9A6DN)MyL^$*8yMm+Xj?ad6Fq;~M~EEp#d& z!MKhj3Sc=NjKV2@uNEf9@6?MEB?_gj83rH$-Leq})15Q~^DIR)9Vsf$xkXktEKs&u zDoB$ELJD~8gGNpmb-o<`>RfeD6}zxEnTQ^%dV7r1ro)#KK=Pz%nrqdok@kN*%jXP8bS{Omvfb$sp%U&Rl8 z{2dCj%rzwGY`l8jmdg>EZYsICs%NogNG6;pa(qG=Fz1k$pE*Lv&Tv6MU2om6z!+D< zTBeO)GPpE9N0!E*jKQ#)Io>a0gb=v?9>#-BgJ%R@d%fh9X}dT&c50p$DN;yK5biV4|*;@2tgD^ z;4}xMQV(W~*W;uM@a0dO+ut`RF+@DdO@3-dZ<6p{$1F*y0`NV z&GGltgkhc`OJZ1Ft6oHfC>9)Pg}A7GuFii`Lr9kAA&MM%8Y395zGPfCKtL|V$_J=a z+OXWl3Bo2TiX78X5B}aECc}$ber@gXO9?59lCNV4Zb=CG!zt1O8{0E9qPRYX%f|o zX;I{g&5m)7>9Ak2Qf)R%7w8WoxUP#%%fax$jkOM%aSe{wL9aK2XRA(gSk|BC$37X? zV3fj-3aZpR0zGe)K3ipBN)hK8jt?Aoo)V-?;uz<>De^Qy%Mc)@L{N@;$7zI|UQLpH zxxRkec{|en>{vA203j4$|+|d;|P@XT8m69YxE;!=C!IL*T&-j9Ds2VX~Vk>d{Wg3v+n_CAYPQu`+hG=Oj1xO)aIW44dur#H)JG^O=!0MCu#OyoQY*Pgm zSG6P#p&J%D2iGw;f3S6XuIb3r7=%!8t~WBfxqi2PSw&G`GCYUZKEQO`QxasTSoLNi zfi2%e5M{V?w}+E!Z5W2Shd~hI)z=>4Z~nDUqO;e6Wf}OhZ$HG_o;yO43v^ADW&GK< z@8W;?hyMyv0Mj7C$3OCJeE5TJL7wgg15-8L&F|Q<5kl8yWAjmUQRJY6tqT4UqL}PV zyMB%*!^JGg@jJ+p%^2!kEEo^eJs9;aMQEf3QG&I&YTdNJwHZV?OxIJK7Nb8}`AqU7 zQ14yPJMV+$s0@5~@d(A-bCt#+xaInnP7_UCVl)bIcxb|FGq}AQ80cyY_yhd=;dmXS zafom->niJpfuhJEr9`WHSkv|`L*=9pP-PdzNT=!MQYl1n+U5m8kWyHdg(nYPXu5h} zN5e5rFO;m+VaJAPw-v!nQ6LutUiku~i9kUwhh=QSK3_ARL{yG2GsfZV9U_ea5W1-9 zUDef=opUBMKe%9cY@4$z+1wAV%9> z`xAQrxUcss}-Zg^WhP)D} z2(37{ro-`9iGYCSMkp|I&ehLNPTF#O#eA5?5JjQXMjGm`jBBtQf5A}%;{j~9t;$$Q zq?FM&kj+nr7d6j~Z4n3|5kwi#W=av#_xUc8<LpZ?7+<0t>tCl&AV((zDARfCf<*j^js z;n`N_tWX`=!aq$ccI%AmdaYJpl`nQODN9Yk)f#doi&X_h+olJllnBNHMLDpgX=zwa zz3(QQAA}PU7)Km?Z5N$sOP|mH03ZNKL_t)&4G_!LM`3i{3*CQ9IRzbIdUkK8_k~|o zK+)0#CX)cIwvStf9gHRkOiET(yfi0hwaTiaDFjH631{1QP*piNr%S$Gei*s-}fP;l0=f`)j3=N#a!1EnTn!7I2qPB zXWg_gnp34nk`P&;K`z!RXuv?VW^z*_Z|E{pk(y{-z;GzYQ^w*V_bv3cR0r`w>ZLG&UWvtQ>P{gQv~D3 zo7!4-(rTny)GxkL%vgogF~(P%b7kRl2+Q%|m4x-%99>W{;qBWxj*mL{`Cs~7eEg&D zf+!?@`PaUP7v6FUmIlC9+ z2QZiBO0t~7vQz{#nq=rYvlEe0u9c_B(*#^M)QXcU*j&41;o6B;kCYCE6AXqS9HW45 z&A!+1J2mN$Qu$VsN`+7`tZ6<%M%BaiIMMSp>o(GGJ&dO!g9#>a9nB<3h#+;qbqhC7 z6lLgWI7Y8OLEA0>0ff`V)!uSjD6+J1Ri{MJiUI(kvaUmKn*^&$8_Ujl7x)>lsIpy| za;Do+0N;&4g39Kj=cdoU-~Ox68o0KLJX4UmvTIM7iZVB);X;T@Y1oC6AzIyI{AYjt z-@~u|+8^Nm_`f~_L)Y;B_dbV@efVw2k_d*O;g7%i8gAY=#9qg*BV|L^@I4=R0bl+4 zYxv~H-U9&OjH2CgkYyP}kz>DO;=S*B7GL;-KgF|8e*{?)fq>xna1X!o=`SrD%d=0P z;6s0TAKw-VH%ymVPBhC~c;pRyjmSxnGzU%DXgFagJ)oSTicF>dndo2xT7ZY4N?%-hG z$E$ZzXe?bo9SAUJx{fqWz#Ag9BnqLM_6kfb&r%Q=7)K1cVc^ycua*)Tk0y9@9>CUf zbezQ%$#guVbKD-4im{YRj*4KLIjzER=b76 z1CQ$aBPD0NYb6d+VID+J_Pb1pvwgXrZk@?3QgFv2j&nOig*t#b~=-gD8e#-*^%Ial^E<5L?2bBiKJFdo3~90J(PEvy?B2qj7pen+dImz*;E*pGY& zKl(%O2T;NZlL&d1fKZALf8aU%g%_Vge-OYjHMCobGU5Ba_nr8@?|oK$DLHPK{g62WWlBTJLH`?gIZXT2qHi1z+96@i!U6r~L28eV6{wR)kJQX)tw z7&r06%^4p%Aq1n*`sbkCb}<=GH*$clv)$Acmk*k8_?-i2RMldJ!*Qu{>|qkmUeYut z@JfYdMK8K~QL{9LF{iGO6$F!*p*Ph5%5m-59!{?BLpKaWVT3zxoMA8+W6w!f z0!lUF>i?^>tPlj2p^h!dGGsJ(tmwI;A8jS(pD*7eNr-9YqTQJ}=OoF{A1LMLWy`Y! zl(D)wy3Qy8igH+mGT`mxd$v*_{=JXQqJ+<$t#6`jGRio3S&t-?Ktk@EzHOcUy#m?I zF3wqHC7WxYO6=hrAY^TJ$2A>XH+Ghz0#sC~plo9V;{lRr3Mo}XJPO9;}C(v1rEQt_|2MES}#K8ozZo;&^ zGQg7!E~udo38Ig=hoPW1VrX8{mAoCMZ#q3d&VFqv?hk z0o9FKxquLYwyz_}1oAwGW!pG9R1vPh5@ZF%p{Ja$loXc5fnss>WsIxRgV91-0Jg1R z&*acFtxg+?JVy{F$g&)JEgh81>L^ka5K`0^JdGomwoFyjL7!MW}ym_qiPDTj4R(BOGQEEPJ8V%REgl82vJ0D}O?KEza zWd%5AxF{bFN+euUX;02)vXnAFss%{X&5esV+rYElL;+mYi8qb7U&bh7u-&$5Dvo+^ zTW?ND%x!fMPKOXhfnYL#*WL#qq_K=OKe!_$Fbp}mT@RhMS8o%?DIT5rHAUKe(|N(0Z6>~?k83HZdjnq zz*oQdI_^L0!M07j>+MgW-S&`1K$;gY3?0Au*)PNQ9K7)C0g@;KAR(k;m*cvLi_;;# z`Db@mBCA_B4sq?Miy(~f^4DKmL0wTw@Zk@=1v+Q={1?B4IG%I<A3)1Ah$SAAd9&Sijfu^qhn8>E&Ur8lFc=0nYzZ_q{%yB~EKBQ5 zz;e8`YUPvwc~Pli5J=FiC5~nL?AfRA(ZlUdZr()0fm6nzoAz8ouw>PkYZj`R!fg-e zY)qSR4$HOY9RAGFYr28q#Y23|_|!%x{g?c|R%_y2#wLSvxa}^Y>9}^TZmYX9EVW9H zr^7`Iu7YU+!Ke?e8Eer6giwI+dVr8?C-bGZp{|S(P)aZ^D#WDSm4KLvO#}@&Rz>A$8Eg! zMjvfE+es_~C~MI79`w*3OwjG9)!{p@KES7c^N;c0{NxYADPd`vVd3t*^D?x55|nXh zx{06t7oR~8#CY2aPhdQb@IU>p{}Mm`H+}%OZXSVaDF~(b+BaUuJKlC1gs8!iI3=Kr zqti0sdJYEPnc_D-^T+t$``-!x^~07O<#0@jFcO%SJj-|Pp5gGY4a?9$sEWok!$1(m z2!j||QQ)ONc?B=N_jy1{w0sr8=Y^_4OGu=NfN-u(?EOCP6BrN9YVML{Q(V>RWf+GH zu4m)mKrwX%VSg{iDL{W2`J+*EcGsEhJ{0M6S>InFnSH1)`6kBb%3PlCJf7k z5Q|wffEx8dDTAgPZ<;E1)dUPDL*(INmYpV1O(lF4bG#0cC}8C1n)FDY`8af8__>1Iifw>Cb%z$44D} z`_QcBov8(9`N*8eIRMY)6< zCqyF6l>>0(K8E=e+8QN|Ci_t5v-thNNAcOSPvOPm-7)b}h}8+PTEunp-|k8fx~&yd zNoZ9OPz9x%A5z)W6x`LOqdwaE*VJO#kU4No#~TmFc=)i4f(eCbXt@2vA=;i(!@+E? zjqkkr2oE2vM$6AUeH|y)4k3laH^1`$XJ@koMbmZQnHx2<6i}0}zx#!+;@PKffOC#0 zO5uAJ9z49jWE$dw?|&YEgkhR^^qmKI`Kv?qPL)|mCK;Z7%K*H-!1uVQL)xP>CmH{Pdp6sOzFc3Vix25ggwqCgx@VS8;* z#t{eOx(Pap7}^~l?Y3G-rIfgTzXvH|_*+UE^X6Lx9-fYIOXIL?8;AP^di`;&Nm=oi zq;aqU*IV&0geV}rC_P_m1a(~FFm zAcP{y!b?vO*4G9E&l~TlSKBm+YC6Vwi-Hjbp^oF@7FuOl4ZhPNc+SZ~?D< zfILr?DCveYJQ(-kwfD=0kEqYHVzg`d79O4s;jR~=0kAk`ZE9DGENkaj%+6<=7AbtXBy7WNBI2je*-seDDwH?D8SGE((mA> ze)320+%q=-03sLo#eefTyzQ+|;BWt@pFpA~;97x4r#*b@JNNLew?BzTXHz`=G8$c;=Wo$+sEDFCvSxGIgqOP4t;*H@IQTS{AbmZ;L4C~D_Cju=`k z4||=N&w2Q$4=G~U`sEN%geWI{_u&Y)Z*ur84{4SoNptMAE##S+s&-m?lPa`HNow0GwZpU>X|U_wJ{Wr_Ir(C<+|zd-%ZnpU40F4}K9Zy!95YAMfFrr%&Ly zCOnVBEJ4xAZxXdiP67-@F(7l8T*CYRnS0M*+wStr^S5%^@uZvYRZd7CKu9Pdga8vv z#u#kOc*5)l;6T8QU{$e{i=G$p(zUU<6146bZ^GOE;Z- zc3gR_|9tqbox|DZN@n~N7u~z#+AF;4{lD+?K2O)3xdH=hvCr{IY zXE=Ii5kh8_gC8TLwC7k>+q)x)JS9nDR@}qvs4;uuSu*8d8NeNtkBpGq<0z0~{9_mH zxt*NjN0%sh1ud`@5cmO0rO5-^a~@xmPup&6Q(0OY$u_d=)ludy1Tr|PV-C;L^qHq% zzjfh)L4IIDI|)g*T&yX$9~KeBQIM)~pZ)L$!7j7TfHr=oYx-F?Mq9}MJn_vF;?T9=h&UOCb>kshldw$Xn&_W12*XH>b&-1_| z&-0cyo+@-cBn&ObHnRTBt5SCP<&WPE2n^Habo4Ai)*$N+&fRLo<5xa$2dbu#r3ruW zxA*Y92cG6*A9zc#jb=ZP>bh|t?Umu6+>V0>)8*dw?>B?Ul*WbYW{Mzr9!V z1C}|z(V$!@u{<;#xW2JR8V7h&Y{VAY9@{{-OwO-2IDUMYm6bZ@*7w-iXM5DrJ{Pe*7%!n+=W~uFSMwkHdh^{Nmeq>GTdSy|Tsm^&LL{ zrTh5xUwuEf+;q*zb(m#BN-YLmD%ND}M$^=O4IIEIT#C~)kwJH#x@Hvl)RqoIdwO%j zF>_iipXFtfQVq&`Cuo=pI8_($^eO@|()|{Bj$sX47KDJUw!vi=uVNT-*RF3h>9o52 zvc@>va*a3)4%EPk!=S(9&e8-`p--0I@0yv#J$_U9hrp#%pEGTD=y%H|ovQ0-ih-hP z{dlVBCW@+|4@K=kU3Q@TELF}b+`&iXdkgWLBnm-+(>xX)9tIyOpI1~+ zltG!LkTnhcHV6(R05l7h<4yIx97bn1Pb1-o(A)&9MsPcCRF-RVC!<2o8 zI7HJ+AaWEW%`Zt}vP`8?cG=wiu$&;5;uV4-zW zSLwEP2LW196z;h7T0*~#s_7(2%7YL8lwbJBZF2_@vNYw`p%N#KR8iF{ICgY}`yYIg zn{T{oY}!oVnmJl7K&bu4hH=#`6&lF~SLkw-HHjoQRM(AtwTvyxm4PImzU;D%ob6qo zdcDGt@^SVyvjYX_w^rUWwLuhzfgBGF1io!8<#)USW%<5<_^RGpWY6`@hgx-v=xX!?XxGZHAA(rW<|1B9ZGLMBg;F(_H*QQ;YHJ*J_H*u$-wJ z*&a;G!FEdIA}5GqKK~_YVbpBg{=M5w0wyq zuwHZ7Yeh60EvmH&Cyv&5`OGd}Sts&k>`IfE_THA%5E|}0D~cjBB1NUy@>!~t`eHEY z*fL%>Z4}MohmXC)Ti$pHd6r_>4nY`W7#eAsW12D$_b$VpHboD4mhxEq1N2;)tttXc z)#@)>dyNQffdFk5!!Gk~CXSiYX?Lkq%N$v%pI&3M5I2rkQw- zN~s&3NXy zGyMAh@LsOE^5oEG^r(mmA9~-7{O3RVA`kueh0zaDh7OsKluQ&^e^%8VzZ_l>Qi-zF z@_GKnb>bx9^qFn`r_a2bi%zVdX>tO$cdQM|CQD=DFz7QpO0^YC$0Loxg@W=pk~rK~ z_$UtjnanAWF+fq(0}T-M(2X=K+hJ{Ozzk|Mx^(^ERRw2YMCDM39M=fh-c2zK4cGHH zade5Z=Xa=$d2DxEyXZ!tG_|$eVyFxB2ov z-p@lndX{5{m)Y8B^31bm_#Z#>9>OTaGn$nqL=Ik^AD%CQ}%QbxMFy>B$ZR_#5 zgDcm0x6Y&!1yN2jNVx2hHB?nW2*Jyzcc?fCUZD>n$@YUF?Uw5#k&oYQj6A*{rUjoo zOVL%8Fix>;6WcP_=_pLGV4R7o%(HW!PvZ!~utqZdyr@BsU>{9_KBm3o0?c2>A)A8x zXU9E3 z>oIMQBnn89Noh;Zv-zcu-$s;V{QiIW0-M`SuDWvY{BVV#>>7ORL$~ske|&(qy!nd3 zZy0)=Wf{Ed9dAS<io#_VAK|h~ zj1nohnp}0o2|n=Nn>lfOwYWpe z+Vb_+T}qzkBL`Fgj%X)2&kH!7&U@ecrjZRZ6cgJr0UN;6?#2?KXmQrPZ(`@(QT{N& z3`y1~QE3L!ky+O@vMlGh7dLRMd}3Ot7ow6gu2qb>eypMy4u=m9JOx{=E<3v|YHmi@ZDZQ*zGlD&g{lh4>^QT-sS_*IY89e5#Si@v zmWZCj5wE}M$k1CAoKl4(3TW?b^_MV79C7_MM~lD9<*s2lIKt=p*Bv7lCy6tarFy9! zoO_L{Yp%YSs;i)C+Q>zoL?MlM3!`Fj==$+Hqt8k0Vv;z-Ff&RO*}#13TjT(W-);3j zU(@9sPSrH3Wt$t{c#62F?HZOtxwcBsZK5bDmL_Pn0$zAIotYQyv7LDDtr^xhAr7 z!S+s<<$8%E$z}$&@djb9ys;nEP6&ZvSd90>rv>8+PK2lSoCeGAc`z&+l*O8Y<7Ng^ zUsIIH#!Db_(4FUpa0UmfS}d#dGv`F`NT)xHZgkd`w^f2`};=7gg4)G z4fXQa8W))XU;p~c_|CmQ;d}Q#!Ch~EqujP$!>_PU(@l$yedsp+;~)H0KR|1$KqW)u zf_5k1AHVV7$addy(>3Ioj$*34!B3J@A&O((`sS4qekGE&zb zM;!W;s>>u%a3F?94^h~iIWar^T+`q6CRmJtH7)D_PP-HrJmQ5^Mr9ifi?Ut|{kLJz>wgH9~bME{umtK4b zUDvQ}6DzJ0X);)8iq2cg@1E+;oMZ}3U*mZ3dxa4D2Iq2ZMUETK2qJ!G58EqGoM@Kq z(u&tni&>ODZE>~i}pujAygCF1`1E?8c!a?=fR zh-4T-WT={nVOXpzS9sIwFO@6DVt0P@gSWA>+v-ma0=)C>Z^W`qvOFbj2UKb+eCC(l zNwei+S~f{+qiH#-D^;$4{iPE}#fmI)R64KHgdXA$j(lK<>eYj z57*e*Zqp0`N>)ByZZz~e6ISyemv>%esj#z>C$Jx@D4NajBXv|&quFe+xznLyXGNyy z;W`GLmO>PCa7$GT%Nglx&q7aVJx$}0fe?}BblZCvmW@}glcgz9Hh(Aec+)*-s=zS> zK^RjmIoOVh9Sj2W+v^{jx(tp}g?40e@yQydWzlMfoISrsy=-DA)3?E^)Csz6R8^g6 zRO*!{t=)CQ@O!)a001BWNklhvV1;h0fe<-q9&^RTE1WpKMy=|iX^8(1__~`$bhX0awSC3?WxT?`IY0xdVnO3CyYAA zk%UsB*tDDr8bk^cl~kAtFn$l)#qsek9!?rX~CT~1m zrA`$1gVo0rb-MAT6UbG9<5hTZu)4UgyoE~ zHYUcN7YxwTw(3F!B%`22rHjoorzdqt_Z0M~;7Yx)CcYWn9nY64#j>pyMd$a}(WCjXY0Bf=H(@N?co$ z^_!jT2JKF_KVPmWkftelmSGqMVU&#Uh{vblhB3`UZk)*>8wK)WOd_dYVL4vGifE3g zRyn2W)Mah8R^|Mb&njT(8d)ZN60j1j+nviAkwQz$`0WO^R~`xcimKw3>r*p8 zuTt;pvk0M}>Z3QkEYF7ok_J!|wLere{`<9}DK!s+z^xR6G$1l4w73vLA zu?<|uz_ATX%fz%SOv|ENp7$-U4&82-Ml<52(_5H|+OO5_hn_{%@>029qX#*XzrNX` zY$XdNH2;#QI2myo@bc*xvler5>EwJzl_=;^TRlR1Z+qk>`>T(P(yL%^Z?*yIaz6_HYmRqV!I9^0SSNa@!6%g?kM(t=*cocMI25PJD4x9(mcJa5@ z`>J!D#$+=PBx_(1g}gk^2>mwImSgp}BajfFjoqlSEbohn4WrZCK~=Sh zmCm9lDjz7tl;R{tzcb4-B0r+jkpVjs8YNf9b&URJ$^R&Wn~5@d^n2HgJa>?jkIL}Z z58i8`KxwA3x8pD!SR6-d2+No~n`0eIM zX3~vR4AbH8;XxT^ui26Qfn$gxNddAPZ)R}rA&JAH)G_+oZMV!$=SAXV|Hi|3kj{oy zENMPFNWSOopXb|~ALXsJdnTUi1?<)2IG4xQ%`It&JVOXEa`V$oYv0MpJTJ|CjS$5o zVV;ww37T%>cx3{=Jra<0!<^cnnHH!m+ncMWAqA0|l&VW)Svu2;(6k&$=~|FAVA?K0 zr-kj6`vVk?S0?n^6TyGn5eOg`ppQjM8K5V>OXN91Q5K>az8265Q-Hx*C?(Bey6r(3 zWn}xtKR^r~>oxxJESq?5@2{CKD7iYds*7dYtghBsTB^`#ciGwt$2qSA|VRl>g5vEY6T$# z=hyehlW?Yhh@n9kom>8aU5A17bD*>wp-e_SfA$^NgPfUS8>ZV z{Eoc9R8?|_bzQ?Ub<%uL8t6nCw&QT9SH{_C&~A07T2z4yx|O9hy3O60!MQhzoM$QB zu?)(z9J=W?onZE8@i>Nqw5DbRVS?w`D2fiuzfkXQyltjXzlu6>MU9K}=Xoy65L2}` zW@8b?Mvo8D6uUgreTW-_yRaM&r&b~K+l6k$`~jw3pmxjkejj4iak1SJt-UQdoDxhQ zPO)qkRnr&d+p3!64~Ibq+btDR1R0=AoR^wzNHf&2z#pe7C3Ez5rfEL20jz1Go|LnF zAE)CWn&8u*Ym(J*P?(l%45rEKGK^QLu(#Xb?70BlFj=ZOcqNZ&twOa{A3X^=QFH72Cx%i3y% zYPCX^ro3``3vxLvHEX)3R9o6)X9Q=Q2%rGG3At(NH&{*Vvm-K;}gYz(6&3i8d!@AznV3@WXgwX|6H^bIKc6ORP`@#lW+fDLZpsEUoRx4b7 z$svv%TjkP=5A}m{5X3zH(k5Bdq2{Ll>Vk9c8Xe#7`d(M3>SQb}RY}u$f>W5~lJk4) zNEO%fNMhOXw6z3F%lp(L({e^^g)GM-4g)kLCruJe)0`ThL6#)ka!rcpbX!voRF#KLFj1rUQ{0E z($ed(HIFFw(G?3-QE9|mxaODm*2ahU_U1=(7oL+Ll;iCS8!$hO$2^>uE}W}$|PY{je6L5T@)fs!^hBeOCZ=+vv~Y_ z$8XfCrXlilLUUr8X{iu0NjP$-GU22$tHdF{Lw{8gt3T_&+{5sBH4Wp#D4HrL*%>7= zd_U!=g@&(j{8$~= z^N6E}7f!sPO~6bWM!{_{_%+3s5 z!_3Q=s)Lo*`0SrQh89+N>CupT{^1N|qlT&4+`0Be?p*sK4?cV?XLfJvf3B*i6CqNF zd}LxuOw;37Xrk&M7l{-V(i9y{(Xlm;l3vBpN}TbZ<)3%{hUa;L%F?h;!hbW=rsn1p{WoRB@SKJ zSX(Jmt(C~Kl(XmeQ1fWQL7`^`8g|4k}_q`GOE z3<|lB8MbLTQtfbL+oYCu5=RIzQ07w=S$pi+LXE?*Y)*Pt;p!DsR1~4J`EtbCNsH6r zlcXZ0q}Mo`yntbu94ehCWG^)|O+(f6e!^fFvYi#jLE)_@i#WDZ!tu&uT}AH=wh+2=av2OY0{4e@GLB|3oTn#5U#T?Ec3 zRSA;efefFs=Nqil4RqC>JBn#JCEATGR8^x~TY+YSZji8ybQNf~6xin`KPynrW5qW5L<+D$=Tb&h%QRxr1pr`v&Jy zb(wawNf?jTBt3f>OJCxid!Oftr(VIb3~s#Pa^CQUqqI8b(IXGft@F^2UgF^&4K%G? z*XB*vU&iW61w{eRF-SXgzVvrL^=ocRah?9 zdHSaDur(LaF7dg~{fJL|=FL3V{RXE>*Rb)^obNyI zBp?6aEx5LhuA6-6YmZQ?dE9p6Wne0(hRYxS*ROH;rAN8r<}1;3lPpV6GKH<3E}#4R z@A2!u`fgOsAkPPXFNKLpJJdLFtd8f(T62=5ymDrjG)*~nbh+*l>=(IbmZ?>p;8F`Xo)mCQ) zXv37*Ua$5hZE9-lu1je`Yfc?{8pZ>)t{eM~ff}YYaWRZH2FKCkLIcEc%FAbVDVgyI z<7C8jcpr{wn#5?jIaArIH!>duT?})y0i>xquD#5E`>O}YvYhw4>w3a4;qLD~PT;59 z`j(4nM{*SqgfY6VamQ`fA%tLOx6K#7{5@1v<)$01B1~dLo^yVE4*|5(J%q?8S<9R| zzcZ3ms3rLEPoAUG?(*;d&Cg?KDtVUE=>{~KGV>EfhU^Csj$?82jaNzAt73)Yx`XCh zw;NKaxZF^T5N~cZ`R{-GZGQEa-^tZi7Pd_Yp8Dx4)0egaP!t|}^cBAO&p+f{KlcW_ zlEoK3cRz>LYA8Y(Xo2ML#FH;0#G9#_D>T+q{_?Zm;bR}ZmDSZcVIhRxXmzBafdZD} z^0$BYJ)$__)|;;AoAoNHitUzpjeKxil)SL`V*w|{~xvMCOY#zS&a)?>ZUlZHR-W0!&Mlniki!*sVYmXfyKf{wxz0AM=tq-7xv`>4JwN8~se)Jsgeb)^< z@bEKI&sjJmaWpqMfL?Q2uGCE1mB)W5aP}A*z3U|O+nAPvTdr|#qk~s+SgMcKoreXI z0FpUP!hbE$O$)=Y`qHHPB{dVxW>uwJU7^$3o#1uvc65#$8Dz&@_9_GO{#5vE7MIv{$LmoUGE66u;|Jsg^0Z21yoQ&{$=j%Eq8+Inv#FOhb9N z8{fmU#^5j%RmHY-TJ3;p#i3Sp*xGIZ8HQ;W3Uhn=mMf;A+u9o$X}8@HimHv=#G;@> zt$dX2#*1=$6qO(l*rv%+rH05-6h-CAOOJ5TZ+-yRwQ22jhy$NqX+cpGG{Z!o%41e7 z^&g*x8qzJgE98E;=l=Kd^Eb)o?z-c8{_Y=sz_r(0#Of)%Pqhoph_>3IYOD?F&xS4i z141Eap?E6V@)@B@s%yYDCWA?UCd{{crTqG!?UH|qG4JH zk(0zy$!z!)rQ&2*W93NK%Gqmmab25|XR%Z-(e*>(G?>t9UlhZ^xrarA?eM<6QN3%S_w`$& zD@z{rn!K=gb{e$i3}pD7CZ*a+|3tHFcW!pk6ArIb!Etoj&BcU#W+9G(e)%NNrKq-B znqFg`))?$TRW+$!n{Lx+DpV^{da+t@K(|pfv9MCwEOeT?cooT|PNIN#qN$kU8LKFc zfugABy2;CXEfiHj*9_KoyWIPOCy=p4;l1yABYh1@;LO=={`k+o0YJAKpy?Vv|K7I( zy~fMzZS#~8H>hvtN0;S*Tqa(6(IMV;%eDO7SH8zD{n}f|$)qn{be?D1Kjg^rMF<4X zzi^&E_&+|^|E$|?ejRVQ{v=r{>#9NsUV3?*Kl4vK)dj^+Zc8s4q`aHMad^K4*(38=0 z9o@8W%nB$fSrYfPKC&$B57Ky*IwH>r{Z3!Tbi7m*$jxa#uNk(+9}6LRL<9#>vA zu*}M`3_;FAV*17Xv!uycP6@-b3favV{{n>id(aJ&N`0;0Odel}r-hcr(Zf}|l1G|m ztZ%mP{eac-^yJAfZPr|e?d>KdZw-L8l`1cvj#-{z;=CV*gY$16ZeCDu_9}IPPKz7a zKS=irKfU0*wY4XG`}Pr5i3`a;Rg>ya^HyAjCg}JDr_?%F9eU=5tC}2gL7}#K6jh(} zn48rY1bNr@s#4-pSEaVAAIJc)R4=jDIJmFcG?qb#A-)8eVtxN&FzT5b=Ibv*2*FJ^ zT*(8EJX1`$4YKttO^Jdoo#rl`#x|O!Pc*W!G@;wtBkICXq^ zBsh1vQd7OBDAz-p<>boZroacmqSr7Wm-EMwDvY>?`=)2 z#G_QD6`7nozJyouNaBdoXSY$Z?#w{zmTPFbPU7#Ok`$|AIWSkNdW6Zr1@`~L-Sv@w zUubZSLVv+)U?@NXoIblt;QLbtGR6^yzMP&bL|?SR=WP~5o{?u6re)0x(2AlK`nndT z?P9xS+;WXlb(uvZjvR*$OPED#-OI@c;)&?c3i7i>@{Qt zV46CHY0lNNn2TaKMK9@Wb)Mn$#*c`T+1W*$bPJ=+E=d#=rn?zwl2Y|_Zom0zuD#|Y zxscA?!_ak&Yp*)WZEw92$2NKN@fSxr;+m$CrWr|^p(v6)k!E?}DX8$jeOI1zwmQfR zG)3@>AHALX@Bb-{-LYE#P!KtBw8qg@m!qpLWmhdS=h1CDbcMq8w;Umk6JB_F2Sc@{ zQo$4yG)+g-^u8;)s;XF)NzhH$*l2LcRg#_JcS9^&Cm(7q3L*HVU%8FM-Qhj&e*^d2 z^90GRP0d_G9oip9k1lb;9fvq|b&2E0R`}{SA4JhKD)m)tx5U%WoFhq6KL4fr_@h7h zD);^137&iY9P68{nOxjn<~*y;Y8Vzt6cUXEaDn7IuPu8c4c0WxIDK}PvYquCU_E4+ zAX6?p7`_^)nog;@Ec;Wtn^R>J4vLcY16YZcK5pdm5b+D#OcAW?cwZsmPEol^reS~_S=3p#gU_*rRl;%F-I8>N0M*hV7P$FQVY6LU+eRfr!_JS(~?cYBI|L>H91^Eg6{_;i9Au3 z>K;LKu)D0Hs5qr6s;jWkdW!X(r->F2JrYA1p%8+#l?rK^@uSCHLe)&-IOY2fJk3(A zgzFeg8}txa!h7F+1K)q(DLUN&%cfki@m!k+A9)Vlaxg5Hhkx_}wr#Rh^U$vx$iw!K zrU|ExFLBe2SMd0guZ;c1!3%R#bkjyRZ4A>coYlwJ1>|(Z4)6N8H*oKLPhq7sl(CL} zoMiHb>{YP63bksfFl|-2>WUNGch66``IgH;6TI?thb+rkUUP|unwYj_QeU%ZCfh8Z zRJr!ri@5t6PqSU_VI3%tOhZm5-01elg&b}vP9DC;`dIl_z$fSog!w&FWoxIy(Ze;$C5Q9t8nFLrLRB^C zNSrq~-*~*w$XFCYhs^>@uyw_APf_J;lsBA8JSSI(@g;datP_Z z001BWNklK7{oIX!;Fh;u&7b_&uMz|?KYT=I zd#A+*KXe0>I&}Reo-Tviu$k&kbe^}r>k9tw|MQRm7ElwO-;w?8^ z&bR*Q2|oR6Z{=)bo0m^-@X-(6%%Rnu6l}~}Z@7}LeEmV*bJz6~$IdYAnPcYTjE!M* zLJiZjIJ7oMYT_v3m9x84oeay!iBn~&)M)-MkU`H266KyQ_G?Jvb4pbyWjp0M?yW3p zh1>#+_Qgt-m61lPVL8~2N4LE0TgtcXlDC}aG4y|rRoMc>d>M-l;yJ$qXu1zjfHnv;jx!~|x4NcAXFW)g~pGf(4 zYaxef9_KfktSy&GP^MeNX8mWNw^P}k>eE~y!QuE($zW=?eRg;D7AoiVvgdhC!5h`P_`sh$#T#$CizG?$gOE5)IrHQr zeC6LmI%axIF?4Fx(6m<6W02`iUvb}Qu|P zbvGgOQ&d%Dr6QMgS=1&GIos_T7En?nf=)`^Q;5TMKMOe*JddfK1xq36%H!IK_b8bq zJah8+MSiQ$zUZ=U{ul*?*bhlX!WsWLO#L*9u5d|wm@G}m{T6j^@^e~2A?FVOo_01NBp|D)5psK3uBXko)Jo^4L&lavh2U+J;mp8IBk=pP@vsO`* zzDJ{?DCBug5{KktK91v16s0gaaL5W5oN>gdLOV1#akPr#I;2U$+4Fm7#3Oq1QP8Eb zw1$;?_^rl5*PpHm8XY-oq#&nm&u=K~w|9mo244$WqpImsR}C|_+YclysK;HcmQCU$ z!!hN~?v*p9xf$<=ars1D%}L@I!!*hAgLhGT$g-4jZ57jUNRt@dFlP#^cUyb1VJJq& zVrRiMbGG(6EH9VPG!56bNU{_|6NTJqnO3;Y=Jro7$Xb3H#P}ovJs-Ex6HhPIMxP&B z#Rwq?qa58RG=cl?7gJAS>zbT*6dA;{=QEK`WL|L|kZ1P9Yx~V=<$vO9-Io~G;rx*q&c}z0wVksaUbF~!YGPo-mC$%g1cKdUTLm>J$ zdrg;OV0o4j`fV)Roq66(TgLXNVyBK(Fs;Ep+}Ujt20m3c!*37z2Y#%gnWG^@WN=cw z6i2;y;yW*tVz*zA2|7*Oa=m{Ig?XMs5+ctDx-I;6 zgP_}@+ipnRj~OtBlGZFDz-GoJqV_(jnS>)%k;EP^0-d6cA zKWP8szOT#Dlx}O6IP@vk*Q8;=l;3Jias27IdmLHwaJ>QbuhD4HXa-YhtwJbMnuIws zrlO|?jr~d+i@+_{5F#h&H1Uh!u-^F}$Fl4ebX#;=d!%Vhb7!4ybC+&wm)7nko#rm8 zqS0yW5Jv&s_8vi}iDAltvmiB5b%&EDmN86|PPxK0nwFg>Bz4~8cCwr~KYibrPw zBEV}EoIy@l?&sM#@_Iwd>2@Q$;-qmMn>3S@l!I8B_Y6emSpnIWP84N$o>aE;J0bc7 zN&rToG+zyhdU!8LPs?Zw!y*_8sB;4hP_iTmzEW|pEQ4G~H|CxAxw-GVPzc0Khm2v& zYmfqDxrXb?WpfxN=t{~gWvbrN?dSmmbV;vKuCMf`{-ixoZ{G@Z(?->F?&RZxn^@st z)O)RNSfpCi?`jV|LV6&np|m$s6wp;;Un$C016QwbCVzfv7CsAEmeShYK-F|H9Id-H>)R}BF3NdK34!%1_HGX!=Y&~VZX(CM1 zME0lMuyn&J$~}XiDuf{P+idRmRIBAalVxwO$=+U<`jEWDYxY}oK{zCgR`zVxbDeoa zfMLeQyuduodXgmJ_kQp9_~IA8NVogiP}X{IJcpa#_Xa-rTX#+f z{a*+y$D3KkQ59`uC25#;Ul)BCZn-)U8}eMC8ECAoNDDoLU}I~Kzz?WS@%wx&ps9kr z&LBW43Rsp-CL**c7vXT`Jnua4Doe!C{3%M?o!uCnSDMldO?vXBNrG<32vjMV1peYS zB zrP<)zMw3fUt>SqWBCnuuZsz-54K&r5XeP}<=y$lM^QDo;-oVX(%%FR&#eR@c+Q*Xq zW93&rXfTdmBWczi7D9j!eGTJjuM?us01@&=++*A*io(_A4H#7mT{mTIIEnavxPN(K z8g8}U$1~B7F6h0($g@ncQVhwl$Az%lCeJh4p@weg{ooAnd;jS_@x&8PaQEGJv$8U~ zG5vWY6i{{WxG(AwnN@ZNsBFkzqfjU-Jgc}tF z6fHK?lsrkNxoFhi_>Nqy5X>e^hx=~XnK`Y(pos8p+q(Z52wOGzSOVcogw7ewVXmcyfOR@W9z&K z91)!!OXeVpw3_O!b)gbj#WXX`ABH6#af*UR^gOq7Zuk2sLNXA|+w=B6dQT~_kW_hB zE=1%RrQq3D`N?|;4158ST)iGxKl>!W*C;-PiMkM5(#$CQUKVLRDZN)X{pu1j|YmJ~K5YBdF;$jtApje}gJd5@U#OWblFrKLU ztzWCGhTdDtZo|)HsD%M%skVKELqqUogP!Rp+p(QS-owPc%`lx(>pdIWQBuaiVAd0f z4a_tvvXVn~zb&B*|Kf*?C<>;cLXu3IfqK=d_Dzc_UtM=1YSWSOMP4!1E39~I>34o@ zl)en;;`3eB`0np)LJh=d<_gXTEXdP3KGIg7~49{DA%|;YsHg#lX{!Ffc7t zS{A*+O{QrjlPCjz$yqN-m3$+-&pVp_X=d%e%-g@>bzKW~!Tf)(*=aL#XcUi~9i4Yzq)26E@ z+!1MxG0=z$hi@z<+|vXXC(5$}5QE`cmwC9*A@z%N;DcdmzDY3hwY_7$*Mjiv9()la z>#o>kOMp+5@y_LcyynxHqXQCVp?y__UT4=WuJjAClWr%W;h!0l>-PL)Wo3#?AT))) zp`XZs9~G8+ulA2mv`gp z%#dg68V^m-eJ|bS>eJ1;a(n;hm6xULSHk^?Xy`PV*8wG&=gyb68>N5s{}#{xy`96X z8ff$cF{@}2&kUz?t_p$3gkf&C*9G-wiHfVInXexi-coF)1Wkh# zoW4+ma%lHWqKOgTrOlEpLh+TUfp?T1sJnf(lPSJ{sOx|EGl?rz={Q219DaJjo0GPB zV(of2-h)QBPp^%D=~&ZZv7Nx*{Am00@O1X#l_dNZ*>Q0bWK5f9QCL*4CdxBPIUTSR?rID!(yj{kUH1!8Gj48&@;cKIGzN=~U z#N`o?s@itUm2~r*A33k(xz2@lQSaRdb#ynI`e(XXYXkvZ=x+PN6;B}{tWNCX+Xd!7 zhrFoE1^?HDRmVY6RR#p;pXq$*mgCAmaL3(f0c~#7aKl+F@9g>CkX?6h84LCY-Jl;K zRp1KfbGN6rcPtzc0P&qNh0Kq(JSYmgn3(eN zR7in=g@}#KkfhB)pjcb(AC)hwx-4HsvA%!VVWIdzf%b`)z<{l9%*gBq`x>mWRp)6x zQ}~6mj-#BTytb@OG&41VC2_AK`Fzd&-+h*MOwn;Dly8Pl=%ROcCTQv$93{_5O98yX zfr-B;V%cG~0;?K4OXTxPaq9*0koG+BOda_$_ezxEVDn|!SJ~R%f7rNWEjvp_(o%C| zzgC4xPnKZ_4CB!|l5`gDip8b{l@W3(1k!n0$FBeV(f*A)>Q$(JH zac)UGqc@bMz%j^@6?#Cz&DU%4LmjpCbq!l*j%(t#+JWSV$0rJ4?S-nq( zyZp`Y>zej3CNQ4yuHvuZqwk+;NnWA&1;x2=RQogMb(PD95TDo(mJ@4+!wI(vCEs%eKi&bIHh2eETyfE*(B zxSGy1GJM1iVEdxyDgB3YQmEJWer<4H_@1B4`-J`NsOs(Lf_6qP3^25@v0W zbrY*T$2KtQN`9)d8ue+R*wz_QCu=aCEaH*e9gYmZF^I?Hx=dcHv2A?y_hH z$Nt0ad!`u4fCoAzncAW1Aj=CM>N!vRCcrRXl0aEeG0h?wqSOAw@p?Dkxd7a9kd^+5@`TI-w(s9HJNkY1 zJ0sKWM{ap@mdwiWEdway3$B1{)i-DQvw7%HU64o2ZZrU>nnruk){7a(=Y=pz_BZ?;oAt3l;)wE1; z^=xc@?N{L7RUyos)zPpv$bChBSrd4%XdD}DuSfng7253c$f5ssmF#)$y)jxWd|P_C z4FGQaL?%nQ=V(I4hFV4|!{f7khf>n?ET#SIPaK3% zjS|#LR3`EY;kO~L3>E0fpdy-Ja?r{^6kNDyCpo9AnhC(`K&@&V%W37RJn0NM)#ad!=Chnl17=92*JV*Mz|8{KRG(?_r^fVUfS^MZR8(BWYsk&0Qu%0)>A>SsJva=%@WPLvGd)-bEg{96AS>u;B zPLusOWp{4#tCp5PLV^0{2t zZ7DxL7FvH1ku$R33_uDd8J8iwhMVeUT$V~VisDwNNP-de9ErYLBJOLUt05Uqog8N2xp<1c8vDwoC3T*+P zyf?#J{+yVznFC)QzbHscB?0`pBOKe2?hEYkwp0=x+5x~GHqrz>l7B*vO(0`<4o5r? zGw@-kN*PUqZYV+^Ij?0qlpsV|gK1=`TbQ`j3Sk>n>qe$*2O?0U5JOUIewf^s8>_8N z6)ui8`lVY~ZfGXRMt)@#bF@^x!=LS-`rDMIAS4^5ph|zOJ0&-L6YfB>0(T1hLe@~! z)zJ~X8@3*4Mlfh#kGA37J!l!+tMWnvO(scGqx@Z8GffkdS94i!w``H-cwivSc0g8A zqYEvpULhVqkDOExaY*poP=u1O#* zSbKd(gxK&KzsSbUm5;q(V6kyHwLyT_&W%1GKue7rtSCh{nvk<03gRx4E8npc&~O-@ zMQL<iR?u&^)i7q)E-Am=npuG>g+Ju1=0}bfvP$4}(?mrpb z6w2JbI%y1}SR&XzZ~UA0E;iQm$Ixu*&{PJWsfP&~Ih&|41ByQFuBs%emhE`{EMq`b zle=P)Y$B0|ZOxQw*@hQEgA{hv}vBx9=P}Uyx-Cxb}0sa0+MX0 z5{nJdU&Z#vt0y_FA|u4l_FbMl4L~qrL`MJ?Wmy74sFeV$p zs$LCXrN-l>*M2WQ+wb4(x&7C~Ec9@*7YYUE)N5-vlT?-@Sf^#Zmt6&|;yV;K!^*g* zdO?(K6sy;X(4}!0;F(PmYPT#CHoUbx1IBFu5J4edfnvN|J#0Nw_b_f47ukKs-IhAh z5AVxed%pn8j`M49mtb|A3cE8;6S6Af-E4DNZn7{o$K3!*FB(6QlATVrz$2Z$A5l zXK{y%%zt`8X$@gGgVkjm_=!I~GYoNe$DT}~GzUe|zdv4j^g2zuh&KZ<$&crtdsf0Y zo{G6RJCMez;xEM<5e!PY4Fk$9@A2W)m>$y_9EA-li=CEzTkg8drDsCGq8zc|#;E#V%Pf5HD&pW=zufR__0qr($LPQyc_XqLFa=>!38aZ;ARsw)9B-ikO zNVhBYxb+#qg#`Vp{XK0&DEBFTcXHR`rzqseRFp(yEQ2}2;mzfzHz{p`LJL$Y{-8h> z;KBBM8kmbvoEdVbVz<6(WNaKNG+Cm~m?6?6-$YI>gNYEoG!)^+^n5@3mxoo^x;6Y% z{h)zo(8PUkXleb+JI~TX6|<&B2{n^wAqD(-!K{XgJV?kxKNx+s{nye`u!k|-1{#n)}zH!Xo;dt+)237xv}ihZIlP@4%Xw2{Kivj zsVF-@l8Hi3`mzv10Z!rxKc>3Y_U9~9$kp<$Ez;KJyY~O*0xTODFJ9YOn0`v*_@+kJ zNk34SAT$|Nb6RcZr|dwsDbvfyDV%TR^|Rs1R>)zGB*{vWZo1-p%I@Bhj}Xpd^KeCj z@vD4R3%O|)lDqrL0Al-7t<$cR=rEN!iYLh6($a?spPD$hXXM3T_vG133U*8Lc4SiB zosr!V16BzJl^||Cv&$_itq6s-> z`x3w*>txP}-*apVfpz9k%LajZ!FQFZlQ?%xYs>NSANCB@!+TvAEI5DHyEGKwOCkFG zI9>eBMP%dJCNpwb{~nL@I%J6#x3|9LWW>Y6BHn5IV~C}au0*7Tgq(~;NDM$@P|oY} zyc)?R&n+yhNXVv>Zqp*4Z4fv^CnV`}OJMJw+)x+EW5T!f ziMY0r`8D{Z>mcF@fcGMQm&eIsvNlu2gu5?~wzNcgTs=R3Qv`9#7mHybhZ6OY;U0P9 zO^L#AYQ@s5X?#D&q)Yl6UvEEGwg3bF;{$v@M^m-pw%=GhDo^HNpH0y7#)g2{;Q~zD z@ghjTY@&=2XrqnK_B1Y+hU}?^CW0ihqQ44oul*_IGN4oR{d`Sz^Sq5I16A9~ zQOXKZwf*=$d(>}a7#o*qbgPFy@bnZzR|E%L0wM1f!3;7v>~Zf5ObdX6D(dM$ z;`1_T5{qYV({7S1@xVhjZ`E>KXfju$8#I14I=ImgtIX#m$_Fmw;A+~)eZmzj`5SXu^kJ3!H4*^HAXu*#993uK5kfrGK?D}nV z2C;aVKxJ>nmoX=2-X{rGd<3>~71aJh`f4hB z_;GZTe>#Urbd5L%(=uiK6B-p<9NOa18Bk^g0FFILVU~uKE`5k7gU|Q@-IZt#Bu`sX zDH6`dx*?YNM>KC4QrV~TL7SrH-h9T6Lc7g@6u>yMCC$JUwmyl?g4UuuD{)gr)3M%r zE4iCCIA}#fz{X1UlqC(1-L3_fVp=M}E{ub%T>nYxmuu|=OQf9W=M@2?Hmo=AgA*Gy z;5=X<6VFB#N6=1>Eq{1X*hZtCK{@+EWs^ly+feP;h-@JCDED$FM#P0M-1|k;JY8rK zk0xdk)dc>B=b;2>w*=qW-q&)adis!1@9#k!zS_;JPt7gYa0!?IzhKL8s@6!ERa2xT z#b}tjp4yQ#NmV!o+|A!2+*^`ytpVg zTJ3`)3B0gHPB|ku``1V@s@|w?zft5N#(;nauK$;#K!bI=S<{utVoA4sZOILM`PiY{ z&BZ0;et&J}?z08Rt#27;3nDvz-1MV>)H8H2f4pk&uJ*l}dbrI74kbM@649=H+sqH?6$7W4UvoP0ga# z0_VNvymGrj0vl7Ptg$3lBC;;hT4s&vY0g5Pigp@3tK;Vwq73q+Yza~qcX*na8mzd4 zsdmhxmll3lx@YR|&5dfyU~Mlwbr7uCnn;o+4&Ot+w=ZLL=g4IhYAQ-jjfJ3#sL_`S z627kg_?cbZs?zUBde&-C+ptEB(oL*KE*XzG*ntldRK{`T69PpQ@^klQr1lSNe*ai> za?368OF-*Xcy!binru^9#Y$3vFHn)ez(x?;f zo%7DfdKW$6l^@Czp;E1~B`*c$R;=<&DFVjt!$+O4p0E(c%7%CX5SO`fJ{?M}goSxj zrRS!Y(f0ic=V6?&?H%E-B_;)B9Nb=~edt0Af-du?d>q(p4KwLRQ;lvC0A&wz6z4<7 z9Ui>4a?N&pyXl7@H86xFD$k*BGV{$Ux<+MG`1S0mXM3%Qrdwzpw2mw_2rSsU4MqC= zR^motQ}GU8rTIMtNv>GTxtPj=%SV4YD2CeJe70YLh88R==&g&1&S=dfK{b%Qh2 zv&)jeJN$5nGOj2az1NN2iM^5uh}CKeThhvYegOTqSpLJ@^24c~On==)hCn4YM;L?5 z)t0ao?ml8E&5h}3UQVY^gr7Mwtn@qNGm@{CcAL(z)iz>amO(oSEnn>W<&XKx*Hzx^ z=(bNEBQ~QC_ll<&ruOcLR28HXl1k~jLD--d*4z>XtT>5W0$%bboEQV*oS`Ypdx)-W z^{PvY4|h?nqJ4JUZ|)G9R@*C^`*XjlZ;jtz3dFtjgTw!Y{k78+pQcuz#t20C>I9Rx zfHgf4na>k}>su9hDQI(xJB05aui01`vzV^`Gx6-!<9R+snJ`-~NYlwFOv)%x<=afL z5Rb26``F@F7g|{8q5iWBrLfEH_`*q#XH!2*Y~1T&N)u#Q0K8v)PON*m10##!#T^* zy%wjnLaWw{17~YT9EA)-uS~f@od6AMMo1#TX@~lw*Jv#VZUF{k><$D){J9bs5&&NW z>ZE46{V7eP8I^N=O2!8G*8FFi?)qY9y%EYd%;9G(!q`{NjIQu;%lL!2qkeRY+Z?k*7`g_4*}J5FgOxStu2{+84o}0l&v`WD}aq12po%!##mV0UNTqE`mK;> zl9r!kLccQO>ZiptgaP?1Tk6c>9o5i46w=bB55k!~550M!#C6spl%pJ`o?M4(1|Iq3+`!ntj9twuT*F$V9vF_$D$8(zPj?S^C)F$VX0M8QAb z)qh=nyinxrA%Ebj6z?#bB5V%DsA3{?-=2e-AO9NDe2XqZ+_tD09)w(2jk+|tKeptb zJjO4dYICrt(CF3&oDzNDZF z$}S%Wh&i~YUhW`}9AT?ZNc(2Y;XIYeFgU*AR;)rT2i79iV7GObZ4(2{89LYSf))Q# zptTAj$DEVnQrE?T@~i1!;tkQMb`zqg`Y#w16QSnk879*u}7BBm>Yx8XaMvQPk(%-Jxajc(o=x+6SZK_hg$ zXGzq4xS9BKbnDK4diy4yd6=a65Xd>5ksLWs8;X+)r7bn#TYsAbymVF24wjniVZHY( zv6^Cq`qDCC4q7Xiw+4U`LiFc(GSFbEP(?p?V~NO0%tRXcVF)!`uf)O1wG}vLg)U>7 zUHNttuXoNC)c_Cm1wnUzt-cw4f-r=K`lSHVHlGoWI0LTqB>enoB9XrHGQ0HB9JmjZ z7tj%eS&mEa#SKNso`-=$5(!+idp~VxXVcC8O5hr2MK6XqekbVysedcq79wol2da|slsJ9H z^uj}H$iY9Ge@srpc-8aQfBzY+bx|?t&$&?>taYmH?|j;J*L~ZH>Jdy-Aj}jXX>4km ztg;Z(xVSjBSnVgnvgXHZu=tHb5|l@`RV*eO7qj?B3sDJQf7|Xc86E^IDZD7;ikHBa zv&=_Hm&4gEE2*xFe|983CsEay-RPy$xB1^nIcR68r^cE!=;x5KwoW|ejm#QqRi``& z8s2=qVxGaCPQTEQQNBb6HwLnF-q}t4s7=~rt#8MU*8a%DJ^bjplgEbD9v~ihEOFH` zrs=Hzk`!e-7zZ@aI)?44o5$Q7Spf<906>m-N%GiX{hg&TDMMkd&$3-l@&7hsb)FrIgO1zLTDk#IA_=g=XU5+Z^FiKdpLgG-AAb=XK$RG&u>M1W zWJ#6Iy1V62HE1jb%^B*i5tKzj-y%9~t$sj*U=f(dSQ#hZ;BJ({#6bW=cHi zoShoj?Z{YonQ|Khjp-B2KMkFY$+yy7IY!H=xo&co9KsjO1;O>p!sWC#)aKLRbN!tI z&Js6Bn$hx^4&expKnvJJu2QvJGIEmeo=M$1t1oZKOjwmSz2M|9ZA#(urS8^hDovH% zvdQp@DT$_dM>tpbr!U+~Nv)xP;g^M?&tI3l^+>qBaPRSxE1N(8heKe^2pyvm`ct=9 zsr-R()7W(0mF-DyKp4(V+d+}5!J+htb9L1{JJELn?hlg{YSTAs#5WDm3IeMIRk};h z2~DI%Iexra5$xwH*`mG5P@YK;H@Y3=P&5S)OR-Q9OPaIpNNAF7#HSKA?#Oml~6|Va%@jV1rfD%%8g>_)wfRusuD> zLHhT3vl-78GT(^?N&uKZmZU4N{S*5)0G~{ikiI>=+95Ghj<&^Suln`Ym(FEe?i3my zn*@8D>?GSQ7l8P3-#7hZPhe7Vp9(?e211L;IXkGI^`xPuBSM=q$J+1-4Gy;`*VgV# zN6tFFHZVEOgclk@Y5IPO2$R+RzG!|D<$`P^=OPZHL=-5(y#eK95&{5||HRZ|l1>-B zx)lW}fJQbea8KFB&4U>$y%5{+%UZ z=rQvu-dLPa3z+aG~WS~x0s-)bl) zzDZaUOf^o|;R73gE=9y{MS)9I7g=8K;4f%mA7!8&YS#i>0SL$8&YLcgNdx@S`B2zx zk{dA-j&ca`vOZYqIqe?NwB{xxwMBn}fT~v+Y{^x7)5~6E5`s?WES_@?SVkl$c;rLT z0`=(78z=!x3)G2lo`zUMi)>+M)al#+dO#)=v-fueok1xi_muM%9`$A8p10{_bN?!> zpZPs64&L7h*eT0KP^IaY^-2kv)+JINpJ^fxeFwD$rSjZr`IXhUl}*U%Qb+sfwbV-{ z6wDs8zp`~R!{DCVcbP@Hw7IyYG!L1p5`4u*S zBmp2nT=C)R*CGp)G_XSV?Hl(~MS|`1qp|I^BYUQ(v$WOJe=RtPv1zkqK05+8AK{NK zU{t&~vG@r4m86Hmx zbHeA@B@pdMI@@PDArPUI6N?yiuk(R>)IS5*Y{;@SJWg-%LbAXWsQBv;S25V#MQFeg zHL;5U9TMy1VD_s(*INxOUz55hSdw$MF8dj&>*B4+@$RP90a;xZN3s`Fo#tN&MEYXJ1?t0BR4-!|rDC+!*SqzaeXK77e?Wv=gq(mRzCL=pA)H_?8( z0yC3F4jTa6m7eVA0W1B(8N{nfD&p7c-*bPPcrI;5sm-1`L~O3??t0qz7cgGIQk2Vn zA-?|HN9?(ywm6<41OxD*~isWblCo?ni2ZL>Y!2xtHCh5YqH zrs5Avi!JtZPtAy>-KP#bV2~l(r>^A-Kg=4LG)3OlWxpoJ(K&|d8HwV8&>m5x3wuWYT)`#yf7w8e5B{VY9Sg}ce?&j0i za-WR^;T2BJypev*)C#SdX1BHCy)e@=CBG|y=+;5lWc!#Pd5e4djT$$pno zQ@_hs`@wpWh*}fly3soL1#hXNmC5@tb&j4XAlum3=JPK#86LoNR!oN|d9J8|hS``;b6pN`|R z;eaq6Ub6i|^*zqDJx(^;a)LBi?Lp-z*E4)RU(^JV{|wI|b-fOUf=t4&!$lr6{KxP8 zFF4NqUdYh6#W(?P8&z*V=wu&}{~Zp3a8gIBHg;k~p1IFDj{(-S#6jIZu#&jOA1ajE zL+6qhBq3M%`1+f2`aaNq59sHTVtc>yFJ5@F#h|8s`y!sS<$EYqdh1)U!q2W}oz1f2 zb21ps1~J%HCX(>wYYAv*?ijw8td?j{&s~cix_a*_Q+E=KlJMK<-!}ySFb{^_?3FLx zOK7VE#0mx9{N_u#G!AZKogMgELWjAi8N0~tCtI-k^c|iVh4tkZ0)u?(>T2nKq_GI~ zWkY?#Vgm{P86)*O7Jj!+>J&P4>;5@vjJ4zQYovjkUgAX4lgFJF#hRc!3$}4D7 zRz7Q0;=q^xZJB+~y|7O!W9^nwVnTP-YdVPFmq*+7?>zM4Xp{h2XTO3Ou&c^u+YOo6 z`VTB;+0@_fYP8fFD>=a%hARu)9@Fw|-KwRRR9%p9P4d)1&6loN2fx z>zoAEe#Qx?<0w|m0cA7!5@VCT6+60|B&<(s9ZF05b~z|taLB7;W8$_f6UzR`0vw8H zwKq58e&A^m*#7M~`vG&V_H0!k-xd(zJkvN1S zP2BTuC#TQ(Gwaoa^f}xvT<>X#o6PU{o6vot-1EAI8ZM67=F&dv<-^MP*7Js67MM19 zas3RAuAtXRnG)pi@(Auo^6#l^xV|AeWkoj;=B!+^qbD)3dcFl`Qv$I@<;XmRzJpEI zZ>A*Qb|$+?`E%K=moY}!f1eSVg%&hD;%>F4B_-7;7~pa5fH zMA0x??dHax`&x*i^-B18Yh+WCPQP9dH~jBh8M2}eMVA=kM-$j0;>QFk%jyzuO1>f~ z3BCOnfyg>ISwq$?rC0Rp*Ym?nq}4P0ur1o1S!&^T)m!wUJektL9&L13jXR?dQ&EKj zy~QOe34of`lbV*f!p*ZY<0*S%Z|=&kd z@GI37BDO)>Tz)~{Jp##~nd$JZoW5uL95(uqTBP*47iRWzo&EoADCbC4`kys?#jBag z%F9($jRO}SBG*_e(>If;=k-^qw=3dFr?(Rh5x+NX;hRYN{ZV~ir0}&G2m~qv{~e!y zA8Ovyb#u8Y`X0SnBr=!+NASC@5Na?5zp-SA4BPu3Ay`C6@S8}z3=ER(w~2V9nrHh* z&+FgD0mAhk|56Ki+}{kkUzu_~ZY%08``= zd3z@ULsxH~YUvao;T7EcrPbc2*VFHmcU_Tn1E-1?Yc3fezqEb*@4oKlnNk$z`oZ|# z>5@J5w@_zu?CG2Yxc_`}lFj-9rDR*fx4$=Oz~I9-55Hs(N~QJEPW z>1=(k`VJz$D&Lc+3q?vfWBCBgtSWj^8<61m->@^TE;HM# z6QyIbb~h>JROt-uy{oLm<9BtqK|Rf6q2u`HkYAjZZnWy_;=?msN&3$hg3ZqX1Pnvh z3I0#W`VvJ2b9bST%8~yalg5}Lf69}2;rc2`Xp4(!x^poDm^Q`osQvg7`Ejo)i&la2 ztwY}z`E=q1^L(oXmu|DF>-s(1obT;q&K$4ymJh)Wlf1<0y2P62`LFbg<&=gX6 zOqBid;N9%t7VQ6wKY6jd>pGDMp$va7dUf8Y>>5Z*))MJ1;>P+FOXTI!+UJr{3GTQ< zo{?9c`K_+!+~>&9#ytrT^LUc&6WR5$7yEdt?~Ax}`QyE0{BZ4iZPvwQLW2|}OK83| zgCSM^`;J<85bDePhA&A|?nRQwE4^caA+J*yM~%_Ecn*K2M=ch9cpZ-l3DEiA! zbMA5D*Li;v`O@>e!70O+N{gK zI~*|=`Q$t8{t`>_vX#ETwWJ^UYRXY)jQXt==gB5mS=2Gde`4=H5J}DjiJm(+-Ts@T z8|^0mv>K9HelN1xw>iC8S~~nJO<7h1u2AReXzc61X5>m!lijuWmL!?$2j{SaTK!sQ zkS)#0n9}%GvvoOA_)(mhy?%2sA242c5OvhFJDVJ2)l4w&zy(f-!%3BGi1}USb8D@1 zUBs)iBl1u|OKA-*_@>vEdzC8kg4K1mDSba@&;7ygdiz{d4N#CP*n~J#E8s%UBiYFC z(=JWu?Es;!r>6F0CX7@2GtV+i)X@5;ZHaOwNp(LwlHyh`xrW0i31hDDk_#F+ zEq|qHi82kxm9meUadEE#i?ZtK$p5n^hNO|mHgPiTJ2dnYmMjs1*m4%GfvCZ0#oGcj zP}8kemP)~YEs~$E*gx^PxA(oHip0oA?8TM)tN?}xLbjj0kgE_!Yv8XAPVi?*R=FCm zDLv@d)YbD&Fp^9L+peL*%=8k#`t?Wc9UHtku}~3fy~ah^W(lD9`zXiE_VTOvy+D!7@%0D5oX*4utmgKy@`V1zRMD zLUAnn#P2KPq=d`t;PFM0pdCkHMoL)>|LYfP@SssCWOpkSj^t98)8J2L612@0SdMvT zdxVW@@Oa$L2ox(V&N3pwD|p-EJec*O_}`wlMcN24nZV$4mWP9;JtL?Ad(jL|0rfd0 z_DA@rU8@f_wDnjJ-1w8j9H5ofx9UI1@W1;1Fwm5>9Xi=L)_-08a<=ho3J(vfMS}x4 zg0`vN=X&A^{YQnFHdhn(dOI6$ht50NWSBf;drK4gb$5T)d{n&!H=gepA12%3W}(Fo zeO1CCrGpvNIV21dud_`LJ$r+m(y!?$TGq|=$pcXETIQ`|?>z;;k*`tE3SHGia(7J2 zxcU8;#nq$f;}5E*Xb`MG=HqnX7~7b^M!3QVgljrdvokX9`UHxFKF&-lo(YC2FBRbr zZU1+=%%lE%XF3%tqco$TYWRp7Y!M+7ha=fvIUC&eYFiCWqYZIuW4D6KbIxZKo)^az zz>I9%@XR0J5{lTCe34d-!|%sjm$(!hPq*K#4LADVR_M=NkaQI$oVC2E%@>N4DiwJR zin;%=sZvf<4$(yfQH>5oFcom%dY%}D0{mEDJeJRGCTr$&3Cy!cy+eESbQ}ru`uS=b zAq8_3n83D4Wr>A&9Mpy3kSokCKbS+Npjz2bbZeg>W8s|W?FGdvav9-9t+LSbbP*{T@uR>n~%S;RGJlL~34 zIO!Rw1<(WDiWTDfJMAAQA9lfA-!dqo2S%R)t!k+~ZcX*N<_Bt-<`w6QWYyqBU7#Z+ zgcfAdHclm?9;X_~X&nt=9i|BLczvQ-IJIB9Y`q3xU^_L{VgJ7Re4mLcbYIKlahQ~@ z)6^;M6=pn1gXGU0VLka;sS!g!v4tYSm^}|-BIL-=KmrG2U|W%+&q6WY}alQmZySr zz`6-3RF)+!-`cb)tia`DYm|WYtFDA+)>wZ7q#CT;V$@J z2AoDFgm3T7{glb9I{tlm8}gCrSw2zIgGaGsI!ThfA7KuMP$Z090bMe_#Vwzgoq|1j z7+W2N4(Cwv9Vi@%@8j%jc4MnplEe>ufof+Srq~FqFJf7l1i*LQdcK|~7nr2eh4uQ%ExGn3VRqb@FB=Nan!p0d`}FipgQC>sR%LRQocdD9RC;UvQOMr zHT};$sLCJdezll>MH^1vhTw?VvSK=vE6nhv0ewVd3ekgL?oIeJHq92xMo+CqM2y87 z>taw`o-tw_qL(&=Y)%-N^qiTMhO{4fu?l{Kdv9yg#jlmDt!18!C^?PB76&)DU1;-h z4@bW>W}+6oCy(H1*Q`60nN*{#@V~GcR>R; zZR?k$E~Y;!@63b|M8Zbj#+v-<$VZd`X8OJ1}c==lbSq>fVjB zH)RVBOk;nc%b#otJ+g2MXXWxtp&CG|+ISek-$)yg5tDE9sNl7{tL@b#y-T|^Y%1SN zG3hKT8?c_4s7&hVwSMSzHv_RiyyGxu&VBBCUweNxtcD>T(7awwkPfgmi*PA1lLSthl|X&=qijWkeSsLrx%s#ES-iM$@a%wc#4!BqMu`R(}a^BtY=~ww9 z%I2JJnCpY9WL@Cec%^=}Ad$fzdR?G4L_{?Uj1xfPuKtBo(T)H*Cfv#IQosn$2=6CE zL!FEt*#!QlDJNK=)umgu$4QOn7?;6#^IP`S1eq#3*x4#I&~Aoomafy$IyRj_HF%&2 zwGgRl53|)&naP1drtR!LQV9_m{vm0fN9^pRvjx5GnBr`A`I9=Wzx_>Ul4^Q|{H^Yg zSbuxg(nfk63|F=-ch$U{UJaYh`x53)JHae5J+rn;{ocC$Bmtibsgm=Q~)>8zDC#A=#Gcz>bkL%NpLP{R1$ol@R6qUoJ7{UY$Vk_G=ch)ySDfG@MLZihC(&a3= z#f42`)pPg(aQW8P)<3r2YeX~;W6h?c=8aXUyswfy`+XS__Vn_n!Vq_ub%6J=El^x` z-qYpjvHY2se6g47W~gLW0|GL!h_KZH$L82C+9qP*J2jy7Q2ho+S_UL0UtWk zu9&-}rPARCNrD{?bExsIFHkCMDW>2SFS*SrHhgRJBpZ=))j29|L0i^VTe)U?cVfpB z&KPdAS4uVm*76Q=R4W&-nG{U9D8sUst^nbcvr{*&90wceYE;tv@^EED!C1s6fkT!4g9bmRDS?Sbt zj?Z0lAK^r{W==b)sMFDo=t<9v74v>(=gl|Tbu*1J-udJ4WB&+0Shn%GuVg{>7iaDQ zN#-FZXBha?XD8R{@mCV~Oi`qO`UHWt!i0%+b&J^j^uE0*yz*B_B|fehqz zn_B~=b=CKR8j%L>isf8MjDCvjro}rUNUB{Wfy7(tig2XU88Fy_MVqlmdEl&JpwYN4 z$C76b9+?YXX{PR5~I2&Z+^=niK1rrPsuS|c?F-s`z@##bJszB$&*}8nl^gLBcW#-kNFo-)vIyjS)uu_>>uQ3g z?og<_$}7-dQdbg8iRS&JhkUhCr1bYNoMrU^Yv@*gV=lSK$v?mcX_Xn@$+fUK(LL!S zS```V-_!B2!v%V9im``N$kvQiaix(wK9`+tH~ znUt%;4OVA&o}G8zYx}W3xE5bg{e^+ZSUGz#XKH|+=aYblp<=glM2WTd0=r3+ErwTJ zZu+eMwUrvDZfUq4yFes$! z56FN`iE?B(W~g>Tqhjf^Cm;&sZt+l2E6j5Hl2Oa&*IaKI+W$&Rxm8tz=i#G&IDw6f zwbU1VQy=Z5G4b)`+Sy7LNEf|x^V4JMorei&S!S{sRU8EOC9Z-d>LB{*E|-(42otr% zl&+Igq}h)=6S!b09@PO&4Vi}@?|Z7&nKc%Zu&%o)Vygr-@9Sy9*@fBLPc^tnWJk!J zsB@Nobg$!YZE&kPY ziZIb%OP^XT#=IlILz=chCi@CSb{e`7k(@+YODQ4D2bcq_d#Rjc$73arab=xSYp=|D zHqKt!M2N6Dxhp@0BQQ#X0S4T!X0X3~FgdzlxRxiMkrN%B_lY`foW$0Kqs);G6$rAc zFcIGC$_|JpLBUe}6&!nL*s~`QBN|J_yj95XY6Y4$#d>Z%lG$t*pv!$4H)Vs%T_!7&*RcA$U8GY2 z;>ch(3MD$;7K!^J6-=;FTFV^pVun2VCK`OUpg#e)m(BbMx@d><3%0}^$5?DcVmxpy)ENkx$mPQ}QIi{}=cjAnF=Y5J zuass7hUVk)0ivg52G!UXZX$}K$)RxsGz2x6GhKHB)yN)9;aMKJX{oo2DeF28%(C|| z+Sh*3=e6e)e`>%Tq-ZjL2y_^<-HOM?7kzBh7FTi}&Pyrd;|wERI;e%LAh4=*#2TjL zqkU!-uHtVhM6F(4IFR_XKh9PJ`V8;>9@$K~k>SY0mRZSIP} z$Iw~b)=eLgtv>{&F0lXV-QvvzL7@nbiwjZnPAW7qB#w~!Mo)`TpyIBUxHUVpbX+_d@>xuN3%P&KDl+!WQo3ajFh;2AfUA^H(3jd995(fLKf}pY z#uqz?Oo>Y5o0FNmGfGd6jm&7JKt?S%L{&ft9j)bF1}tvUup0-GR+F~o-`&FLN|s3xV$3^w&j;nUU12^VRY9(AS-gzA6d4T6arf=4s^w8HJb?oVk-T-Q~z2f=in9ny6WLvQD$ zgnAn3N?T_sl}+Q~63VoMNlRzpIIgzF@BAIG!Z$1jPsbu;({ZXMg>j@%l^b zGCg!sLwfOiKkI&;)D#TbRSWr?E8_Wx72u>)U~= zIlAhW>el%30>nag<|9C(s-dpLynjo-_F@J@*&N3bCo64rh?gh=Q4Lpb-3+uWxy zQ{p-MgFwX0AJP~jut)6RT@rVeR=v=-B`?#f8^S-O>e<3^p&Ew}78=E!IH#1s&r46N z1A@rm+srGc9T=}mXJj}?riTliTm906@=#m*JKi?8o5x9oUa*Fbv6p9TBR<~?Zp0X; z5j!bZNd(SEN?-alfFT(q9+oGmTE-z>nQtXxuNzlTKyela4(~^$grs3fyp`e;GMQtY zK9AwM$3p+WjK{4p94(% zD)9c;s-^r*8;@m8;z!~U!-q?_j zbVGEMfJV%RYtE)Jb$z;U|k2kMeL;Z_ddXhi?y<``bay5SM zn`S{Fz7aBBa3EIKAd^w)rZHuf{BtY;?8z&WU^ahkIoNvg7)Fc_`QH6>2tAp@oiDSg zx-Exz4q=&yQiXKRLUQOc65s09v; zXMYt-eBXLt#_D)JzIcnvI{o7eZF+fMaO+tA@Qiy_2 zq$vz#%nwYaLBbolY|K%EzN5iSFb7W=jO33<#zoCPk+1aQk<-#AK&2+_Fwy;6S{vto z@GJsZ#wP$sUg((GC=*)%BP@^K-uNOg5SqvNd9=)Bynx=umcI#JN@s05+v3*pMh&xD zrZL=iP<6ZO%oD@Ty*bLk^+!pAqA{}e@N#IJHsQ?8b{>t}(Gyx> zQk@p$SL9Se92oE!v;y&f@l4Gku2+N%SF@ldThJZ5-jAsTnldATuVy@MC23I%^xK(h z^`Wm}EUT5a<<*oD2jYoh0zO+tW>%V_9UZx4y-A|>|-+CxSu3vcZ*782HJ$1Z+F1gvXf49tLJPWs5oSK7> z4`zrYjqp_lueFgh(6HrO>MaeI;G`GQo0bG-$#*E?UN7HQx3_R=HcWzwgR(TM6f5Ls z$ezFKZSCR~sw>u@b^cCs4wum;o6|xN)!_ClmGZi|YO!oTo7^WsDE)b1aOK;5_BR%9 zu{+!cjOmGyTPs0QdT)WJfsGt{YN}}%FV>lrS-_@8L_F}@!Bpjf9B*mhhv1hFD*nvE zD#I7qjKZCGQ)m5#VzC&;W16~xz81vWHavNWGYF`G1km@Se-nhRS z?>tAx+E)CS&xxo~G@Ym=R)i>uC4UsS>XFn!t+;g@J@RgD&<5sNG3UIVG^HFQha^Cj zCBLy&3iJ^8a;ZUlpYi{_022@pw|Fcv?KI^UYp_<#0H#LMl6B>R5>9G-Ix3^iQod=C zL>d+j#ZevgFNeGHpK84#(+iBX%RHjbfyGU&l|zT|sJBZ%YmdW7FlW{Zk*}HH)@9;t zcU(Uhh>N1n;%kkM%SYeb&^6jj*3W;OhH;jYn9*^d&*~|3w%28Y7&HMRx*o;{X%XjS zTg`}fPCZ(b2m4MpMSFZcEVI*M3yGWiejTJn_;js>Sben1tNeL1l(I-{kvy$bxiTzC zypO40+r=0%xglA#4a7<^$^?-F$5yBw{MnhSfoa~}kj23U^ozbkPQ~tA!I)ijQxmjsK8k~;SRC>47)r4K68EGn z*JZAzXJ%-tXzQKc^!&QwULCf#crEJC1%eeABBA`=%II2mq?Ra(R7Mi|JryZo_X)dI zmKV(H`dL|Kl@2`d1EC;SM;YQMvQgad_iXpDc|4Z(h1^S##l6_jHIY34H z+n}0;iV5aiu+mw!+(bK$9x+&AoO*jSP2=ff@9c{-Gnd^H$c6JoCP(3xwf;B(B0?c%BFpH^Uo$QHwsyWpzF<#uEifwCd%x{hv-(wk zN#KE0`%64SODc)>>L2^E;v(f)b|4vd!O@~lyJ4ti9~@-JzdaNn8RxdYx|7*i6dFwpp`qodbw=#t3AfG?W}V2X7C;S7HzF zF~b`vVZf1dEkoV1XI``6N_=or^}qyxJ8i2H3+#Lgy;rhqHi_*n*{5H+IWB`LG2w+O zL@E75(22NuU$U}-kD&W5AHS@S)m1dl6O4sXmIi+=$)MHgxHp-UEEZUD#L2Dk4mM?x zHWt8W(#A|I<_649|Ff03K1mb5qf+lTu4-WtCvT)MXR!aO&B5`%kk zT&b7$@?qKEJ~psHko89oZ&2y720cB6L#uRiD|}rxuMnTn{}7Y%W7~NOiqIY} zS1eN#`<@l3`4E}RYa$LD$4WA{Zhkw`fu{_w{(B5X}Os_Qo6;6C#W zO0I4xH4wQX{nB6`7f?dpYxsrgJ^kHwd1r9*jnC!ndOT8gnmejgO-#hh;GTuaF-omF z+88%&T8xiu99YsvcB(}-Em^E2kilx!imK7Z@lcvjBU&k>hoZF9kcX+?XB)#MGJJ(cxE~MtGUEc&+|M#`b4c! z*q3|vBBFLDb`aAKdU%kz%jZ&I&wR<#aLplK zQKfj-yNzTx+K|cN4Qo-d%`(G3y66tV$WvHcI;?J)GO?-X|Axmp%f~%?bjaMC*gt#b z%s&}z{sSi@o8;A(jqAlzUV3eOg*x02M^}w@Ul#UKhh+XSY`GmTPWJ&dg~nDA9#nIo z=Jo4!^TH-Shp&4e;@R4TsiRweptBE;M?Xy4IdHz${@9TS$ZA%#2WaaG&y8Ii9l2_w zJm|_kGLC8s0LUnXX%8{BGuc=&t8oiq6&Y+m?3Kq_YL|H*E7mtWfPe`3PZY;jJay)n z>hH-73wy42#pgnMKm7YV*{N00Z?fe}qRq!u)OVy5YY*6$8#N`y>PfT#MK22F-`0h_ zcLiEK7y5x9vT)}&%HpcSt#;s<6rVHgUwF2)vhV{!h^uVHDY}gMi+xwt>ghNjagt;* zkLMVdvo}78QGE4#Y;k0yk9j~--g-g54j00blEt-^Ynyuc4+s)y?rA#Kv>Ll z!Zw?_2ql@2puS%Vxz!^75HX;6;MO+#1~~P!%2c@~flt0xNNB`sLs;Y;EL9Z0nn3ba zht5a6f(d}3n%w(?zPAkVBK}{xV12gTwQRH9A_>*fJIXyYr77<3zF8T48CIw?Q+AL= z5w#xJ=GyI^Bd+{RN)?|R?&zK4hF7K9;c{ra*ERd;i6(FLRJlrny9Tn`-G}Q;onGea z1p+3xB`=Rkz)DwI%EX4Af-)RJh9($k$nU!O+-gV$LA&^!{kb|G$}(F>Xkada4Rz8{ zm3!SspPVRJkvR4J)JmGws%z5`yjtFKYae%RV4oG@xs83jg-$NT8X5VhR5|lhJNS(T zwu!-~6z~Tko+}5xO>_0uw|~~k28W@!cGiU#ei$idzI5L@44o^K$!9Efz?sO~f;hFk z^|T?CW1Q^y_ttRX>6?%dWk(47SO4DU5I7{&T}LV5@9B+&^M6M!!HqxHGR6FlTN&a% zUv#!FeUc)=x?XCgs`n7UndoJ89?!DH68J|X0u52kLcML+L7OjE$2$*6$Itx_UZkvE#-p`#4#&L%h zAVxS-Kgkww@3)^%o*3v5brPCsO>6ZhDzfwleDP-Yxbv0XcdO7hk3uL`RqxNe5uJOe z<4rW})pNLhfgvrU+Jf7~L9-@%!j^&Wr!@ue{Zqlp-daMGr?<8RWGm=V z+ys><4a~Su-Tp~GWs^TFeQ#}V#(od}5KDp*RYgIOZI-zRP>SBb{zhu#Xi^V7lBN^r z3_U9Vi*i5z1p!zpjpuV6xNv^uOBj;Mdez`JCoA<|K(QRIzF`Y za868=j>j&OOLLBfTLDA7VSAn$2AOHL{29XPhUHx?tLUf~a19l%ncV!)@UHV8*n{qZ zuH9Th+==@4xo_1B;S3|6#TIiTccg&my6GPy`+dY*LMjNBf^HorR>qZe^7=n~>#P>F z1UXhi&xPfd;ZCoiQsw}(fD3Ek*nJ?<97n54N77oEcTBgc7oii}YbcaeP<%WU4j6F~ zVq|E850{qEBJh_EjU$G@%a-01psKTUuzGg68AudYT88BDWg83_UqX=&+kM|6t1^ z)L^vTLX{acVLKu*BOTF(+&WFYNaQ7uI2WgKGXskbIzw-ED+ssRaci_!y|bj3_(T-W zck!JvQqPl6D$c%itfX)ao_sm`@2h-vx$!dYaXMOG16~c(CsbtEynn)YPJ25k5%$K~ zrXe&xrc}*-S1ZJnqDcKpQ{QUx?53r0b)XKHQvn_JG$|dxQ)2F!#v?7Iy+E%Uo?t%!ea6FzZqCl0B zb+#FZ_#6#9y$F?Dn&|4?lSy|x6^n%xVUMFdopYQ#zyV~0$MGo?r41bM7iH0(;uAI` zfy7zn;{XO`Elt>P%zrE%bQzAH;L3TUlr#u60!(7(jA-xgr(W@tyD|w~6{kR3Wxk

Pb1Lp@&0tMd0~NY>*W~-);C{LCUga(~Nm2?0BgG7lO5gA}6F_^~on? z1F6lrT;qa{Bsdqjt59cl2i-_1Oq8DJXoz_Bgo>I|-HeL)(MJ})AEi5xOMY@LPG*=o zG=W14+G1&t!i28Ql&Bx(I7+oCjBhE7G4S`a5dtZJ8MP0qOw=o${9B@nx2L-i<>!nJ zaGwcSKyG@-Ye~BpVWu<2O_fy&y=rF&|7<6xwh;Xwyze@RZbVnD@Fe9|YO(V|eUa@& z2)Zg!0Ccps2)b2qy#rOG>vleGrwn2xGR*@c8(Xhdq{U$J39_}|{(9Z+9L^if)#~%3 zvJgjVJ6yCREHR1^06l%~X+tA}=#vaaE6MQ2K0M_Ot9m)TzYzBd>cY0`vx*m8 zw@xj^4?pJu!+9JpiN|_t?#5XMZ2h!YtbNPNgdBR^p5$ zTHF&lr}iU@ zL^#C{kH1qN66NPClN#U?WbHdz)^*QSj8Bu{_BaN&4W@G*u%;&HFrgf`7}FgqVI{T1 z+=kdfEgEriZEfxp)gVu_ti$IDNxQkr{ZngZ%I&DV95!P6#1+?F#)6Fr5=7be1R^Cu zi|z2;wI90(*UJjZJ68e!Ob)k=`*BbfMZR$)b0A(Z=xW_E%X%_!s3swla>xiNY{h`l zScuVA>w%exT$Nz7K?}~-WVWFOSP6(!xy?~c{ic>92kLI?JQKC9<|MTu54x*P1#=m~ zn4WoVVYcZ;Y+}N`blUGRd+8$Cr#D@cIT@U0S`DXC<_aZ>8U{{nMLJ2R&D~N&Gfka; ztQdj%0FQO7v?1NE4-WVn>ghi(HuH|8h?GhyruA59xzF3afkf44FCr3jSiu_0Ls+N64i2!BU_ zX~l5Z9^z#$LaHhEQm=yw=%d`%Li6A&`;6Zx=d3q#2f^;ET6joGEU-$Oo4}1Exyz`tV&j|nFK2Icype^D^P-Cf?H%7i_yYsdXud{ZIG0#Rl?$A*jK(O?$* z4<=GvSpsK6+k%tlmwZYq{GpmRn4eRb!;o_JHBNWS%1)4tD|v0z%jB#oNIx5$Nkvb* z!JX8?3$>Hi_pb*Q6YNxwwZc|!vB&9Gs?q_JB137C)Z^bALd7Xnn>c=&T55!wT#1<8}m|O1>c-(XF!>z<(7fzU2vb)}@ z*A+HY*@=TE#+$s$>PP`TD(i9&7(zVHs$ZElzs@&Oj^5FNUD_`9N~SSW>n7=}{rgpZ z*#T|KH#}9Q6=jr^hnftf?-_M$4F_5F{5Sag3+Xccl-D-Qm_x2X3y>yBs5x75z% zpHVlP{)jaJQNFL~ro9QW&amFndbDMB*Q;JQ3INwN)~@pjj zMy2#~bCqyOtuTcMw+)g_KtYQIt81cj)_F7lmj=;A_}`Rjmol2PJ?PEr z4`dD*V-U1P&_HSDeLFzHRI z2qgYlS^cP4!fU?dgh>3JWuehy)_Up?J%A+5c4JQc+_R!Z#SIFH>Am8fsLk6@CqQ{v ztqBh+{TxCtjw>E)nxb+oD*9C@*8QpEEBrsYO8EHY1_S+L;jgH-Qn(k_K?!3wpMaHS zBo$|x&8%s6<^~owTd3DmOpM`ofigYa>)U0Ui!6W{rfj~hpK6iL1g-KxI`ev}oF2%f6JSmaJQJ4tPAHirTp&*a} z#~6mJ#yM1r)#L5wXjD{M$~u)p4We_7_qx|oI*6X=%o|j4e#fp`{*NaO1z^Y^(bHRg zyligNS1wbV+DT!H0<6u>dd7YA{M`nE*ook-1r^GVRcjzQT2wH%0TdRbXJ)1&Iprj7 zLc8hik?qc_?D*v>(J3Y8YH&~LdN29>W%Y1_FH9oNRS21+T5n)DY=3g~k;a0r-N?OR z`J!#XRXHk60z$B@3Ve_!7avm#K9<_XgoI2r8zs;XX>$|f#do>?%t=IDEsoy$%a0CK ziW_z=pIPtTILszq&$51Ixn1N`(CwX?B;rJS=QJZSQ&B+axBdIp^4scN6Q9n0x*qHA za+7aeEx;J}MAq(6m}r|p&Yljn=3N?0C(hgt=z{2KZB+uh@pc#RcXxTUu zkXq*Fy=IbT(KHQ6(l*wp0|BhnFl>Sd0X*gRump>Zj2C$U1uE;Gb0yWWtfdt=gq9cg z2uB`hHVTgzpdw^YT_lAZbGhRE0hN!lc(ywgh(ms+?EPYB0quTV?qfb_nJy8o3edn_ zd@cT2bMUwWfop50mL=A_dYq80Dj(Dl=~x5GoFzS>i3JBvpl|{)?vSB$+~mCN$;}@t z1nY9O61N#G3X8NE%bW86jDf+aQOBp1EkC^wX4b6xro3)v#J|bIRlOHSuz`}VMF8&_ z<>?gl80={}KAsg_X{FiN_aObfZQHoz(~#UBguqQ}qVT*$aH-PWeU#mcG6fk@t2S&iWCdcVO z7fD9>*WOs=m}-#3KL;E2A=A4sXr0)0A<8zL#nNaPPIq4&An>r1EXPl^>Wx&W@_E5W zZn?*$tT)$p#_|xJH=fe(kAL{0#VG<~U3qu?Q_oij)HjPBTNr`(;+A5L+nrl5tw|l$ z)3Pq1q)K6=$b%h~%vkcp5;wOb`+bEY*!KFrg z9t*?%Xq0D!Yqae^qzjHVJ+g{x*2N@4QkdSU^2ck<^{XPwHhfX&4k`f9@4%i}M2ShR z*~{5seS4#FsS$;NShhh(<@Iu-!&ZXO5^N>MhfxF>wfAG#UoblhlV!UL=f|{ z@ZtBWR=^J}3fl&4&SxtmGJ%iLA|k84U)h@3zu?g#Dny;l$a}rBu-$56+;($T9V4HZ zE(v!B{oIGnolU%a;yI_h;nZ{e_y&I-&n!E;9}`%^zn9^KE=4d8|E`k2cEKt&q#+fY49pp!#ltdN6{{d2lGo^K-5e@$-ag_^~p zlf7FKLyGa8dfBnc9gg_Wtvso#{2m{A{!+`jjodRwe(P4Ao}VGN|FOU@+KdS!wby&V z#b9=*OeLJu3s&ONI|r&I$|@$Uh%34%W$YbS3uaEfg~||B2%a4 za+O@qpMm!#snxVS=7TUwaSYS^MjDg|T6w5KkhptdioX+Re5KUTkKXDq;B&*gUIuu%-&Biv znpv5UXU}Y3PrI!jX{s|I73Sh|gI7)&a?5&h#Z_Mi8El$(utTGez5f*G*Z+xVTvQ|x zC72?W3GUC0?zqIbn0u}9eeKg9Xn!;V{7$x|D(^$T;E!?Z^{*nVtA1o*3xI#iY-r>a zs7)YtuSK~fHs}|KkdYyXD^{T1l&vPd=7l9b{-2#W*-|{Yh zccvM}1$Lo$7OTQVi-@Z5f~kTvZ*O_n(%I#$XWbsU83FD0^BNZ#iSH$=;6wcD*{sdn z@L$`*8fr#4{?i}H>pdF2eKM1%$k6Tp7CCZ}PEO}`6UcDOOkF`M=IlpIR$q(@Qs0-m z{<}FVM!|b;{cz?ahAGt`jm|BBm%mJczmo;8frXctUw63|R?-htdwa)+f8{-q0eY_`%(x^T;9cR@ z29^9ds0|~x(Alwovu<;o<_-q+bSb$F1@DGl?B^EcFwlPqJN1b*GiIuVrpDW9%6$D9 z^`H1$bvcA3FW`g6R{%Q({uKSo3STN1?SZ(IUSFj4S;F}02kUX{jR4#*v&|=Ml1Q?a z&$WgWIsuv5H*xmx5`?QXx_T3wUbv7^z)c!jgq3!XLqgbky6cJj^*lF?z~;_#oA|%{ zwXxrc3|OclwBt6+VLQ20%4Y_o+2$POsZz2PZkg7Z=dp;-aD8|1?ek z5-lA0098Uk{qMFjzwk549@kj{)ZwS&`b{^BW9#ahnMr${ka$8h0LG$f_d9GiYFYlW z-OlIvkJ$awx3;H#J3+pyX5KTdzB{k|;~3~iHTD>=B2E}X*wD-_Z}3pbnmdM^h{LGv z^3HPSzlK@M9yAzjWM4U0iff{CN4)83t@D}dZq+lqSokvDAO@I8`}5S);zQ2czB0I~ zubx!z<0r|)fz8J>WLGsz`FAL0_oLoT4WtOVJliz9k#R029yHRjAswJmME_iyf&{@e zZE(P6SkVOxS?`xAd4pmTV-HpPN8`8O0}R{h_J^1x^_*gY#D~&9?$WGEllcovrW>wB z9#l(;%e!2QC17EJ=sp&QdpKYE19o((Pjp_!7+jp#`_`3)x`8>HGU9$p3TwL=ZLTzu zbp6jiiz7NH0XfcL^IF@1!wyT@e-^V8z(a0^0a6p6iM(KxoQo*nj|do8X>`(2>7SB8 zsW4&2*az+osBaP?75Coo-L2Jxd(xEES&rPn7t+AObQ1_`zGn;-OBxLKySn^8KNC+u zF8b4}i_@3SabjtCWRWy96k@{Br)#+4v72)m13!R93qHUL!zJ~L@*@28rSqbH!HYuw z1sO4b@jdw{cOHrWaIxyS%NGfjd!RLz8Hyo+sK-lMc{W*ne z3Z472+;V2R1%v;|oN3hI4!$e?brk3)V5he>asMAubJ7YE)vLZgK;^C=6Fv8{%(Y_l zM=~(Z#9srR61an_aEz<@d?Bq=yN?(~Z+WF^^c)Jp1@ACiq^cpPkZ`;2EGSKI0)^~tiVXAj%wWkt= zSw-q+Jv@(806e)cs*OfQEsh2@J*s6g6<5^ zE<^o)KRaino7Ar}3ij*tXM5lJ@>f#Vd9Rjg%fCoX%Z6}-VQW?3YE*_|jTk0}8_*C{ zSO9)nV9>Aovr!v+d<&ae0SK+L6^bve{Vcq4AmFedQdXDGabx;&hHMt&b-okp@<}4d zmK#QE)p_1TqVMoZ@#i1^x3{e`AFFR7ggb+5myC6fxIW?PX;Rq448;Mrc!DcGLh*m~ zfnRY>n}~8t9RApq7N-?|M!)IK&pkZ-9|;#NT;qlQVXEbhhbEiT4EaLxcyNXpvX?VTsC2|0{|$K zz<>WbX=+3pn8?&EU*T^0Cp^gXe3UJ>dV8aP^@Upf&LSF^2rxYl zUmJJa5bBThmyU#=wj+?FzIrN9K@+)e&M>L)fc~$bl>^CSClV8J9EedTg$X{rv&Tth z38~MMe{fJa4QR6<^|5|wL@KXqg-V;ltXkCibMHr-khi((J@x$Kr4!o{K1YP^ua5%1 zkB;cJGUJs zZvThYOcrA=cM#TEQ6YNLa=UJJ|0_>SsaMcMyfE+rwDjw^p2jivAM+-I01iG%INwOG zys2AO^b5cQugx1p?KYg`?Ki_yaUQAU*Je6EB5SvemTu@i#KvLNwP2bv=Dz1Y^Io$! zZ8_f2ENf@@WGmRzf7ki%CIKqovl5==n}oN*|J9D(ibpvX3(Ee3+wa8Rtx!wPhf&L)r>oC0`bE0=BfpHho+N%JG z&%NPr?T&=+j)dEDQ#)LbP7_?!zALQ0pm9H6^@=9&a3JyT(X~BW!+RCafQ}<>%U;+U zOU8k#h#zl^Iml8w=`Zpm(@=7OA-|*&d)G-OhA`7*1mB3MlMc0EOJd1ysAofsz*VHd zhAaA9JXa|5fuUW7s4~&8j!E3bZMNa+Wjp7!yXvaJl#ws{JR}i$#Va%M=vtlY1381u zZS$@>2U_j_nsC$yr{7Dd(_A_kegS?HpTnbD29W==nr+|_x4FccevVN=JfP#u(dvEs z?KH}A#fg;^@_r^k!mbE^V#!%XL9bG^eJ*b(CZ0z94bo^ zPKXNI=JUifLuPxFd;Dl(`hJ@?nLCTB#%k)S;1sQ5wB;d23c`rLgup;gy7%`=aa93{ zDr@?kIF1^HOg!zhOj!MaEWlGhh6>XIb;^=GCHZdZX23BgO6?ECwo`&!?BpXjuJ zql)Cx`6+PU1_b|U_d19bDDR%Oo$ZBp9=ugoPcwcuzSxwcsH*#+_0Icci}-BEnDiCj zBF*8^rs-l*v}$i2W+tT)#vo_vU!P|wDY;Fms2+&7G!`R2I*q@|9Ibl z43Qz<3vgR4wq0*S5l6UtDTbz3Gj%WdiWaQ_C31ky_-;W@A&bfy78Hrf@-(?*l}k@W zf|~WvOX;(PR<2-=Yg5x-#PDDMAd8KXi*u(*(Cb7o&{6YZZZFM;;V^_ z+o4F5fb)sg$j28vLd@MR7OE$_&!*pe9T`^am2#@OVxyD^s+O^`|F~LhUy4f8_fcS& zXa003RK>mUW$zKQR+VUR6S7c2!FlGdXO%ntJxwg7F}&2`Dq!e*n+6WoEx|_cKdfco zN^g`%8%O)xHK@38K;+VO5VQ9nB)_%6wwVC3Aj-Aqm*wXUBWH>EMlBp;;%@lt{=TO^ z7MkkStW99y5Iy`McsCENBrqO$9X2h2!w_L33gJ0)lu1cIZOU%1Y5d$A!GzAJ;?;d? zMi=!6Z-{`)TkLWM8R_AI9xI8UN>H~(9aUN{Jw0P`RWDn5mca;R?0IlmRi@68Flp6q zQQ(rbZ6*ItFAlHSsT! zMh_>taPs{K7q2$hwT@k-_$R(#YI|8ty0T^!1&!r4qH@N`{xxAo==s0C_Z=;;L&joLujT9*lTt7T9&h_)SCykFO7Y5XY zobX%=K9Z7o7CSHyLs3D$pf`k`#!g3?gw*KfweoRcK6b2_w4!u@d^S%ylWT9UU%u8u=|$YMlCgG zI5{<0@BjRt8$vO(hpsLxqmcah9sn_%q)ir{e<7uh%MF-FOABKA$)JluH>YIBXH1ow zLHb=S$AXI5i=f~)7JR0(M0khx_}eF>fv>x3p+|d1v(Hj-Q+G2Cuybboq;Cy>zWNsu zngrfqLPu( zftQ8_duHVxwQAzmp-9E%g2Fvx&5GeXiNet?X;9iQgynksc0>!@=qh3CBARp{ULLKbpQerp?Fu8mG8B z!ySf8ac4M`0i(FXU`TP7;?A()ZbOC*cmJS;4R;wboZcENe7P zxh3TClEfKPn6Y$Rza``4BbhhSDSMw&Dt`TFCfVRx){u*tQM)Vs8mx|L*ZxX*^3hDb zu3JO!0_4b(YF;%$cGQJxhXk`M$J+5h?=cbQXb|iq&0{Y*E|A!jEPG(KC1|0E6= zlcdDB1LL>u4BZJc4Dm~-6Lg0zxNs%3@p%H8RL5ty{hMi^ zUKZb{f^k(_I z7HY`=FWgKfsldg3yDI5aw{q^&R~rm)GEZ=Yje#+Ht)A4o?Pkj-+BlT5ZRubkjtxgT@ow9<_|@jbdQo*dcbh9Ca7?U<`~ z`99@?sW7-5sN6T+-*Ea-aB6GCt6(&LgP^~b3#3ajNVv%vy%*8>&89L_l&tO+ej^=z zB|)DWdhhdmID1yag>^082(J~OjFVh=QV`enu7Q=X=~5o&uGA2kKD(e4yu?6U(QM~W z-~wwE;vHQ|0VAe~T1#?#iAw?e^J9sL1fEf`OEfq^y3Iw1N`B-2^|~3pt@By}P3D={ z9oYr(QrgZ&a_VQ>eDquefs0D1&6KmNQYtWV<~2;;9_thqJvVM!S}&`jOb3z8uIcK0 zPrqH3pTE-31l{?AgaW+=IA9IN+iIEZHWfE&ti#rm3KO zWRlmPqoM(Tbm`GCXO_FgS~uWAgQc?ojct`Qn;8A9z37T=I0=xR!}sgyhWM0_4cnic*JzIK+NXt z5VkqG`Sv!~?c2rl$(Py3a?{{m|->U%Cj8LVnqb0rU|)&x7sFCw=yw@c)m zo&C;VPFgy1&iWH@gmWZ?<0w$j!el~Fl;@xiXNJG$HFB8{!t8sKG)n+C+ z5^2u2u*`bU?>2hL?lxM{OwU`AC^8r4wcc1YoN$EDNjf5 z@Cv0}g>(7Xpw5&A4)#E|8XWD|hzLp_*$CPx+R{;Jci5TB{W^LN-0UqX6i@LtxP~iv zY8{}|9O~yTu6!p>E^+HTv`(wB&g!iQC>|1<9ppZdMYr`toR4_#iuP_{iAWy!B#j-; zSc`43tP0{QVGW z>d{bIlo=8XYJ_>-R6L!L8C$YY3(CUq5a>>K?-k97*o#NN)wDR|`Ve&e6i6-Zh280W zKJw0cEmSLLXZJp9@n8>#LGOAhWgW4siO4p2ixQeZK_pkMTaA$M;Cmb5OMb+nP@=Q) zpIWmtrgRw7p)=EXTEexafq~6v$&t1Y@(;<7DxT0!tzkYNM)K(ttk0v^J{`OUjl2G3 zmZ~bp)|;}sX_?}84~^Sec?nPDmeKe4uPSop4*%ZSONza!!D4i+id*wDA2NoWq5iC? zXs-6wzddoq)%$iu5cK0eFk4K|DA%Dr&h$_qTAq;Zky=dnd8WK?ZnyxYwZ-lW&|VnwV`f@`BPq8)pWo5+`ISk zgW^G#<;Ia8*vHZb9rTC_o_6jogI`vtMvdi#@l^B+nb*7s@3#O+%{ScHQ(`S#pDrhx zW{sz}WP-??A65XzQ1JgMNo!}vI6B8@0!A{pUFl@YZQk4~WL79E25>Vgwp8kCI5 zRd8fA=&bgBRVx_D>}6bfCuj2+t;geu4024h8SUH}x9ajnSp81x{V_3wdO&cQWA)T) z*}ztH?Ev_5)#*YaDb|MX(?*QDf>2G(>)518ph5Gnu|UHw1E}-7fiT!?y!PmOyVKT6 zgoI6V-&he_Tm}hFI@-kTQ=U+G=%~VD0#*eL?dp@Tq?<`N)(~Lo(c|M6URQy)9%81% zZBgXw)#?kAoMof=9Qb=%-8~%wHtDP1%s!f~0Q*vg$iwnD>`I?c;SOe$idVcyzkVr! zrhI2i!t~50Q4?kZmz|EC(BCe~{2{A3b;F-mIVNqw@e!zr!2_XoN&Png#=gVt_uDW2 zg=`EyQnc7G2`f&T)h8}A;oay~F=UDMbAVU=$Ta#Uh2@M13<)Pnfo!z7VTsp*k|R>S z;N3yyPihz>dYAW!49(Ozt*hN2f+^Y@I-H2(C7DX}%R##lplDnXOTtLuV3$qVTU zs6fR@NYM0CVcw8apTeJj-{|%nSb<)-;Uqg9hTb+fmY0;fMUu3!bklw$TYZ znnq&Zpy6;wboZrJ7g}rZh|r?(aH8b(?2*T;vp^^W{70Klx9d=mY&VvymmFb6bDZdJ z1YxAQVAMg@z`8H|45uu9z00Q5N#G77It57uG<%HK;D46{Pf*k1ZxSKDjD?xlSBULI zFaxpu-;<|{F@Zy~fr-E{ZVCU8AUhHW@j&Gq$k7=YhDGkRsFtH@!}{tY*`Z^G1jK#0 zbx7Q$yr)6A+W9_8X!oXqe#j%?Ag5zZ?w1cHR3s1!q^;7WSpvjti^^k*IbNI~7W0Pd z8HGFRS8UWd&u0?uC?wC}PeUzXHnRDE|6haHJZ z>qD-IbdnT>C4B{kKPza6Mq?muSkr|~f6-VGbdNOP)$O9-2^i@ggglg2k3?KOqZv#V z?;cDm-g?`-EccvB7dK8DRqKjK9olfvC5f$)D7Q?}jjU|rm{_P(Qiy@F~y{?X=|$hs?wW z5k+>0F-am89&`c-A=N)RFeP9X-`i0VcQ1yBw6=B&?uofO4jHpJN6dE$9xz#iyd3?`wt5}%90uC*k)IF z4BW$pZ|qd`?f8vjRjGE(8*BK{^5&7Ig@;T0@hpp+;fAzpzKerxrwNPJ*!Z%<+vt3_ z@NN1WGl(b$$vg2Dk<0(Ao*<`c+z9l(J#Psj#<8%VZU455wRb)qFvRCc#~<*rEhXrw z4x!#nbU7V)H^%p0V|YREF{imbgT(3-<&FI6;43mC^1*K{Bh{4GXW{GX-=wZn=?A-4 zt(#$HenzG$4S=BgEYlpYF8$Cu2Hy|a7DOZH`3}Y!LX^Vm=VgzpDosF7c>DO z!%Se7&^Hzz0?LUB`jcn;u)qTJ{}jH*r_zg3B9!thSZx_ep(j5qj(fy`Aji7W@3qcH2iUS3c8$ zGTE(SQgRbwNEZxJCj~K)yY9S$uzJq7QwyGnd;X=@ZB2`xqrk2%B=F#eYFk#F2Weln zgComx3YkVWx|4Rlvla}cYDq>!(f9%8Ies^td3D00%;(h6EY9pXA~=i<`*Qr#M#uzr zCpMnM1;WPLQ*g)xPcL=B%jBj-(QF@W@I}%^aL?1`?uP&QFgzlW;DF!p4cz7PvghuF z6<#Mu)EnYU&!#zYWzngD1~)87bxVHVH?wQY;8|4_?mnl-^A47w=QIehkh9!3bT$dE z6faizwIq8&17(^Lt|37o$Q~m;Y*PrqL{L_D)gWsB-cNk`LqxzoA61nd{zjdP)~ATo zIv8yENI{%Pi;O(6J8OR-LV=k5pV6#9lSMQiERjGubk&f=11|QX$rEtOJiOXr4q75x zrV$Do2na*Zo(QZ(hu&VVM2gobb_QvmI85EvJ(rWEm$qJ{vE)0|>X!xOMjtHzWb1+%z zA7Q&pfCa@Z1uV-wOzomb-gs@0rt@PgnSw$ny2!F`>EmAU&`5*Gqk5h!Ub>RI<|#qT zDoBv=DvnqIqXRra9U9B~`a&kFf1?0Rd&e1*rP2U431Q;YCMKwByCnn|$M2O#RGS6R z^gL_bZ7&8tc*ZRJjDMo_LyAkl%=hzS(kA`Dmq_hoHR{%LTUX8h!+%-v{(3VQ>-@QF zabSj6_;%_tSr56fSYCbHFuS}@P&b(ki5`Usx5+8!$J*eY8rt&`gCuTfoa-^H3#H(( z(?u)23qfgp4;XaDKD%bc44s~lFCmZ-@o*i$=c6yf8T8O*RSNPRc9`8`=G^zHE70Bz z;0L-NX=d8Jaa)d;ESj=UO^V|FMqH_S5AArur+#IV`7P2fzj8UT6|YvP$1N|o6jm81 zQvAyJQH!$WOlhfuO6R3ao75D8a_^H{e;0z~=^i<0TX`~Jel?o_PLd!3CPRO7`=y^lI%$T~AKqnlHha}I{BI>smJTrioi*fSF3Yi9p zt~h2fim_p~!s4JU)_C;yISW?EXaQaXv*AdY8025ube(vvP3)V=G&XyJMB=ZU)vcwk z&WCG+m&O8~y@njk3W83|Jxqtrnh-+FZ>VNqkMD9lNBB=nk4x2qNHn6Pg$>d&!k6$P z5eKXK-A^gVh%{uUAa05(qdp`V$L4ii&+`g^z z-1>II{QT#u-Q|v&)`#ld!ug}!Pn(yKLwHHssliV;CqX{6UN4h+?Sy!vh~JFsk$W%C zH^TG8DMkD1bcbPEOF%IqeoE4yASST(Gu@En-QFHGH_#hh-LnIiIs$PT=!E#G_g>=p z_q#j0RsjLSlAqK9oJVE#!K z)6m8nVdVrWb3Ffx{bZZ}P!At}2@i!y!W$(3f3KG&v}^ZM-{*tk&LFN?01)SB+AQji zL_+<``u7togn{WmfcRbLrx7J5QG&;;-UtitmZo7QCh%CJEa8VQMrAn{CqXTi0?P`* zROe!2R29So7)>2SRE`>@6rv<&^>K6;jg2TpCq1)EeHb~Vv54CEgwO*NR~1%q)xVxZ z#R65%>A$uO&?L>tHgj)Gz#t0m1|6Y^_{K?i&=_vqbuD;84PX8-G=zKYhQG=jBn_ zi#Pi~t*CA|celSVr%4~nZ_FR)R^5Rr4cQ~GLA7m0BpelW6b=zuf|_3`4Z_DR+@~yK zCjx7|55$l4Pp7%ze}S23PaaO$qEyStBsgUG!D1d7h-`|~ku!o6b^bSczyObTpG+ab ziFIC=I}c;$DREwig@8aZqZ~@4&Cr@k;6cr4O*o%^ zM%$kOfx^!MltXC)fjKCGvE8164I+^+R+JsgaKE}jo5!ZU~ z$=t{jVXycFdc$zo8T3vTzc6nu>j1Ge=md;eFV_-$-2^bQ3Nq=!^d0R*PBV#E#asB? zjPOQ2aJvpz-7I*pJeu|n5vfz~?p|}R2c&k4s;h}+chpZfG%K=o)Ul2IUTxEmOS1+P zOEgJ+&(ZUlcKxBK3c~S%YN@xt2XdrMt2kU33(dz{$V zp#uA5w){my%lMUJvp++$2C9TA+GeOn0+D}m0}9u2sTyn+tnIr#<8(zA#`STGmz`yGVyB5T;l$gDWC=23?rX_H(_bdbp*UlfAIV#_5*GTY{kVbkjRpGp`K zi;;BE%MBwcjNks2*ncrs({Ef3`G_jAWsymGl)&-Wjo7g+gYViGS0Z*Ikgw^|%NL6n^U6ooKh zA5`=)D{y{qW56i-s@@kn*Rw!)y*72(lywYLDi=*Apm%L(ILRx6Bs@JzWm4$`xShxF z7ZMI4-WCoLQ)49t8-w_r!d3aNI;={L8Qr6RmI1bQGx9EUdq^I{!}hJ{g-R&vRsDCy z3ZP`JX~wTXFbV|fZ@=X<$#6hvbO3cc6hWL3!BvfNBo&)z<*x*&Q%7x+f_Foz#<8}x zVmG@p*3kKk1cxc89$$Tffz;EWOIG0=#uDml>`&cd`Y&cVvLxkDcppPL2YdRT|Lg+VuxbKC(Ffc#L zg1;8qeC~nk?ngWwfW~sN44=S6{+m-2W?pM z1*L&no#F|N?9ysN+Zz%7+Y(w5vupkTU44Qr6VnYdcYUE@w)!#{ zsH0b4H@=Bmj)?Vh8PL=$QeKaiDt&Bfvn}`RF#-yRJ)rJ?N%3=%ahmY#)~>I`@2Uhv z^4paNtTGm&nr0K-DpHP&(D@sBkE~gyW(7;(Zm9&-ZV$q=F}goQ?6UYpU_E69eCjtO zc=>Ustt+jJ;V**HUD&Sd@-3*NFrgr9OS~F`m2(#zOO_s1 zku;(3Wp2MQGny$r5pz>Qjsf()aC_UlkZh33Q3w?}k&1;z{&!iLYTQLB(drroZMiK` z`THI$IictU)R~qp$}R{Za06jS);ZG#b4c-o8bMjATBoH8wX21wM<7JtWPrj$#+OKE zPtM-RIa0eDO}8>M1rTju&iV=oKlL~N5-gvHX*ZuUW|soX)m@*2%-HqUJAhr|2SS`a zV)4s@(zaO22*9(M#5^(hB-Xh~%?;ZO&IUrl0R(6WqdlW+7pWarCzH~N%R^kF7O|^m zC`d5`2dIcu7P6olbz(Nmu1TagLZn2iF*(0i z{?D8Ep$9T*E(Kxhh4!|IhCck}Ev5;^q_FFTWp257UDv|GE+p{KVUrfzfJtzj!&n#G z?~|Rmoo;e;Lc_9SjjFnSM*rRrnxPbSLG~MiJmlPre0uovNo-d8`;2{42va` zD7x_(Y~crBHEB7;LfY;_4W4I<1K-G74f>+B3jBLxer?r6T5ueeR-!e9V@jaV zbZ#x-I(miJ)FjOM5~E6?g(f*zW!dPu7jBxu@x_l>>!qh8qXP55&durEO?b|L7p_V! z8T>2(b>hhA;t-GmR?FjO{P}oH;&qwcZbP>-2o*OkyXM}*#FFSByQGT=gTXnlo`cju z4;e;n%r2PC49Wf5O~&l_WBo(fMmXJAG@8GK^ow3HAH@trS*H3pCBjkCi^OI| zlt;+LJy{=^C$jOv?NF`4&Vw5~@7^z<7eN)p##vT_vtFfPBUHu5L2-YE-&j=wuUq7B zUl^B@;`ax5N%BiuNazOj1$Td}aq9lYTR-2M0ZPT`H*K21U~qWDmC2S5?uL5-%4H&h z7oO7v9IAY?D176EmLRwoBW!e`DBZZZHlN0~Z@1TgisR!RD>~S?1}Q!zs0rYMXASfv z?abt70@%I0v{*4&VR*7>nQhwCFek!e ze__Y}l7t#;S4|TdCrlktQ)>FolAy>|)FiCHwB$+Nm3PG7_zVWcixNqJ(a0q*ZTzx! zY%<|6-isy^H^anjUrf*z0UA9M7-=*PA+~NRjURlyZq%&k+E3u~!TE#4n$f+FtTfiY ze?|y<9@mDPWuxrz%(gv_O{RJ(q*F;0sR$weodnvzo8Qp*r)N1Rwv7K~#NrcoVJ>2W z7Y@hNF~L1OfNZdayU!i%V?X=5)c11xhJ0Q+DzReCZm9WTY}Z9O|Dy|+eZ=a=PDBYL zvQcG;30ALAQy6H3eg`fA)dG5CFhb99vy|IyWlUaCFNy()j{u`h`I(+54MOK+FwqkP z{|TbN`G#OBPSgeO*v4&=(^zu*qd$ztuweNJkp5?mYq$Y~6S5p(rE`Og>Qw*`amWmi zGhMk6bG?$uLwLbMeZta)C_Q+Dag^VB&{?g9(71wbNh1)i zQ~tIAG3lcTkqR1QbiTQ6HaBgh2zO0D-OpYOg%m(--(kKq_doKY?Hl|$ob|Wsytjbd zRgEYg$q1B;i-PIP!pAleQMKU&(fl`=lMh>xPoT6sn9dcBcIyVF-BQ@9=@>RnY$4?W zx%_A(=yS;KyP?_ZfvGs1>Fy|sr>{grh@!q1|Gme2MO5HK=QV!eFRgV6)9EH0G>waS zW|b$iD3(gc+}4uAX9lDQlJLfIk3x zRy$`8FR)?+tI?J&9p*pv+4oRVk6K+EiXS|#A%wKS;2%1}Crl(8tmp!s*0O|Nu$=If zoc_;W*wbpyd;6CYyFgs{$TDrPK!UcRT$Q>@&(48ei>soKMdmwIvp=n6E3g=;XOx*0 zvzN38wV0o|GakBZ^Bw;07Ly37+ar?Ko&KGE1O!;GVJW#{Y%)?5D9jN;2^IM?xO(^Q zS+@i4lehEuVWR{OJbYM%B!Rf_hXgi}Ax1s))~62%JB_SdKrl(2IVDB6r=z&k_Z)%@ z#XC91MXzjra6J)-xI2Kas@M3U`_=B23_C8-*wM)Ayj5j~4lQdDugjLK0GudFXghv0mKD_TGRwZkc9D$$wU$DK~43wnL}6aIBLt60;$ zUjz#*p!)DPd(IQ^)490x1s-0MtQ<`XffiZh=jehp{Y>^?X;G%{TyJZQe!AsI_{VaOag zX5WTtO3709+A4$=+f~@&@ela4uw|T!VsP3ZZZy1+Z5u+~gTM3;tSpGYi~e@vaOT`# z6L!)0o~lYXesUkoKFQXz=(>TGwosH{YyO0G^gBWwA{5h=11O8kdbovxBY3;?Gdma% zt=g8{m11*UdWD1ivRgm>Oad%U6UC_bt)9wu9R1CvAlq4EzWHG&c)IxsABCVp51AR| zhrkr^wy%YJKchZRE)VeAa>!?;hyOjei!KDh43W4rCu#H$`6YkyA?_c46T)_hhxj7c zzNu9??=K0DFBsb;pLoPZ<>}y_+LB?~%|z53QJ8!b;`n%A`4w`?1%LwdL}tL^NT3-v zA$x=^)E_@*n8q+UZpze~B6fZE&j`@6z97=0*m_!2@dzM&)4(X-OZe^=h|yRmiSlFL z1zJp5DOgnz(5Sry7~l=z;slf|BN_^D%uHdf$p=SNK5bpQQyj<}zk*%=312TH9dzj` zs)Rb;*|BI_Y{Ad^#it8#SE0od4ioQU_qqZZtV$xM^DI({Z z%iw#4*v;i$5?HDNlnL9|irVf9txa& z^2%(6$cQ*Ef4uNwTN)b8#`oEvHTGlI`}^|?AwL%h3R~KoVlU~(IM}kLD<}FcC9YK^ zvHme(%Bb|bvR?%JRbs(@Ha=(R#`Q5(?vf)ZPsv0%PUE5WDe-%=9_(ZTCZT8XOUU#f z1N-J_u;zBpj#;r(=q|buQkVv3Y=)S)b=w3uaFn58+o|WsIOX2FzkcNuIs3loF66?| z8FXoQ5+AoN(cLmguk8I~l=Y z;{)?wI{3b$HjWL*{=Ij~a)opGl4SGwqKQ%KF067OQXkMH_dR$Gp0N&eYLHSiT|)mY zD-H6z>GWYCRT@zjiq0bN=xyI7v340_G`bP|IZDT8Mg;}q4cv(1FKh9g0*)B~Bfj{k z6cbaJ`QmFzQ*>pXLkV=_N5+x}uq+yFZ9$@__7~ucKbQAr^+S%ZCpJ^!jEOYny7f_5 zkGS=be~0KtN^?SeC%#2B3$DbmJQJO;{4h)vcGQHcM*&+;dQPJ9J#-a)0V`eEw5^rE z`yTg!e&2tuJUC`kHR}N`KXx|&DKguB^y*l=f*6UXd&q*LeC3h7v}d8c*{XyJ$CkO8*+zcn+|amX?ZVV!^Fkwbo6i8_T>b->-$CXE&{(X+wBg-vKB3V&Uil2Kwqi3%}f zep_EZQqS?ZI}cWc;d%{9KmLvR;HKTuL*jNty7YqE^?EWA@b&dZNx6BgX%lV~+*4n6 zu<#tThj9`lz8j*sqm}gOvR~ep=;NLo65&T+ASt%A>nF)h9)#zE^LmWx=@kO)QwD>B zUfP`nGo(MK5p^zJv_s>s(onEbpTMu(=n{OdUYtz|_z&c*5ev7j9ycZ|NB(1-fs$qi z`@T8>1SWpQxJ%v71e;_YMRI2I-Hnf9$B8YIJ-LuaLI*vp+9H5-?%PkB&YlM~ zrhI|Pp@%yZX%6gZcHtcMa)1Q-kM%IR*yZ*P0{EHBc0(-%Q{2oSvM@Htm+*w2mP6qx zdXYpA>ObZ;`Y7#~rcov|NvTJ}OO&bQQ?3%^^an){kZnCt$3dpYo#KQ=P>|ErVyQi0`v8I z)>m)zfZMU3&zK?n(~QOvDchGVlIzf@E8&9pYS^v3yV4DLW99BPpUwHp>F z3(x&{)7%cQ>B@4P5?5&>q-q`+f|edxv26tm7LxkuGIOnvW(W8=g8Vn<{sMW|&VPS2%= z3X3Zgw6r=_LVbPouE>=Cmk}J1X*Og&tyIr8<{I_#CA%3r?95P~21%*Kh`nd^$?~t2 zNS<{W&awfLdpL$Aok^-=Moot_g&8QDVDk`$WSL6{Rq z`}e=UQ(F_GwU10m_=E)59c|v9+PFqaCIchEPQ~TqGE6Ja9QU-W^ez; z{Q&Q1c;`ty3Ljgc#S~eb*QJWj*6X$E0v(kS{J1a*Tf-&AvLqE^&Hng4o z!S+>@WB%~3fSy;(OtLr8_^Vfd-08|Q@}O0;{wqybcQ5*{Cq#!hBP?kF4VKEki292i zK);#@UI5%`eR^#^+&S}b$&!9iZ}z&~pE+I3-Glbl5Uvets5x6(i_#8Jp>bUvCco#- zmBrKVhP(U5+J+E{=@oy~lT;J)Nz_aSqU3LS#w)i<{bQDLXSdeV(w$MF@B|lfmp#6`vH6oKU=(vP zp2S~%5T&tvVTOx&{fT?PfG`M?Cez5-ZfGOPS=b$qJAz7~}7QR)fB~IP^v0r{u6bdmX!9buX;d@rGVLHWoLKB_hSv)sBOa zlXYb9+vB_Wux$EQ-6Jok@%AasBYD&pebW~1w0DKR%ujO#o?S!9VJU%&wxw4yQB_&V zX|uvz>UWm;jf2+a1tgVm`8;~qT!vp2eZ7QVVTj;)d@ou{OE5<1ikfU?GAG_ceuC*S zkXkFG@y1M6`VH1M?~K&eaO$_F*!60IP4lD?e!QtrW@yD+)lmMGflzP~@Unq`USJY& z(4nnMBJM2+s{1t4qUb}92mbB;gWU#S0b{Fe?EJxhu7DMp^6cBi!4K-HdOUquGJwPkW6kNK`X{f-9~K{zWZT7jXiSR zD^V|XfZ`U@r6Byr*x|KO+|P1;74sR4jM$&L4hE7KQfd^OQ88K#F7!T?(l16V&3p4Y>Oo4F z5q)OQHEL&gLJ&rV&rIJk+w>{bR4|4(PM*p5#701+ZQqL7w8=m(y6YSsAdn|ktiz<9 zurGa4C0em*(4%UNX`cH!4f^U-O3xqi;MXf^V3-RRq=V^L25-#@J0oSi--VrtH7#KVzz0MQKj2iKr}9c<%P-Xge&`8{YmPLZPSnzYn#y}xvF%0M2i`9$8KA)50kSRfn&rBhqMQ{_GvOc1Mh0jUm#P*)zk^3=E5Bo{D zbpP1G5HC3 zS|793`$Vg@?B2hB9A-eubmPYV1b&OCH~j?`YkL&^?2$+u+md_`FGKlsC1NozjWXQ@ z?996;sjXXkyqx48?ZQ{2Sii9DY8fFG|{(9+~w!{_s|-e_DkKGZ7OzxGC3PG z)?Ru4BLQCb8nf*_{5LkH>%?WZI)8m%fcIZ)Vr8qi9X=P2F-*zq;AbHwGG5pjrC*-# zP=t}W$u&J-ssMGU;U7|htiSi5?@{+fVi0LIVR1)2v%gEWy0!??PeVy+sm4TJK;dV~ zX<#5mq)m}i9DwDT{Fm+T8otL=cK2NSTM3NCGsZ-@%=rl8R26}0*U0tUQ@vPznxAZ( zAC3L@OTeaTdN(^@C_~zOwu^3%@ZHly&EkRAd#W4bT#Gu_uZ>T6HNi~Lgd8`v10$4H zu`$GP`r##`Mm~=SC9s5?Gz0{D09c^@XIHdeNoeAG_zW!k`9BDpi_lV?`P>9{U#Uab z-;zzzLegZ21z0oJN)v_9O=Myex!b{ZgS958c9pfNA~(b5+HhyZO8&dBKH2$~AFhB= z^^3vJA}AvF&XPcZeN{iACu-&n?n7OLWhDG1`HPaWodgx^vJ%IUV{jYw_Ca%8tg0hR zfKE?{NU0g|u3Zb635C@@+7i>|($79_HAVCOdo3eJHsYO6eg*f!kN%mBEx~Na(?!w&jJf!y#|Z0kscq#!cQ~R7KF7loNTmGz<>UM-Lz@*MHX!I%YZI6&X|I~Y(Ka%2`mX26ES>jICuEG)9f!$CTq!TdZR2*H22N4 zLmM53jNC>Y=SlfaTJ7v+nxO8~v!ycy)|2$8F`rx9D&m%`>+=-gHwQ4&pu0Zdq3DVm zNNk;r(vThd9HQ1>=tT3e7SNx4sy8?+zcGSrAoA0*8 zwz^p8&I&4HLM?(#NOo@p^haxPm3NHcr{~by9(0#C+5z9&-Q+f0hbgCu8ZL%$OyChT z{-NpeQ8dJ$AP3nr9Eb_mLd?PugXs>mbSx{_BBBj^LH)+#3(>mtK)_sa}A_3(?e z@i~Tv1RMY%I~>oBRbnbBgYU;SZ&gY9%nYUf%Dc^&?kBU zQZ`WRZpW#DxP=aPJCp@W5uz0md_8%b8PTA0(iN-mPQFNeRi5MuJfi-;DzItM~`boi7Zmc@J=JvaV4G6)-WDQ<1S)B4qd5U`tcj@pQq{m^!mpZw^v%! z=}{MoU{1@V$X>C(WkCD%3?%z9CTfPTVP~rOZ1vX&XEt51{G?$iz%y5m9$U0U=7F#MlxI?9nz6#iFm}Qx%5@9x$aT&hyfmw7HHl|AvEj-eR1Y&X$#oLOMJ4jJoKoY zy{v#D4BPjSYCKRu$&a(BOYbuC9RKFJ2B-Mh*grDkf~G}qP(e_z6CGw3k)b_2*LqcL zNF+|w9NTpSSDeRiT3AK&po2lnrOu&Ahd|>_Gv(oua0(8lEDSC8Ap^uCvC=G6?A4Mfl*Iya%acCgrTAY`@)BGhPNmHMo8fYt{!KdDGs|a88D&~bVx{Vf2xhyO_ip;rv-t_wa z2niu?^p#aegiGyN(Z2Pwz&GG8REY~}(u%e;>uvej@&gGs0-F*)NbHPVsCrrowpekr z<$yZJZ^~=n+Zhv|>5h5bx%_|WqDtV8OTj+nt||no?W5VEO%nye1}8zR0(Em!9QV*# z692rve-*&)3 zQ=bx>l<-F_Rx>DDTpTT%c{KPW8%Lcld`o@k;XzoM@ufYF6G4R#pVfmepA0`jc0VK! z%~}OSfXYP$pMv3_hI~>#Q3RbTRR(W}_4eOZH(_nd9i%~BgoEFo&=D4Ch%^2n!9wkG zF-+ev`wDvDd(fbaLT2{4-kex?kx!n`b$nQ7OIxM{Qr>Jrf>2TS0?1z4B zp*q*dW-8d@R&Yo)5soflkfYI*uGphaeiOZwN&BNQJE1$6?Vz1z)46NzR{n)kc?SSj zpkYfUsO~6=V3OL%b15?ZjIH`+OO?9w(pWVp{_I^s1tfq|U-E_>wXTMB_#3GJ++dW! ziZ^WIdKV^iL&6iddSK~c`;fT|6|gd`@s}x=3lKwa&kYQ6mlw~VEU}36*01k zCrDv;>Hx(Q^GoC{I_`I33%`QlgjSHR5ZRUtC@0CcRwe7cKXxzeUwU_&-}(*)gr~U9 zO?b1P0ZjQuRfD9=WbeNP#O(lwv5mutJ`o%K2`mQPL1-V=#{<4H;+}KOZ=#Q#S-OMu z(gHzWgn5xmhF5F2trr3GkRQE&{BP%u|NXVz>MA70|MQjIhMIXVF?{MPnhx&T_v&5z zY$IQ2Uzqh7(vWUgI+Q3yFA43!5Kk^;sjB)*vPN}BOprfL+8<2fKY7qY7BrZ$InmiQMCrlWY|aw!>&BR>=`!#4 zYr^+6pN*d}Jl;A~B?A%5XDEJI?Fex)%K9lb= zRrv03Q#&(R)nV0}tViMuG3*zQiwB+qv69#DiF&)i^D!tTg=Nwc3Cxoibl0KkRwmY# zqZ<-3wZjnStpleBeF8z`!6jP1amc0xMTrINv?sXDTOoP9-->iT(vrI97IWhGk9cl6E8zvdOf<`KGugK^uR~pyO3oC>f&o4?|3tu zqhCkd`5q9@-~jsv5FY(F!u2~LE!>29^X2gD0W(%LEcnO&e*8cnH*Z0|(@k7$hVYyr zIG%^BXwa=1;xItqyQiE}D=QkDaSdwG+|&qe&4}UnHl8`?z|dtZHcY6RhMhY!*tU(; z^&vv=IFr8+>o_{|xlYt!-?OK5*a;<>IYf%Ub6{3?K+tv}&e%^BVdnwJ z+U41BOu9InY+xRTYxf{48f(xd1c)?H`yMmJPUW0Me=k3GvkqYNI!WOnr2OZY)tW__ z%h8tTDGktcs(}>-9_0Gv@RI;dqcO34XAdM<1Ckt*3$nTd&t`Ipf+)?EF=$2wLFXqR z?ns$SJ^ft(fLg7BO2t6GZ)2_HK=DK9{yHRChFX6G^lh(ChCsdxE-ZIJL2wA+u}>jv z-3hUABkD^x007+nNLrMtyFfARMotNV@7nC*<9Nub2F<7-jv@rUbJD?@3Hii;vnRVv zu3fol(@|ZHq02xR$2fd6fN7{`G)x$VfinyP?T(H0c8rUqTcFG3&KE#lynmw$`b2_x z*>i@xjW|jIQIa9mYX-VK2TnktO;G8|T<%|J*!>Pvy#lkkfH-C&`}3+eavaCxgH@(N z#{yb$%<=4gGMJQKC<4y~Z(TMPpn_)bUgb1GMkKSiAt9 zPy-it0TO@{bY}iYZ1|m@LRL@9N(gD~E%PvpBS^A3HT^fw(1~iyZ{#XUiK{rJh)E0@ zb`jf80sx460K>=M1G#w%%*9uOlbWR-isRroo;iRY`R3?#YA*$^Ux@t&R?u9~VOb_> zwF;_L6aD@WYb_U25J3;xknBEG>m{fx-wb!{9z?CXi+vzd1V<1Z|9>#-+y$w6889Zy zuQYGjkY-5fc(CR&O>PoL2t2oti@OnIMT6hEAL&I&rDe$GnHa7f-t=<;%)_pxNALp& z2M>9uR&*>bRMDs#s8%)fdjqVsY`jRh1*$Y(pq_;y|G5)=F2Y3!_yM{-3ym5pWAQwP z)3!IT|KJ+rfd?_Ud?ZQcr_0 zwxi$9F^P#kL~$uBeO*doL}9?#GM)pT=UMaAV6l`YwAv^PFzl|wu>cRVJ6hFQFbB8>XbC)EU1Q+xi%}Rj$r+csrv+L-$JnVEpVa*W!qb^u;rzRKJa>B z@G`3n_^k&4f8>`ZF5CiV*g-}0(d|T7S#z+opuwt`s8%beRxAt#L#(wO@O}h6=)kpm zQ1we;E?x`2{Sd;|cL49{sn<(E{UZogN7OowSD@6dMz1|>S6})Zl*0F%to|vhI!t{5 zln}&G0B=tIt*q*Bj*mo|c=JVbO$TlSMIulnf>zH#y=H>r1aRO`uUApA40O5!bb2l> zRc?VYG0bqH+u+GyeIn1(QuaVzwV>-F)I^?DmPKseTF2329n=jDqClYKJrekQ5b0rM@Yrkuu1N21PSiS;Mp8+I`51#+uGEdM?aZm<4p-D=vTVf(X|q_}ZNh zf=rwPr|)RuWmlgEPEhcukg9S~%_aCX_$jbM@<}*iVEaS=(^g#iv1(6ei=U=&+p--@os1967oU%hYh?On?%LyP?O?q# zUhl+C%s6Je>xhlm*_nwLM;Lo-)&qD9Mi?6mSO_c&3n2mG5J;%i>Z`iz%=5jE-~RDt zW@T1p*3n%pM9e- ztyY_-pIM{PXi*deUd7}3Q;W>aRS7bKRu|f>(y+HMZpOXwpQE4n4X|Fg=X--Pc1<=u zPjzPTie*rfD4^TgBn;YUhSeMXsqbnWTBbL$@$|+aMS4XcVHz5mrV<1ZPoG(%)9#?C zDsyvnP9C2_RxO&rsFTZ;Oa|`6m6Cj{G}$t~%f*$}$VIB+nas_3v_b_%+dFzzH3QqN z(r&CHL_waV2kM^K30YCG+$wH$7J;DC+#vMZgM4rjhf~{Pb<-{dzf7mhEjKqvqUkBD zLI@uG(ziIWQ0Lf@IgTyQaqQ?EwYrCdK$hV6(Rq#?okLRzNmMFjl|2X|96e!cD`TS( zvN-2pI}S@rv&2!v`ev6fj7JP?`y{=SY;W@JV3|`CMZtsqCk|y_htbxa#R_M+w5qeb zv^}LeH{+6~IjfD3niZh#Xr7Q|1z2fCJQ>%L9c}fyRKtU9C(M_AXUvVQs6x{#dcj)>N z_uO?Wnp%)t`UtsyncGh!fJEZHl@ESc;w3LS$!xuxhxlgvk1Q(3fs&8zy7NXPhWf@I zoV>3;eCKsYlFZUVosa$1L%j73FGp5nF05>^y4K*=fAMV~QjC|Jb^9(JZ~>+sbcp z|&hwRUQjwc)U4k zH3r)k-fw3r-|nj15@p=eSfgIEs8wBT$KizI5C$Qe4WGb|NzzWQMQ{%LnY zog?BTQP@F}mEO=oIR*N~&c{byf2ZrpL2%rzvDFD_S_ZZ1c4T^Fv5IZ$tXyg`=cQYz55Cx@1X=p-ZTGIRKX?aY@ko(cVbn0?Sp1 z!wjU7j1{#UQ0W`RmV479=tC$H4qIjQ1-^Io3HH+*X`i6;?Im29=6K&&i_Ihq=bro1 zN~YssIUb>3M#x1mE?ku7rKpcAD}#Q^GHv1w7-KX+q?8u)R828k1)!l9XPv^aenIif$MrNsJ^?5E_nG zM^Y5*IK=lOF0JO6X25LS!FFs;IX0b6m(_J2T}g3_@_ZT$D7dqO)s*P1&NQRUy$%y{ z%Wa`X`rzVz(44d^foJ7hT5Vxl8oItsAXU#IOLLm7kdt#2y3H-JEWt2sOvNRR0=mtE zORE~Djcz%laYX2MNRxP9wJ23L%D#G0Agk(uiiJ=HRpofJM4lz&c|n%veB>|7nv^7g zVQBo!d+$M(qOpOu@;(wp+J(G#4vF5%dFVXP^9)th2I)$GI7#{7hrclRzisPG^FR5^ zzyAKHI+g$cAOJ~3K~xH181wA8HQs#h%gPmcmU8mMB6r?#Gym}ef5XCDmATm}FL~if zUU2gfEVo*={q9G51ImJ6`Jwb?$1{PV$;81B@f|`AdYXUXv@bl3LY(x<~ee}#vGc|Lh@|7~SEKifDC zID0E zq)9Zmz$mJQ=Q-3hosEr6&Yq8`RxD=f9-imox(=;Yht-WPj$UBtWgqgSwnE*o#=3#3 zehtOcuq$=)JRQ;e-U|cA5>;TR1#25V$CgK3M`r2{8=GC$*EXotJklgOP|tB6{Zxb` z$z#38eIc<)EswISpj-B!-?<;e*lu;CA9(8P_S}xjf?+TyUY6Ei3aX;;vfFP!Q`P343WTLj^<4h$5fU&xXv;I8{^6$g291P3ZGZnFOyKY$M zmP4MU6Z@UxC>ZoK??l;0Za0FAAdaK_yX&jcW+LAOD=t+`95l>n* zj3(-(2~&?RzV#T0;R5Ppf`0woFXZy&29G@U6fe4Exo03-?n@MOSeUOeQ!{zVt;?v2 z!ed{5n%iG|oT4c9*Ts>>1*##FCB=ZC^Q_E2%j)ozX6Q>fK!#%)nGDO34u9c0WfQ}0 z6Zhml8Py6N>QhWsK8Pm!6FVI8y{}Z3)5jgU`%qMkB2NcPq*4lW zsB^=6B|_TW!d_7|bju;Q_=!<+mTjz)zs$L`zAHH&6uMgW084qm%E~4eE^ZJ8A)0Qm zurR}^6ARSqE=5t$Ty60GJni#=Ga1_Kn};l_rdP2M38HyF!IQsDeCeYDZ^3>9wp;W( z+$LFm-U&r_o1hOny)nM;d*8*>3TEAmZnwkfXVz%9I>?H`>}-wePR^4HiDsY@XA(&! z(Tx<^k8n(CC}2aZVuhBN@1tkEC@lnu|^bh zrXDYS6hff(a>J^sqv;;_^W=4~v5M?l_R@laKu?qqCic5!V3%i1Q9*_jGw&!-rg zK$RyGt)`o})fs|r>p*?bhUH+G4w5XD?Rxuc>B^G0BvYfD0xo-=HvtLTtHM5F5?PV? z@W&qPw<;hI+<4s)UU&DcUvx#j3}9E}W?n6^uFVW>iHy%5zt zL1%q3fvH+4G!$I;b3}9K1T=2Iy8iwA^<{W)eeaHx{iHW`gQf^HD<>-=*47g?wn7%> zTrRIRxcTTDYwO$5M1Mjv^jnzTop_6{Ct81qbn5|#pPl*|qWvI2`$4424`VL81=Cp~ z3Oa)&uIX%d%=Dp~7Qv+<2XW^m5aj@^`Gtvj$x_Shn^P&>l;lrn*sAPWg+(H z5o6@Oi}N0*pN&wI6kXYV4~FH8wU=r7sCVFgJ3TZ-;21d@n{AFC+g|0^mdM3$MoyPDA(6-q!7`qUbzKba@GP?v1p!RxvGiSEJWbb7S`={YQ%X!G~9b_fnZz zKokX8nj)(TG9jX~UC`2JUpLjbRntwp`W*hb4A;%L%6KaAdJ8gsog^qU$Pivo0r(&$7DO#*bnQwZJlE(h1X}hUH8x=Jm;1R+K^U zZ5WPG(C`yBw>r$uY^V9==R7*yh$t19T6yld)tPeDSQHey423{h;5AGK-7rTAc6}sK zSb7FdC=AQ8f~xB1md%;?+gu8sA?!>JJ{~FV=he~Mhb9gsG{Z#KO=P81$}5V3A_=+v z#I|ysqUwMkPt$=;o?Q?cu-{|gMpTj_=ig9nLe_R~d@CJ}mX(r;R-qbPFxb_4h1FVKDRS;#iZJyE=Y z(p|oBAF{bbW#+|uHsDug7ie$oub1?Zda^R7&CX!+8h@r z(hQSIZJzGgKS8t~+P=Yl5#EjO=cDIC9@%_u$$1#MTJVUg(GxJ_O~wZ8M%j;CnOP{i zGkPcUKyJ0$#&mANx#4A`?QfHA+>Z#pHT5+_=V7AG!$|I(m`iU)GL8+@@nAf?fwqM1 zUeDIrg|dKTxf9h24-82R-Y0-&+PI!h5`_mAVggW=(srvG`CPnIaBO*oH z;`l6CmJ;|O?QTkIJw#V!OjRJur4G&Tpogre6Kf}i=@5thM7MC)%vsy$;@BppS>|UY zNn&o+VLm|9hJdnVwf1FLy>1libA)wH8C%oCJ~jHQo>h~ zWr{rKV*U(q5fbMiLDr$Qxxe!(i9;&0i&%w6mX&GBVU;|mGBei7si+yMs*ikcWu$M@ zefCecB_f6(*X|(~8lgX)(os|mQ53t@k0wC~fe>Qs_z^`xHe^$$8y1dRL4v^wYFC05 zf`Mw?aKE#nN{B)XM!tvd-~W9T!N)|TNrdB6k@jHzBnpT$9ew$IB^)Ld4S2XLfCDis4DlmKSdODcqsgveeLUm{$KId>MxLYzcbjD zM;D1!KSOo#&4k@HLAPAK_b2AMXZ~<>7{q=l-i`kgA2}QF)yBa_ZGZoAIZ^m8Uw>_# ziIbj?j%HX?>I=kScc8H$L_yeX5q4Xc&N1xkew{2hL$dyNi0<@WYSH});nQD1a$kl% z_eQMw>j?eMczVNq$)I~94t-3=n;5NK2}FOzB})IgZqY^4&7NPLbVX$CnmOG#WOc2@ z?2JPg#&kLf$P%@Rfo)q(y7*#cWWawoi^&vrB zzlqBmGN+Dh8>Ut(7IBiX*$K(>OQXX=z3*4mjMCwxZ`>UEgF1^ONfVXg`pC142bv!} z&}TIXj}-TFSL-cP$Igc}%ljzu47sQ4tmy`}S4RX-(z*B{NGGqH&G|PGOi6q0wVJ*X zlv1hoU~;lCq;&(J-2Kb{>%W@z;4CS}x@B1+2}_yLJQGM#pM*zEV$-BR6lI5pVJU|q zob+mUd%0H%c<-HqO_K<#a+0DDh_EOAQ^ZKJS>~lhO4fLYwEbNa&B2?0Vd?6fXM+RO zw7s%lF^PKzsm9IKA7Yv7IG0XeviEU=dmCBvks;-`g2I1-Wa}{$YYunjrgA`~Qm1qJ zKS6iM`rZ8@yc>RvKYKRd>&+`WDAakuLtT^4KVtLR>#nZj<99z_N1flkG7f(yP@V{J zRJMjWUcEP+woPDtiC0;xVa?rzQh7Ofo{y&!z9mA&SjI2 zO{1vdq|0c+!EsE~p#qp?>a4DJaP-NaTi?CLuwA;1^|AM>s9G5%PRch6IH}z-b-xaR z3;ELn<+z>LE-IJDsVpm~df67M8z#0_C%Ett($$YZF_}Z8>OH8Hmkolao#6r@>3UKF&~FY&&Yk81A7iZYn35JfR)JDt?svTFpL#szjo9dvC#sl}n2 z3UQDR3WP;2NTPxw2fdPweHQ>x>>#S>Y0{OaN!I@w zwRR7+BX1^&LZYC9s_7$n%_Is*q7Y3txp(HLNaAo;J%y*ck8|^_|CVI^v!q*Jq=H`Axyh9Nsh z)w{75--M7ILcdL(rWB$;h+^c*scNO7U6v*ML-(&ns?Gqf(%y_|J1B})Y7?CQC`IEl z?3SIEDzC;o@!#>MXMCRQTsyD0gA(ihD@IoeJlBM5JF0%9xF0uLrWW6X z?a3_6*6_5^slqfXh@+H?mm3%wc*gGETj?P05q8Iq0mE`A@_gb*e_yWjFkDGqrM($d z)lfAZMJxM{Wkn(Bo38+6ujyGev~_2eJ^R65rh#*mT}>U$N1zgzu=1B?^HI;((RmcziR_Pmdn&f66GkG zgk9NwibL*pny^oCX}Q#%TqN9yDCnYUvlz#Jg?ROo5PfgLy@tZ1!bdbdi{JPxlJ_d~ z`Fl~U8j9*bZ$O|=)O~FZT~T<0^*)3UY~`y+NO(o9lp0Or!Sc{reivflwIr*bAZv~b zdu#J=Mqhd_k8UO80yJ47J!Hw&K7Rjl^{S$2uQoS`1oAwi$TKXbLeOa*$b@uwRbno@ z9qs5l2`_z`y!9YV8Xo8&51vMyGGn!02k!l1zrE0oihJWfBkepv zvi>>5(BR0R1y53thQ4Icd6;;pMGi>=*#y}tbJ>c8BwL`^NV0{ZyVS@j(l&~HlH5-b zSp-E&CNffyqDTTs){zu<#OM{-qzFzEp8aF$>P@_7@kVC7BU}h_&ILJV{fu*d&Sr9e z-o-=0P9ZH-FCAjyC_s{=()d78@!O3(C%mSiuXUkn2IlM=v5&r!;L_hxH2)qkp_rq1 zFG2`t_$r>6qYm{D?{_F-H}nII{if<(sk~thCmZuO3G`F#bIb6Enbr|D6MoNhZ| zW3!8HXjDA|$FVRBgZX)bxj8W?F1ohD+^joBsI6w3l{Ft*FPQW4!R4plb1uuuP#c_v zB%8>xj3g__vOEYpCK=9#etXbqHH`hFIZVZ-rY~+2vNnq*skA%aBJ!UkT|Y-FUd2jV zjI`NY2^1G?;l1dycM*0w1QS*S&lgN3=n>Ob0YN)MlEAC0WW7S+PDqE`xzWdP#1}^a zimDBYL(^LBh7opKgnpaa?5)`D3+QyeMzH>A++bTDV?fTb0mXzIrbr=AA@2;56vOfD zFg2x9v}dLsRz*baKMg$15?_KXXekwJ^LlQzujeJT>v4|XNH>=`>*t&ea?be~XZ`#@ z?Tm*3({i^}*@U=iLHA)~X-u~n6RH|k?bX;v-a@+dCE}G2jnohH`8Oje3P+Y^xwO{A zP*UvPG~VvI!~1|V{Jl;PtA{I!ZZv=&%d+WCC}Zl`%IFn?HdPNNvmI;rF2_cByosadl}J%KOWpBo6AT_ zIkDzA2G^flV0Ep{Mkm0tGVFs)NKHUb*?jPyW$8L@mQU=OKa~}wCk#Iw>OQ>y_X|Z9 z*t)<_1)V4%igV^AnW{EQXK9+#Yg2QB^z|sK7rf$?zMXZhX4^ggUK_P0Bf+N%#bRlSTL{S7f#;8dgk)j zR>GrO={3n;8@4mn-UX8fjr!XrIrZ$9yj4{vYkhTOn?C;*wwgX^9y4FBA9jCls`8{7Om6~jXyWsBG3^}9eJEvjrZbJ9dYl2l|#l(BhFo>xK) z{SA^NhW_sTpYd~U%U8*AiP^eSrZaZr-#529<#37##}=*9Ft$goSDKC*Mig{<^14;> ztaKL2(gedAzliTlb5yh$ZmYe9sPPc2eiHL4FRaKWXvdJu6R7qnH1`G+Ymq!l$3IIQ+uFpb%uH3g{C;An!Us{1m(zd}*wtRH*B9u9Ao7dtob!ZmSupOreXVe% z+6z1LlgrU@lBk1W%`kuLH;{@J;iXR@{JsXWTndax^5E~%*+m&_m!$GZ-4QvJi3+g*jB>1;L1wPF7U%Y&(J$$fQM;OjMCom->uL#VezJAw<~~RES=oxhysp zL;ufv+w!7J+2r~5_BR7i&Kh1I8c!t|*uVMB42XLETnexoLKvF?Jie#KXu}`8p zH=sGk$+L_sOG?|WFd=K7-xpUDd0q}&?O|T~{eUV2Bw>yapj$Es$dX|CLy=`y^kGixpYD&cdbK%><)1>;es1_t{eNu#A^N`<+#&?B(i_eZWj8^1 z{sR!6WfT(5Ex!k{fyhIOJVq2TB2T#3%n*7EBEcX)OV_`KmDu9Zt%S#V-603TP9mMuXM0d`9>#9nB&GI7J~EA2ST~T#3e9vC zbZF^kh&Nt=v0BG6Rc5Oewqs(N<u9Ewj|wzdLYE~p8FX3VrWqA;u}ORLVa)C$ zXvyyKn$`Rq)z&$}*2jp=S8~_v-MnM@CLY~Nd9;ym@d~2qNkn=j(er+x8&)s9u}u)x z%w2qCYqa)p*($Bhw8BAc{V;1Ao$U?>+rqTUpZWPRvhH?68tnu{D#=>cim_D2Xcx!c z2X&(v6Nr~mt>jd^84PpVeItouI^B?FJ4O^`AS5V7dt|9JTvikbS?c|khyU)~M=pOP zN$&lYD3CFYQKHv0g@rknnVLb8q(pH>6lFAn(kD?>1d1%slu{h2uXQqE*Q=@dm?PE#iFu4L9954W5OhE-~VXu46ldpi|Ga*@ra{sV40`NAyJ1tjx0iggmz zxendEkphK0P0H?(EWuyDcvaJ)KS)qV)aWRCoDro=pJ6Kli>p3FE>QK!1pQp0C~`F2 zB=S20QtlJ=H0*Z*@i3sMI>E(18{4jWFTlF)H}U<5mY)rL>-zYbp$!C=cH(Bw;Ewtm zxZ~*CSlRq8!Pb|VkH3N{rk^Y_8OzZ_aPc8FR!=eK-o>xocn{|S2_w&T9h=_|`5p#2 zPm7`r%OPHSWOSo@8{ayga=QC&0A9E7mxG&9*~eB3>>V8rBV^r+tmj{?xlI57AOJ~3 zK~&~SqtdP)(`dygQik4(tjCY+@h$y=;hoaGv_pm2S)HXJ7wsg8@w;WanKdY{mRkcR$-IF+f@Z02XZ5#3@+8MezT1U*%0?nLITYN4VnsT|M>c(KKcdsI$ zB+FOdg0&B5hDDKV!jMXpY#v3My$5Zk%w5{H!R10{Sb=;mLVT)|@l+?{z6%j|)K7B9 z@{LsOpXKz*LrCo}vzYC^46kI*QfWSm-})Gf-koSOcjGMFSlSPT-2=DE9cJ{rlcdY^ zMnUFptKSvIadNfJ={*z(VY|a&jI8y3@34tsS{SCq>})xe*YzWstr*C$dY*)hY?DHo z{J9u;m91E1d8vx)I*6j6)$Y=4MdW#gsTFuev9DF7EWx-6*dFJTm9y3M>H0BC3snqV zMboDBxk{*-j;iU{Hq>er8e1(cZv?nTj%{3<^CIlFa4It-ae(bs=sfiYqZ;i)Q0Cr+ zwe(gx&5eOF;{T5!f{y&0JQKJzZE}vehuw<5hvDSC7y2i29CoSH7icH@Yma%ZB52cc zh&P6uP>dyJCJ7fW zH&ID&^n&N$Gyq`6%?Of$OP4pv@-i)An<|#6qU+_4rfCy(t?M&Y9M@!Ry+gxKaEu&X zJ^UccZ*NgwI7+bcHzB??)J;&irV_VZ%oqG$R-zMlZNm2#T8&OX4$-_Pe z!KEr4vy5`&DphY5H-Hck@!(0roU%5Jx#WHn%4R!*pyzyu@kSt zUN}V@`YbkOR-^KH;r_)XbWL>S8 zIJSvxZ|hym)+*S+OKG%jMOSmqC||+M=a|!vasAOFD2hrD1f0Lvq+(qgg4+wWUJQnG zvO*%yGyJYZtAH$*$O{Qwm9Z=p%TVz=8&xZF*Sc9#X?`xW^jG(XW)!DQhqVTamFCjG7cS4Y z3GOfm@7t}EZ?{rhRpO5N&D?SPMHu?e@a)PzV*8I!OP`+lSh)z9=KB##WcQlaJ+czaLQL(qC}cSW5tTE|Fy^?O5XS zM!@odL$$W;JmPsCH`x{&n{77R5w1}T99FJse|l!K!83m{cAKQw*e8F10u>=b4AUmh z%R=Op1XBAA)D9D>W}q1+nr4vg!aue*$$e$#bLoTr^dis6vXml@Q2V{jX;O?t%=wU5 z(&)Cy1T6}2V3W-&#cC63HE2x@|=~M{Uw+mZRriU17^tzcuTOS2QRH17>MP83CDabbpv8*pi@ zL!4!}#&{9&An@w*1ke5fdH366w=8mD2j@#DCnAnrkkie<-Wc|rzmpL zET+gy0xMlgic-~1Q3<-OYtBECB$rlOhJ_GM4(HsK!ix1e+7#uFcgy(2Tl0>WHA4-I>7tRGa=Yo(=TnxFrKF1vk@4~D61kvUrWUWUK-LFr5tX%li zJAVhAzoYHFj$gdtpYV5=V?KNNaQa23^*#(6If|{KXCIx5CXUx@2W@f5`DMZV*x$dMzqtRw{ zBf!uKbVZ=6Vk%ir>Y(zfb4Z0x-hOoKHf`=+wEC-PZT941hcsPM7#kB$(-=k7P znr@=18igpzZjU&kC& z)7(1$)112TI_|p=vKC$WK2IZOMb(gHLDt$H$|=+tOy?9&oZjx<*jXUlPyTr~7?z8W zR2-3%(U>0$2+7t3o-HG53TK{O$8}7OF4tLHsL^c7Y;JY2_3uyq`D$S41%@W*bOM^~ zgd+4T9NVoS;uX@(2gY90Jo~A`7A@K{pKMXDyn|40nS4(Y3@*g6!)s2ki#BIft?I6WAwyj%Qc?5z~JJ zC;aBvbIi9s&gJht%^QyX4A(gx_g#pH_wn8D#~?sAZPKmBN490oOZnCn`Z68_aVBG1 zCPD}{8(kJ^pj$4QVbX1Fua0cJAW9?7UfAHsVinUgSw3PCM-iJ1pH>iK8`I@HpN}xq z0>drn#)9viNydtZedvaPZWvT+uq+CqD5ld*@dKT1nxaYxx|-nC=J22Sk7F5O*?SpE z<>jnjm|n0x@V@uROyoIc#Ty}LNs@co*7E4zvWzU1y4Pit9FoM*SZd{3V?P%oRaPYO zOc41wc14|!Je=NX!AplbS6Kd)gq_)q@tyOJ}K zigo?}LZ`JcvaGQ6g3IeZu4_}RR@iDr{D*&Z;kv8dt*b`g89NSr{&Ta=9rc%S`^i_* zXnd9G#-AbQqX%v!`X>3Ae@(UiQ@sDySMl)+Ay2la7ZCSD&Wfs`$`B5z*9pbLsocyH z=dSJYGA|@_Lqkzj!XQLf3-T-w^163UzE0-i0%d)VnQhVADV&W)8QY4b*H<7|`jXl4<@D74* z3&R-KtL|gJ5%i>7bLh8lYqLEes-7KHk@p;sic;CGS9H9l(wqChe%@!0%cyBwkR=69 zb@v{*JQYaJ^xL10HIr^@lj`guMV`}bZS~wBu55(0tSV=SWV&95q*c)uevCY4O#4@o zz}7Pw%?`7(HRkFT*WVoTt@P@Ja}EpreE4TBMSSjZ#E&1p4e!*yAiVfNoaj3v_f?93 z#mzrvHTWL?{Y^j51FJEAducpJxL<26-Ly$sUmck=(`!G(>28LfZJ$hsoqq<1Gl^=o zOh0w~XkW^Anj)y$IUC{kXkVDcu^ndW4vtl2dD$WgLpHX2f-uI`e{hIe?G+KTJST}# zy4{F0lQ47{&(*PQ1Jf`DMy-7~wt>^@A#Z*6(_@BYQuTG9Ef9BBcYXblIe)Y3(MXk2&2BHF*CH2a=5r)fcSz{xq=QbgRKANtOs8_i1Z~+K!KJ@O z^o%Ga#l<@Ht4Oj%k*pz`N0IbJ5MpYvLI}{*^1zPbj8^g7ex|>Fxk~(mJkVj@IbuDW z4=)7#*K;9v&%3Jz8AY2kgGy75NtyAW|X$`9;$s2dj9 z);C7BJ!k2SRK~H(sIJ+LnQ`_e(~Y>dOqW5D1N_**zc_Q}6}i8w zx`C!C#9N;qY%`YLh2q>ymglI}aiS>Y^4S$UbNUAnXEKgs0)mx|g!8#M^}g2%{eo&A zlLYmL@z8q0N>K2gl$y3RP+3atEJTyTGkU%K%fWQ|K4L~Kk^HB?n5 zY;8{u3faV~y@V%LI{Sa3D?m|5=$eMAX+&X&D(}AI17h9*N%leZ>BbJ-i?g^+mxY;G zEXyj1ItbX<@(IHPTQ5d@6n_w)s{&okaf~w1Nb(%No3PdNDGG_3ZdgQBWRkVN9($}h z_g0W~ET>WqWF*lQ2TFS(&r<4jgU8l#))I}|yy=2q-w#ZSo-ZdB--%|p!4CP+rR`&W zUm;wU7JF(vU#W=xbAixrV|i7QI2v1;?FW`qAz1k&^pxXdV-aokwOm|jaQe(TP^K{Q zVtSq@D!4DITUV@dXrv~zT$3p{iFJQpvmkR&mdZFBtC zJd2BUVqww_6|($!m>1j!B&jScdS=d?n^Cng@+>D=|69aPZ5-nS*5aFpf)4G*8gb~O zC>oWS1>EW^hUHAu3b`62all=3F%>1}{*4-bevQmh4}drhCX#bI*Z9ZwJWb*9miY#^ zRJP9nSyA>T=pq*b%d6e6o50fd3&YW2+dVVHjE|sW|2Qj#G)MR}w+H8*%n|aL^nCNg?>q*?>p7Gc3R0cerHz$i(~Q8~2fS zzKL7iKS}F`P0<uHYbkFv$#+vE_y`0%Z2?10j_HR;y@k0qDT?R>Ui|5&A)A+5e=nOa2)vvA?UU? z$VPvAx!TsBq^@$V)4J&-kH4Kakv0JtK{a{SowYCE<02NRtTNw2>9%KWgppq^>ovnHowiktG%njf4=RN#gy>n*furQyJ69fq znULsY3Y|=0CDQ5S<=<%`;i>t^&w_sKY9CL96)qV@ zl8AyXMV=u^r7kg&TnfXdF}h)qG#^D)JS1xlNwHDv>)1+V8p(L~hOK%yN(BMPg>u!- z8by(jr74DKmL|1%bWQTZlH5U(JG8?Jt#c7o&tiUN7Ta++={Wel&&H;YC{k?w>NGH( zOBj}eNY;=$Ul_k_>79grYb+|(4U=SwZcZ9U15F)SQP6a=bYc;LG!FMYh!ThXn1GTh z3F=x#U7LI%?qmwxOyNSPqe_CADfhcloR4k39n^S{-Q=F?>PW}Rr05y;Am}o^vA3C?mi7d$|nubW$37`2-NIRnE_00}uZz(KE<+3eJ5)8v6 z7bfqYJdEE>E;m&iOg6 zD)EA<#to*ReQt#~jB#roU;M&Xc-?#6h^;Ejp>S7KqH%U*@Z7R2;mlNtY8AfGOgZc4 zytu02u3ltwD`itwkfm2pWIl+P7n}rw)5yjWU;o;-(XA>s->^itxq+-|X-(sab~^CZn@^iuEmm_;1=R}~!C zdO@SvWq!WS+^oauYC^@jb`@_)ZX?NU+Cha@JEB%KnXk{`I1Y~E;CFr2Hhm;9nW#$z)?{tZyhfcGGn=eutognPA z`z@#Cu_;7&l6dhc(xgckoIwTW7@YBJRX<3r-XUl;C=Oi2j;UyO0xGu6XeEzUDUM@c znFh^Pz+x?6I_G64R@mX(Wt2A@DY&|1(tP14U;Wne?AS3us#1=B;Zg3o=N7KK_8_O) zDOVIsuFyW8`<*Z1dJctx$H|kk?Ay1K#CGY_qpX%aN%_a-jDW^`&areD9 zbKs^!oNTAuQwsRZV<$K_yM*1Hi`R7#=Zfi_n1B!_&%JP(=U@B||Lh<0CAnOeO| z)T3kM3wibw^0Znl<`>%tovb2i!?gM2pFYO>ZoQhBZAA>zqR~$I)MviQ9q+q_>kjPX zJ5RjKxw$2N{Qg@>;t<0$skdVO?DOB`r+)l)EGhck^wKb~Y?lWgKEmrKX4h@!?wym| zf8X`QLLd#BKlsx}sW-ByR0_e=NN1Agj*s!e%P0A35A4Kob0l$u zVY~d^A3w^ycV5rT_DW_rWtjYzPd!SrwK^)E9Ix;bKYAD<0m9&S|LB{vJ3)V))7!_m z`}Tw6+#I3b!Z0nKc;;1pCA9|;qH^6q_c@P&Dpff z-D52*se#o*F4x?k);R<=wlcLopzg3mpNnYnSwDx^Lr0{ zk5BychfvcyFa+FMTgEOGdBM+4oN3SCnTMWa`}8=se(YWd16qIlATPailI!2QK-HLP{JjPrURk z1|MFxPmSj7`o)jYF$GaAyCEj2z_xNEtz(=#U*sF#`ZoXQ@7>P!F-@F1#P9z8 zgFO3^fYV{VSf=j2l@(r1m&Ej&0XP-X?z&-E3o_ zl5jnH;0Z-@{KOo0-hM5kBSo|pym0h2e(S%S;vfE=H_A;_jF_4ZMDQmiz8HM5Vk!T#jS)AIUZF>ajC?^hXX;%)2D1;<@i1=Rf?H zukx#Z_ecA#f*n5s4R_vl5P+pxi$DC6NBFtF_5rTkStdzh4(^}f|NX7c@!nhaF*f3H zeyPQg7mxF||Hg+&k{H7T;2fHn3b zym5LSQ>?GwG^EB4Rvw3zm)ksla*0!?=Lv%V$IT+J%Uto zK2V%;$~@bq@8O&`1t(9QewT+QVk>&G?_OuxrBc!~&L%Dg9gM;?2)WX@aK)}MUi`ruJo(i3$>lsOE8Bn9wI~z|=xCNR za{)W1$Jkb>6KRV#0?mzg+{E;*ZCq760e~ePislI4fA$PF9@@jT2X=Gh#S@sO)lUdr zDjZAEYz9POh?n!QZHIWE1nzQ2&%+>$I?{ffg~sc=di)HFiy5=D_})eB-g_Iem5sW1vl32)QolH?w1mYxYfYVDAJ6_D*oc%*Z;e`HEdrT(fVI zEA~$Fksp0O9Y17oskO@X)wWHpJFtTTdndT_efzoLx;?!3(g~ztki-$y(Hu8kez6~BsEJjnU^<)P%GfT|RFSE4NV7?YIdzrfjgH+SP%*l$DcXD)KSS zCBE?BlUTMxlwRC*y_M+MkHm0^BTce-d0QOcHd$h!5pX`0EGWtEH1qt5-9&5no?W=?9xXwtd9{^r z!-wu*=T#>;b?gnEf9fdb&o6WLeYdi2|9(z)(rmpt^ZK28`E{muj3e`fp%+Y?q#Swr zC;&fr=_DV#=O#XQ_x0;0*3@e4{^%|NRLVKRu^ismU8IfYfK1bT?{x;xA06S-pZ^y3 z-hB%IQIZlaKaJLDSML)DtHKXnILi}HXBMulc8CA|S8hWJNx>|0=6D;|wHe#)kR}f2 zKUL$k+0(?8v&^YeX!IqQ-r1&RxgBKMq-CMrrW)CeAdDKqsNuKwvAEn}Y&1`~oX6@~ zfu1^jo~NIEg(OL-HGHH|q1`btWr{FjZn$9$F+I{E3}gQ5r&oq0c%IGQ{iVM`xwtR-JuyPH`F*u_{fe8%|NEV{9pt9#b}(BH(Ku)XsTSP# zBe(PWzx#QfIeG>qgl8Uqkq`XXJ;Xv1#R-OK5D(lqEYskw zkKILDC^GWUqs*OO#&a!#&T4|5oT%_uf8tKinkeX?(cOs?HHxKc=@GPu&hWtfd-zws z{UlfKo$9Vbpq8FPNE^cx#8HB>Cpd7+PP_yA@K2rQ8(+zW@7mI%WRCLfr(fsl{X2O1 z`ON-v|Nb3(|JgI#@}W_dqB$b<=BB-9GOb&6b;q|mdL9PPR(Q6e(`vG~+-7?FC~1=N z}JX>>~HyJ&n?t_Iuy^ub^C5ktB@pDBYF9zV&IdnS0` zLlu(x_i)BPP86(s2VPWHwn(Lax!HS)L zWf@#|a5t8h$YtfxQ>NV znr17+*@6+fZEBuOZGJGs9rLX+<}X{48%Hdr>ho;#44Sc~7AqXjMQM%bhU}4o@rerO zPM&3aVgx-hf*nOHEj1{PlnB<0I1^HGqMh==yRPH4*U$3$$@!s{ty!IOvv2Dt4U>A) zM_~?Rjx}TMDL(q4gM8_$S;wG2k~W_OD*b0MURx2oLNHo zF3&#q8gZO(?6ojJ6YK>H5{tGL=%EYp&kO^Di7@ajC&ISMQ?UQZ#)* zs%=cm;Y$xaffRy2`ur>Wr$2s$C`y=~u-RQc!tT;D>@Gb+viuln=Q#1gBPjm_pqZI+ zxnb8?K63AsJpKF$mRmMPVIR_)S)*5L_Fpx{q3f>XtKZ0`F^#zq|W?iu5joAz?##p5WI;&_=A zr&0>f%gQu8*G6w(BD8CIq`y6-+{A968FDKlw#wW+uo_ zPqWyq;Mi$r(ZsZ!@Zmy(YQ^I{H($+zUw;PEa#pRo+3fJ=-*}GiJbAqT4`C6;GOI}y zvQN@!`z3C_UNTlK(QI|lX%n3WsA!(OI})~U8|8QY^H*7Z@g?4P^m{!1_$%CX&jFh8 zGDWk(>n|;_eft>q|Kxt|{fQaw{fQYq{No2`w*zKRbSPMrH+?L#2pZBPL2JcK^=5WY zyoYV2>)zCI$DFI!S-qKkGk3Fd>=p{%7>3;ZoZ5)krN|=6ojb-T>9skQmz(^;Puww*f-5crNATKdJ)TVSgXDOHRS#9{mKH^Ig)A2B!Y+HH+zi!);hzCA?8!sF^ap6U-iJph$PQn-z7Gq-> zPp$ey94OrUB_v$ltz{fTP{}34Y09zJV?56$2qUJ)ZE}Tamgmo0@bmxl-evyxQ$>PH zxY1n-mLtXaLXnUC%ttu>{a1PYwNp5@&F%NxLTT?Fo?Tvfe2apR>#x5GAq1yhKf`s0 z_AztA)f{c5%ms>H-`++`m-pXxZFd5V$`UJgUdz`XIl}y6i<||P?J+T4Ax#zM=2p*Q zOj3<$*+@e&HBrfuTFj$@v&i-f{M1Kp<>Bw<5orSrsNf8;eS}~B#Sinyljk}9>Kjx_ zEWYZRMKe(J~G2O$V)V0SBj zwAQF3;v*ltg+KVzH@M@y2XKv*Yixd@&cFMQUje}PBa~MB($9a0B#9Bkc==Ml#7}Ng zd2#040{`}RR&VPs{LH<0j)ydi?t_*fO(OhGlhJaC`|df!w;o#>zQCz#(J_!ajeDk%+YH`hteLw*WZ81pLr4R3M!uW50{WrG^<45@10t<8(d=i5=D&=v%9y1?2(tibNVJgo zOAF}|PW&zA-D^1Or_AJz(oX8sqIvwZ#gx07f>lAISqjgw9GwRQRcDHdJ%K<_j~3Vy z?|)Oraj|8y@2V-HFyzeHg`pjVwwuFobA&;Mv-KlGma>AuD0s7T$jucq=dx~%d=h7! zZo?j{^Q95a%+{%ta@adhEGh?t%#lf*HGVIU2YvvYL{1rHF^8v&kcGg8Sh zJGadA^cXDs2}$cEtm=n2y|}&`&N5+o#|*+6L&x)+IB}ZMlE(2LLq!YNlON|yV<(oMWV%Lnm#tO34*RI5S&Yw@xV~lVf>;c9Zhh z6emv3GFB}j(h#LmynK<<=W3J+E+!$C<5F*>1mQ}Rm1#=GMhXZNhGCMb1j};hwCY%H zo^x|`woR0Y!*;*K&dn8AtVbkC3cbEWk=-P=PmK_^>o{JXx%n2UN~u!*eW#=YY#)oYY;i)*C($_MF*l$7A>8dpWcC9C32tJMlUl=Pa{JGqPW~3r`Oh&a*X9@mX8thf?V#HD$A6PaG}IJHybL-)V=^^f zAZXP|l7uvkaioD$GP=15Md-JPL!Xg?#F8myq1?4y@Uwkc2Tjmvc8$%NR7(abYIk*M zO{Z1w9)pN9O^JdIdD|fG7z0}_Fr+|hNxNCgMquR%Swb#}*fw6wY*W1gUe~ZlDaFK? zgYM>2lul7;_B0i?8<>_&r&*`y>C6s7O2#H<@ckCa1{23O!(d{t6+p3=C!fy|#}Q{{ z8&pd=BWR^GT3@Ek&EXZwfJUV$Dosec zKhc>-NaT0c)nRAEw({EQbqc&f5h)D(c4O6NlO)c}xk8^f3j2iL-=9rtle2BJFm0RA zZ<7LX9O1W{-9fYlIhoL`FXQI2ij+9$kdw&;Yo41vC~Y%VErZsaovl;OYtpoP@7XqIyqP93Gli5l zP8?%$W)EQ)QJZ~(J;e+2MmrE(y*IN@m^)v`AjUSK=?ly>(HN$D^Ag3oP2=cdD^YZs zuKq%M!&PBpk`pp(_=$pd9zkz)USO_RA&J5*Sv>ZR$*^U|af~-{H?8?UTQ%vt+o%qJ z3ePiYube|0k@H|=eYwavQG!~>V0v3t36eb;Z~c5u;)ur5d8)Z9kVS)23s0?k&qnRQ zmhBM7!w7n70fFP?F$|M-vxb*1W7;-x6lUdaS|g-E(3MY;I3kH7{8k;)vdNc6u|khd zv(|qiXx10V7YAAV#P|L0du^2STq(Aqsk z%|HC;L0Z1RkQ&cfzidB(iLqjqbW9bsrq4vT&@70+3|a~K%A1@lE#9^K3~Wx)hG}i8 zKX3He@TkPzEm11tq<2aq&sNA;2tlD-rPHc!$t->FhSfVBQffM_1g$l$&`3@2v*oe-S*kL=j_OU#`&sCNQ{O0Z3hV=3NF zbIZ_g5&D}C;gHh6wCpY4_y` zbEA{e$fO9z!?0|UC_pJi&haqJtW43%mq?O`G>%v6u-zMI&~B2n>Z>$PAq2VN2<_(b zfEFzfLL#I@N{KYBe!X#H`8NiK%#Z_1RwwiWXW;YmU_kD(yR#>(}u{fShp-CbP)1p;hLz?xemnOA<$Pn#*{(BH_ZHL+zoV`(>7I0t6ZZ zcjj+$Zmxl2DhkCMw(Vfs4kIIw#4+uTPqP`}`w@<*am?Y<%vE~fMA|U)K64?WE>^~9 z))rR17RHiLS?u09ie*{dW7PXjH3&(P#H2||suZ?m;^kJ#5Ch+*-t;k~#54^|LtvN& z2#I57EZb=K#BoHY6Eiwmq)>1v6kPlure1F`U-u~$S9FgkPRN@HDh1nw<)(k(kyl&6 zyQ!0KGYli?D7bjdY7jzzX-kq=VOl@@D0(AYY%=gds_ET> zh?XAZy)#!4skerlqeS4x64SC7AJ0=Mt*`qHqXa=pb4|1*gg{6m%h(H<*_=wFAC(Fr zk<#c-HR(wT0IruO3jA&ZjPBQy3n4P{Rtl9St4LKECVnT=V56{G$)I(=G;1xP*^ZYH zcVp|#5|-uCsx6Q!RJxOfN+h+%Nzec3%6=OKbehQr+S-P<>z7HA7@ejp&7Vg3Z5qmA zsn$YBi*nJXSnzOMmvY&nT+TW(JAOd36;kioCfKIJzQm`Lwb+cP3*{>9#_}q6ydah& z+GgkUD28bgg~7_xg)}fs**!k1k8u*mG+RDPH6KGLTw9Y0h{CLrO=&@@GI;_Gj;(Pm z@N77JZka1~jdxqjEj)LG$%zVKm_6mFZU7*S6@T-hcY%p2TgAIse;$Uxgx6Xx++i3- z?7d}Jjzoy8_1k=tQvX{8$IYYCbj$PJwnEOmm`b2 zk%C#Km8=}kH%rbzEb${rKJT)9%){;abEl~yPEzL1H`q0kWziQFo8*TWV`;6?X~G5p z^Kgi)wrQimxtW>1i8Rg3X45c{U41xB6T-05zgYctgGzOZ#_~LlySnYTr!jAoRO`)y z6hiiYrYd{Qc0F{OQmTxj+Ak8%{lUuSTchX!4cguQQv~fMOA9O29YTO@MA&39V7qBi zubZUWW~7{zS-PG_u~?v3EM&FzzE86ive=9O)$gOowvCm4-Pfhi{ohliNK#4ONigJE zXSmfwoiB}Kwb%p1?MD)%!_4+kq+w96HCR|`AgS$X`ve0YRe^;@Z>P?A^;Z zo1b}8#H=;=U1A=scuY*?`?_Hm2Gr^uYV{ByvPy>@TJ4ar!ex3S)Whd&3|_=(nvkXm zFJ-ZhXYq0+Agi>A0>AIky?$K=`C^46jDG|yD-#wZ*>q$$NxwSO}Y!`1#8mW;7v4EXphlXlx9 zO0urMV!^@7x#aSBa``-ylig!9;8WBe_KyCe=br z({C|9uNfb&U<|aWCvl7^SHEAS$>kyFi;61#8^9om_w;!+q%z^{z*bA@wt~%!rZ$6T zYg+9N#bN=&nP4-;Fl|1Ev;7c<+m}YpsS@~+BvvM4qaM@6e7~i()9J9Z+#w7jTr0&g zB*kKm(a~(bdgSm{VKbf8c5?_J`uPsq@yHiPx`Sbp?)GI-a&>YBbmr;YZqzo^!2!Hn zk!EcHX&5+O9@i^m!;sHCh;BTwswrgMeG^uzixq!@M#ddH_PTevCB zb{hl~^Da>w)Akjewok!H*73w;(xCr>h|pWWM$uzW=2#nHYt^0n{X-z=9|k!OTc>L& zmg|1@h#L(_KnmF}1&V7=;LiNbZ1Va=G%3VsM$FQ%s8(|nikbbW)|zIc$-=UaP%)mZ z5SE}FS?ri9lFMgu!Q6a$0<3GqWIG;~@(( zmD52#ir#R&QW6GjynKmVu|lx$T{`E!1O5*#ZU@pPtrve4QMd`K@;%TY4&{#$a4%qo3?RLb{a+_4Co-E&wSbKH5h7_5{kC73#AqB#)n3^cz z*d{w?#%Q%e@|Hm%XJeQH)hs9$7E{VzN-H#QJ&(zW%v67Iu}-s@k+YDJT)vEuV#7|) zt-^6~>qvSSY1;zYjgWTB!H^nLYRaA-DivQI4f; zN;;dZ(~z1Zh_VQE7(ow~^Jzur)!)Fq@*i(V(1W+SD3~Jg4-$#7o85zyXe+4M6G9tX2-Crx04@v zABD;e(l{ngLR6Aqm=>1p5O!<8!?4qjA|czKB<^4lVhw5BShr3x(oRxI5<{yQF*T9x zv*+4)T@6?3OxtdELdxYlrBabNPN~&9l!_kXD5V~(S+t1tUqllyG@gILlIEw)c( z)3O2TwI=h6Es8mfJ>*Il7X4f-2FYnNxL$r}1x+vU=jIBODq|#ZM6w-!5wKuP!>)G-a{Ut7mtddA!ZQ)LNxv^CvsEu&3m+*;y7aNd;^unR7-EI^whfuhegqjm(RM}y5&`yAr1q=P75gwisiAa zKEGRQy>{6`N{W>+RQo95sow^@qQy#YcQzSifSirO0fbQ?T6lQXI_>JcARUa{9<&P3 zaSilpgCYE*#Qsr|`OhGo8LY88amzOl`fW<1lXRNPByofg635HasxPt`>b`;Jc@*;| zj$>h2)+*_uhqJSF+U*VkD0wOQfyAyKh0M*>7^@bu!Nh6G?D-mLjnyk~ol}hp3jm*6+ zmqn9IhQ*f2=xCAg>dJgVr4(Tp5Jd?=5Yy_U1YwM6 zXsU%FhDe4<-h)mUaO!l}n>&kZX$mpwq0A#NqmSb2o<+ z62INVadTM(&cHC`!TiNAO?oXZ6h*Hx?7vh5?etCi9%n7lS+-zM4vFSqipibJ#o<7o~8{w@avx+0*{mxIzb}3Y<_-8+dTKe+JN`$>C ziUu%?*CMP@;-yC~>prgDITum58F%as%)(yMBq8iH3H(-HpY2uMM5)Q{onu&*L7b#4 zF4pn=m?TLt4W0dy*-t65T4klO;S@>>G_v0)k~NKV$6r|z%aoXgq|pk=IhkqEVA^c$ zP0+Gkgp}P*(3R`f@$&s-E@Wh##9`kmbt7Deq&Fkz%cenJ%HY@}RwPmOMVXf98)x^R zlU2wYvLXT5t8{<6(9KMz$q(1f?qZ~lw~Cx0 zD;sMsK78RfcA=WjV_Fv4C@?wUkjt-}#8OJqR1t#@z6>+w&#+#rwQQHt=mdVNP8@}_8%tEiwq<2^mW6-%lc=Qu z4-H|iCTAhB$3Bb-PF|RtWgeUv%>0!Yxji8B_)E_sgQF0g-u$xwDnK{Bjo3>M5QYlJJ9v-kf?NXP5nZV^kz}? zWr?8UP+^!`t5ir6O%f?osxfVO+2{6UB|BNoj#8l0ZnJ>S2w!zczSpe;WRsi?Rw8vW zlF!icTaHmL?9|yhOrBHgik?t;} zw;LmW1*SLM_5XX)ipDY9B#{$1dUsfUqaf?tYxgL9F6IgyEr- zrr8RxEQ6e9(`k1|mBKV+cYK$`=(g5h2tD7FRHdY;B25$;O`(wQpFf>WhozcN)UAnk z%Z&!?oKLdZc5S{5%gtaj?GG; zd!(Eu87Vt!Mr-v5Ese8-l-1p5QpX_a3po%O(;XV!jgouOaj#_*vg!%8sQvbcU90Tk zPm|2#NTsVuU1u+6QMn-yQlL^z60gi<6k_G6!gz=JZw$7xZ>2l%QqW6QrOg-Cku$=e zaP7Y%ockit+-HY=K3@2GpP+lq0!fng|F1PPLyIKsb_*6Gtv$^EgUz8SF9j(oAxXJYIUW>AcRC1CDP7o(0OgupN#Th zoUwb5-flFR-Dw)f#8Hf)8h~JVxlSjtnAu*&G)>|tVzJ>dGX6pA?H@rUb<)NW!sVyI ze+k(9T+-2bh|Uu>9?PB)+`XjEUfjyHxZb|Z)i1yLOY4(v5@)2FDw0Hzq>3a-iDN~a zD3UZqkPVH4AgNK%A*9G z7HUX^$DnInue`8F%5JVe6oqu!jXpVU6iL738gvq68$b9cuTo7MW)np$*XVju4DK9# zD^9}@SdQE@0@rG#A*M&7{hNZ;s5E=6w+_{Pzp*8f?~?i@NFWQu1~6g2u47{WMnT+ALWabXHZ&I9?WQF4sCJ;jn#MC97QMbU1UaK{=-|M0T?< zZ3oBAp*{aJGI$ZydZBN$v}G6t5^EoJ`5;dDTBJQfyA$F2AwiJoy*<*ET@oH7 z|yPB^_CNKnsl{bBQphxLxt_FCuPV;ISR69({kn8Itg6smDX#mS8LpZ z5=bv0sZzRADMVND$lfXhh@J#O_jBE4rLjUtfoWy?X1t54H!c<%5p;5jxBDwv)L95Zi%NI%KKTEtg+=kTM^*^u_?xE9Z6D5M}QzH}$E=uYC#PlSNXf!+2 z8WDmN&(6Gd-wZC6pf!S28Azd!V(T}*t&p@~m|YUgf%XaJze7@g3K^f+@_I4|$lrif zIgDF9Owex9ZmzGrcHA7oFj!dZ;J6->lNE%JH0n*xFElB6=}?bn({gZgdEz+5usl4^ zCT$%hX*^HTII^`8%eAnlk-7bt#e+B_H)OiK$|kR@`q};eu;!57Q^(-*pfbWhs&Zv`8Xv*YF{RK{o>|Ig^=cZR;ln)+*q z;(NQs_8vJ`(|P5etbUWUutx5|nD_*9^9}Mji=5};beT6vv(B+v-6selOc7uiF}YlE z$QmymTP5g3nZ(LMNQXk+A_!CbAjS|WhD@`cB1MReFSB8ChY*=}gyneHwoPm9JH)jo zFvAxvdS6m|FJ}1`auc_cDoNybh{E2K>^1u>J;De&K}vPRrCQC(8rOPPYy{i!KnPkb zp9GKT?IXzUV`@-;jkx|S!haDRZXwCI7QzC12f`XbSR+WQinK?O&KQO>hBOO(k8Y*X zu4JjuT6N8$^oo~v*EmWkO_Z1<%3@-oi0focQ1kOkbUHpocVmJULXs<%2|BHHqqK6x z%Bo52!_YgwE;~VMmCf2qVvXfU3`>xNYL&J;NXnLLysPSf{}LC*P|uBgk$j;{^Vn}f zXE>1kY0eBQ-hdV!?zB($CZb#cDrhPM-=d@EMvR)ke0Nm6`2q|*tAVnq<82oy$F zDgcO6Nu`pb;90nyhY$j-HRsPS5%>XxA!M}~f>`3m23l)8TT?2!IBqr+BK6M^Et#)UdeC#oX1D2 z4j2wXSUmRSWq$3eZC+0-ZocCRe*16i<{HnTr*-ztvwCL!17=z}(_AraCzCSzPJCU* z!0x#gN5OzgpX%Qc4>K)P|pPcmD$tW9KRxP0PvQ7&U@p|9sVZg*8HM_uog^JF<(xG-$O0&YWFlw5aKs zjBPdA?Nv~01)C)aqeOs_XJWk6?{bTyh-RyU<5)PhjcKjcShP}vJ<|4LIzcusPza6d zc~r`I3VD~*KTT49lC=I5D%z<0ZaB12!6@F0Gx{FP{2r9n>uzqV_ED+K?lei!2)qGu zN|S_6$7i`7AaqF1zPw3f+wrj79G2svlP1yfGo-B}=+4nC&d{^?!%yDJpI-e4pS+d*B5rsHMWum5Xud;UH~ zZV#~G@F@!gwm3nYvMZD zfKkV>aosFBE_W?kvYC$p(gtzu+xW9jl6EexWDQ|K?t0A1t$5X2vhuNJo5tK5Xq|0` zWg6IaHj2rz3~bx#8qu3rrq%b!?vZl68R7>Kj;V00tU=^bF)Se_4U;5^Nm_O2P8hd} zhw-X+BBdr=dWxj+d`8x4^Bb=rRW?z4^+Dmpi#vFF`*Hrm)jpnp`|mlOXO~X# zE29=)dw!g$o4>F7$``PU`!-o-Q|N$m-e`cov0=hl7pg4?B|+Xo6m7{K|m$P(FMhUTiWzQS#P4juEr=Yhj8nV z-H4BGjaA7&)6OP` zT<*q`zr;HWYoq6UX@s^;w-X2~PYb&de|4ly+q&@g-p6X%`n4O=qL248p+25PIk!RLE>r z4XJU8IcztN?Rxl&&(J#Y1kyi(&=)r?UO2n3Mh;_*ya!~FB#8)pAEgzBX)-#t9U;55 z%xOXxtayE_uPzDt{OdS5l!pAkBrTO*{Iu?%!2lZ2pa3}rdHaklNpvRwhS zJ4(dj)-jT>hE9ES+Tq4~JN#b3W{(~5%8@F+{;Bs9{+-kOvzdr?Vv=(UNF&ThQKS@X z$;n6n=KtT`dB@pNm;3)c^_)4qY~M{KAqlAvdXtWdB1#i`0mSR&V!lN5DXU@!=neX|`Gtc+) zJRd5yM|6TQx1c&ik*L@L)AbgT+q?M43LQ;=bt?y%|4^JWjvAs>1{U}78hJmS$qT%p zc`u$eoDux|of!E$L0y2-a3ZPfdMc${t-ps{Ejjo;s9_N;R)0Z!&&RQY2|-y2w92YB zgA_;(s^(rL=>IziX)zSpLGS%}ZJ8KZiWq9eo8aCphFS?Vy_Rxe7}F6c=>qfG5`;A^ z=rlH1z_Cn3-#}|U6*rkP!%aJ*DgWh`Igp!eUySGwNGSB}ll(0Ch0>_Va|Gbn&>^Mvz=Wszs)j&+rII0@h1$ zma=wY_gsZj-a=yGd#F~5=%qaJ3wS;)t&{?*BgnSy724GnAhH zFK|c8Vnq#Y-g~KRy|iv!wdHh7qk?5Sl&b=Z7iN(p8PhP>)l(o6a*2jvFz?bNo5WjQ zi={*{yRWI=sb^w#{Q$M&0-}k1_vk=A8>vi=nD?e~FrvB)k5p)D4U^5p=Mw8I^V%m%c_~AUoS=p^I|Zz|H(I8-}eJzR#Y6@!Z3=su7j+ogtREG>mrF@ z+XngJep<3B{ad=(T@-0k6vR@QjfE)3wx=+CiRG3KxsLXWOn&@io-U?Nm&Waos=g+35kKqUcC@rNK)B=GScA8KKTdXXVl8rFEydg*#fnc`OA<+vDHcl%43$Zac9t6{3AD8& zh(@Ehu7e*t6sbkT?fXgnLHIV-?tr9Yi4~NKlk<{$kG(DHR%M@pZeUcagf)$2OIw2~ zR$R*c4^rCw2$HpB&l{SI$SRcNL4+HRz_tu5L&rBNl=IWK=@dl?cMgW2h8|S&g(Go9 zQKDQJMww)1GE@F|Vk4hdnw%$MN{?$nM3Us%P1!dp+`7?Y#fk(AeS=L8ZsALhiyZeM z7t!&Vzb?(XTf6z{h6tZu4)^J;JerN({jja z_Oo?{N9u3<DF#p?PVQubuzO2G+At@k2Qo(Ym7pcma&3Ho0giF6Zg>2du0 zowa3B=49m9a?D*nu3J}aegl?Kp=x?)T8KzQ!?rB?2g@`hd@Kj@6@djEX~N+!wq?=P zog*6d$Y$3g$r@Jom35?#?_%w`9JS*D;;Ge`Reg`{6*J+*_T0#(!?=Dh&Yj{$oWi5n z`A5LF_bP=!Xc1CkJ>iBU@P#m@p_3o%sX3;^XK7k3N)oO!_v0@Yh7m=PWTpk*_o>d1 z8mT+HIZXV`Rk}DE_LRTYqH!w4+^F&e1kd4_2X=GG&vgb(NH@oL%iEXmsb#@65gQu$ z{<|$M`pqU5=LFi8HgMT{8d!i&IX^_};mi1O|7Je+?X6twN~~Gm%=eEn5gmnOrkTP> z|J3g(J4lX8XOE8O`^cdX5yxUUXX1Juj$WWrn);lS$TZbD7KS4&Xba9oaB@@!?!qtr zZAPVvJAC`gQ|dhtdeI@0cvWimuZT-p3Zxp^5ZoauTR%VEKSNtVeCfw9c3)H16iG=R zN~q&~Fyau!o&x3Q(|6w8dX&>41=!j9LZ4&DoIv|##8v!?HFA@ zz;~ziHjq+BqhyXk(&l4U%NW(lE7s^p356+!3bbmAD3_k0I`ROa@>XPT@61Mhxd|!0 zKWg?cq;P8>wW{hk_SCkOiF6ai-1K_ra3nq_E$ws=C7EbEO({S3^6S0rxVJaknyh7? zO!|}0gRF#ti1bC?m;n$3v}l6-aBtmWSyoAAn<*DZFb$oMT7Q#tJ%M~xVadWqL`kB% zcLdR`OqqumgBDF-R_n{g)sRLg54>3}($)w}N6ERAqG9x1; zWXZ?z6*^kefu6Xc)6-WV6%7hdVu=ivWnh~I;b;ue>BriAMV+pCBE;wlq~u|Q8x9YO z0Q54pHNE-i-auB=V6rb9!LWNM4&8}ZdIrtjJ0k=^jw2@zLX59Ri7%t7>$p~BkCA^Y znVr#zBoa@7527sB8v47ggXcIkHfml4qE%)}9&{Q8m3Nf!ajVK09cm{_{q#_RT7!mkh zO}t+zj1Y}C5nlLVjIJNzoAnV7fLGa!SJ{j+_y@$qp+p;BgD<2otCb*K;QMUyHn4*A zz{C<>e+r3-l0+yR4eX6X4|C{#26q3IsM$|+%ARL~fD>LzIC}_M_MqBQ*KyFRCb@!5 zL=_1uGe^Ka#?Xmjy5bp5J=)*T7CJshP9f6`m5JiP`;#x#e zMv^`Au4_aOqh5T45fbS} zigSphCqj}HLg5Iq5~}M}AqWDV=kBpt&|DEb9gL3;QIavLWkgvHh;N1}Jed9b!FZ46 zN;yBHWN~bw)H14AM)1TViV|VbV^@#MJ_{R2r4kg&CYEDNe;r+iK*uvZH~OAOwNk{; z%fwQLAcb47x_|b{5VRT=aUFlJTZvxMQg}rSOJBuHLns`@7`zYPt^Xkia!|8u?EXdF za;^QHR4c{WgpMufn681QMoA?jG&KgF8yw70spur9>5w)y3+_+obF7yO_|XKheLsyc z^Z;)DZ+QC5Y6-8n0kgPa%JK;w*MTKe?Vo}#$T)5e#oN2ctg0mO;;Tqxk0YsO>8*CM zZR9Qr_Hb=igX;4P4J{%y(n?1|1JP)d=B5nkq{(ouOxc*)kjSyEDemUA?>CFYZp!hM zi!~L;#W~q(!j|ooc0o@7I%>qK^0Un2Z;r1QA7v=y`#fXXLW8 z0cwg4Nmh{LnG38HHC)&CWjcgH5zK0ZWTqKWEKl2FbTT|Iko9S@&G2xMrVD=xz}7FH zO-7#jv|$-l)Nr^)@H4^pJxaMjBJnmNOFlV?p#7lf5kjD87Nzk<_M#XxyPpf>kcd@v zk>t6hImYB$vpIWAtYG_kUvf^{eHAYcLRyqc&m&Wot1WNB8vZN3J)RqsGe?2if;rJ= zPxP=Y0ZoPG#w5P)(bu2HHg)3Rsn=VQmC*u(sXvrzrHE!LWY zh-PIWjhPr)M5DDO#K=gV3nNvv001BWNklOHQIa6lHf0|WM98y6$&q*pNs?=-n3)g? zMJVP5NoJa-Od8GxP4y_0^xE+?WMUMHC1Rn;H(HZeBr_{Pk7>LC^im#Ii;fetS#|L} z5ETIta6O-~8?^5ReN)HajlLEqG_v=pCv{VIYwbs8BG-w_UyYpqIq}71GQQP|U!B^- zM~<(fyyZW~7l>iB_IFY$1UgdN1n&Y_i^yQGSh=!)W-dZ#<WUwBUtWXh2RsOdw=W{zdR*u{=&C%wJD#NUI} z(->^A!cgcLie483eT!+==F`%gCX-1aNg_kTWfGc$C)`p`UPaI_ zeM)2^e9xnlA0jcDlNJOKRg0jgVa#fU${aQ4f+*tcA+<0UjHMPtQG)D305a!3Jn5ic zgj@Bj*tF+Wro*a*0Ho6iN@WwBt2KhXJA%xewE1oF}S3qfEu1h zW%FmJyeGx>!ydk~E@}<8o`GrF4CgH@S0Ek@kxZ#Hgk-{_UV+28GJ- zOgot}6HKFmX;gxWviPAyn@+$gY{JPuh&N4o<3%I9965O)TH_IDuE+EGlRVY`YfSgW z%e*YH$YA(M3~Ly>doAs)DU!(qvLw;dS0E8_M?1;+wHuZw$w-on8j2vxDzc&m1uLV( zT_f;Or;&-6ZNhO3zVBh^Wm1i8n0g>vG%B;F2qr@i#TO<0n{j)R1Pu#=7wMUG;jaw* z(VM^?YC9U5YkxL3#o4vnCOt{jVOA@|k{N8da~7G2_)Smk>!2kZbPN zFV58(_U!h&H{|^){&5f>C|#WdIk`V(&#xyeNT6hop-?E%+L}RC)taFuK-DzSLLn4M zz?)@EDWNds!roU0j&(%SOL;obtauTar zAwM#N>)7n@p56QH&47}!i%!SF?pn{h_7u@rlzHtUUEKxZ;rd5-Z~A{hL484q@mr>L(<;)t|+TVaNb%KFEuDO+j9zxJToXYyK(0c> zM-+ld6fZDxoOZuK>GDg@U5>%F44yLXWpm+SR52VVLl6-V5Xb%&CchRC5m{_Suu4;X z^EP;QPP3<%2d0##PuqakvzC3DJBY<&%8xe2;b%yG}*xq2J3y}Xf2a`0rKsG(WST*qMOC6ejpX;m%36O2hH9K|$( zC$oDF4~!~wOJsPYKtn^CmZmtnx~HZ(Y_mG!|MwP$Zb_+}6{WLYb#He;&3HssM zb5G&f-eJCY%R@Mpg(@q2;jT279v9rHUR7`WV^A3G53GrNA2p;Q+4TclR5HlXrEK4| z4Nue|Y#>bRJ#0l$qrs2XG@WT3p&=--bzfrP!DJjP9v}SS?H##xh>Kp<N8^a1h-Fr5a>yA)iH&iM^Nw82f8KZ>L)$iEmWzD;sKxBtnjKw3 zKoBJaF?dWe41?j}A#B@0RTR?c6roTsq6PyGj`Doy@cnErl7(ahF+eTpf~ppv!XT2i7OUx+om0yJ6~X*B}*xn zOSN)b2p%<_e|{VN1B3VzE}S4hb8{1^WRk7VPw(2hy|a_+JNHFhGW7>r9_VG{kv>9; zL=tWDNHn*PTDRvI+4(%KRUc_ds*2}0b$8ZqGEK65Ap={Ut~<6^V+-j8OJ@4&|Frnw z$#G8qo=(%Um(m%0X3UmO8jCt4S-~sUPjJYIb(E~BQAQ1}LPQCoAj5Ep#_Hb=X)!`t zP%JR9C&SCpC2c0W7_$C*lX_9C5|ek1RTT7JN}~a^PfzZ zSW{HASQ0}ov3$P}|MPu`1J?)R%J)5N(?AVtvucvZ)O*!(Vb)UkN-0M?)kwK8RI7TG zMIS}985t>(&8BE+O0cVYWJ;>Tu`Sea1lu&Rt?^@V9h*ozH9J9H_t`$F{Osv9(@s;Sgas8<42wd^qc5eK2BYnLpEiEn| zIA7xbecY+DU5dn#2!e=FEl-&+87skkF(m!l8=`#YdkJ>zl!?bZ)~&Vp&VP;2(&F;( z7iC$x#O9(4$FIjkvVN)P-xcHhqu;{sJAYPNcEx88;rCbV$A`alKPSEQ`P%Ydertbz z`R#SQ|1*zp`UTHS*_J8gFe*N->k*5FShl2PkNfvL58JZ1;deflToU5m`v-Asm$2<3 z;310wvgFU*JYW(^xj|A5trSNFW+iDuFB6W$_gKZZH|W|WbLf$+6!SWT;XXoIlyD@9 zF!l@~2xzesp6k>I^^%JVESNtj&ui$!l36U%m{O4AdIA+wM3hua+eH>!9MQmcg((p* z1Y}w+3=>N=1jQwzk#zL$oIZ95LeOl7|$8lNaW#U}-=yQ~Z`dQJE z;XhA42t}6Y&Xw?dpH=ORENjm2%|AcNEgL&IU|tgkEo|Y~W%Iaa>ux@H^cupd%n$E* zilK6q#(nph_B)U45V`;IFik65^brZ)55C`B-_$tlT$6?+vq!Fy3cDVcnKyd3-g>7( zw9%(L@Xz1bZ*uhf$6F%&_3kk7xX1QR6-5=<_JYK_-=pw@&lJ$czLKZ{0){i5!usSz z`|!+DQNH&5Z7g0sLgy1J_}r%(=-dvUxwQTfy;{!C+HtK`tT2sv>vVW}qsm7=p5ez= z3~}^P2Kl_mU+)Ry&Af{`I1b3KKm&yK#YOJAen}lc-*v-2v@M$b#%)L==z0tBxQ64n zSeA`|kIz`Mr(iPA$48cA)R00b93~P0NrFWSn(;gr*Y(i#Du&@us@gcNiz51U(e_-R zMH5uZ1)_-zmC^{V$hz{6a>ycat(q2KfL!Ts+P?=4_U!`4`0c$ zmMj}~^m6a>yNS276HcV2eqkT(zdX#kvn-ywL*Wfy(K+)66^{8xmDhc~%7Z@&%_Kgk zVdW_nn{FO26yEelg;j5;f2@4)iV#=4KF)WKNN~;BF}gO4v%%9hs$6$Ll$$>h;b(7) zam`y}?0T%8Ep|OBbJd&TTy{)?+rOaUPT2gTKM!%`8{&Nbm;`_Lc!X*`V9`Ri$YsYQ z=-U+hiYmhbmmim4=Z5K-sIO1r&wtTavX8^?u*7x08sHB%Rr%;eMZWxHfiHghklMO} zoWS$F+N8^-r=r~ay9U1ZldY^jq(n64a_~VO*InoH(`#h9x}xNDnN|C@^XW?^PJDd} zM;z12M=s7_S>rddr#Gsce%2yZtXayD$24=-T{5B+{9C<$JKw!5!AY-g;ou|M__qtQ z*mm&Qr=C{Xcd5-uCsqlEeOg*v&N;h6TdT|Uzl-vRnisx3ns@Ax#sKZdH2C*an71^`0m9=VCccQ{NnqM z$F?NibI6&z=a4h$+8T_t)ra-b+ZAW9I|xKJZD=N$HRxD8eq(eUkuRNl9OtY#hcj2a zozJ}eBsL9hr>k!W$8lM>P~wtL*c@@B#Qys$y#HM2?ahcp!FB~YJ7pFx z>);#TN^;WcTR8maR<8I_94(r_a~&}S~>90HlE$AQmF`heyE9 zz9&5GxO~@p8!#<_Wh56HfBwM3+IaM_U@q+W zZ3?HH+RQ%7JJ@GgE9ai4qJ+Yjw#Z0XCZ0&JctI1tx;DZor+A!uu1hAXvi^WDeSH~j zyS14k4sT=qL2X=neGJzN#@sD`ig5ICtu!>nSiQD^tFLJQK$d)d`x}*Gj&XR~+u#kS zWO?1|Te$naN&Tf=2iLJtCzvxhc98!TFKH=oNlSr?TZ+7`!C>DB&02il=b4RxC4A@h zZInx;3Axz!lUex&n{YDte$lLt z9P(Lsh*KlDnXv3cn-}g?a7=;nfXK*Bkp+j;M}3)v9`E>hng6)2$N_J&_`@X;Y-605 zc5aYadxpikepTkgPgS|;V-d^=E)AP+S9se`%bfT75<@RYJalz17@xaC;n82JoPJq_ z58PHlQsGaZ4WfW#yT>sfF}V3t5$vkKZJ&#<;&m1a4i1iOa`b%TA0m9V@Kghs<#CN_Ikl^r$$Qfrh@&5Ogc;<=c`RbSYIPZg5`ufJt z|09ouxaIf#JaBg}ojYWHcT@0P*B@ZAd9%V-zLw&VM?;wA__;gdEfr3EgU)|^sK^tK z^zh&RH9k@Fz=L6KySbl-?+^6O?>V=D<|db?9_{9qKlF3eweZmG^8xtPx7P9OBTang z=0Eb&hkuJ+R`}UB4glaYKfV)1b@}PTzvZV7|Cagt22qhH`W$oGcJ8_%czV0@`XwBH zX8qhu*)FjE3D0ray+7uP4Oi08R^jqb9!62wL3MPJ{h6o3+;qbr_ubV?ZbalqSHy^@ z9ud_e9(GAb9nujK!8P$cpT7Qpv>n&u+G}lYxw*vSj~V>p7Xoj4TbRo(lNlHgaGel; zy0wv_pcbI24Ramvs;&We2)3rlQ4euu`DS0%8jIZk`C!wol%r>g$&#|VcUY|`B9)?MqZn|AZfua9v42OH|H z^%#EklOaMOcw$30Pdw7YvVDVe!e8$Wvu<^nzFvb5T~Oqrk7lNP7T}9tPI1zSRkm&3 z&8DZjdB@xH@uUA4qI2smuKv*gU;e7brY*rSsFKfp_bHrnPMOCZgDbBTIQRT4 zLnHOy&#YEZ!;xB#5g4`ofi-vt% ze(|m-g&vWkFA5&Rrkfb->6Tf%Xlzm?ST^Pf=bD2wW=iCXK_n>1F&uAvhC4T+(9mR& zHiLg=bu%Gx2tywtn>88ew-LoaZ~Pw@iKNpJ=Cvhw=esN1aAUB|n|>cW5m^?jSU@8*R7-1>`Uyyp{-k#4FI(j4CL zu_w9jk9(Ho9e>6)?z&+KmMQVj9rHN))J`1V!Ez1Cb^%HDc+Kh05{}xaVTZSW^hq{7 z+)P>SA(s!X*M%4QIDU{)_`tcP+BusHN%9c{zed_3KL7r~JR!9}C_K#i0}a;gU!kRC z7{@7c+M8@PZj@O#FO6;mW9owQg8XsEyclmi+u+x~86V82zokM`Qx)IyP(xvExG}<~ z{xeT1>Cx8e^3jV5Tz7p0*ReVCbdwu@AFGX}>wg#J^f&9%Uh6{-HaYqzgFoLn_mb{a zD{am?qk?VZIq!Ulu3a*P;?&=&qWJ9CDbw8}V|yaYRthv_W3;qnkrjny1I7Ntz#IY`IdNse4#+GSi*5;cXB9|%8calBvZk`Jh{u^+L0)yPFP1D8N?_R zn7=3}q0CjP3|E4EEoeyMdoHEE?$O394)e1?^p(?t$nER{mk|$#@PXr(&*z@!ceAT| z2U;>+R~Qxf|eZFAe_G*-URLQDBnh6SQopM1Bt#~d`k%2RBfyk4cyBl59~{BInUmz@Yt_HREB~w`pS@qo*TbVkxc!0i)MYwgX4oO(LA1KNwoS@27}L*2SpOC zcHQSB6-omlp?GlIYu{pV{l7;!@sm~L>D7$@w6!^O?vQ!i$vQvypE%$D?l1@f!y^h> zV=sdvaZ-sOCFM&IJa0ULPG@X}2BzxO!%`o8y~_~9JkP&S#&H&4c_Y|%f>=Dpy!kGD z{Q&{&+AZ<;lPZTE*;*S%dR1igN`o;cmrQ1YS|{w&+c$m=4?f7`;Ddsj^TuaX-u=D? zF8e`(i$5~6N~O7Z{Mzo`E#ug5(YMi|;qk(V+&i zFVCZ?Y5bhc1+6V^Eq9uXxy);`z||=g1Psd~pO2xcAv#(`LLnbjqn6glW_+G}YCLr? zcD@X~gs3!7EQ-wQ7(a*e=DGCt2J~{^{y97^#v_l0>FBU|;z^ZXUK32>O}y4)&~=eD ztLLsbX=w@e>pC`C$VXLtDiwiby)ign`a+H`d^ydrC$`Ys1fTk}$UEKvj_uGlSirFi zQV|zbQfO)#|1R;UM?CJ)nsu;Um#*D5;czRuF0${wX|`j~c$ViS@EQ+pARX_Ci_OM{#VpgnN&4$0-&&Fqh+5Av=`aBZAu3ftcYg%oxal_`R z)jGr5pQAYu;miZ}#RoR*=x2AXL|>uI;fq^&WJfQL?C1nwZAT+VFKK76ROR`BJo~j~ zdHw3e^cKqe=F#W4==k+~=$LhU@}~P4-tjz5OIJ?mfYrR*<>9MCtUA@^hzm?^{zMS@ zcO2kw(7P;lJ}k5PO?w_Ri;l3l?F$;QMvum&E`86A|9}eJB7gph#yMA4XxcXz09U=K zzJ|5XU4Q4#cZ)1New=uV{UWWagU^=w1fq?>^@=rm6nn=%TNxH`t>DH3fuiKjuWPJ6 z&Eml;!Yn({=5x!ZZ>WCSn{>YRjU?ax<_MQvp5V-Lnh1qe&Og_qvOq`EEM#evAjJr_ zGhSVK*wF>P^VRum*&?!Z$@m1#vzz0*usy_aM?FSNE+Y!>( z&lhNKb2;*GgKMrHn#N3Y(ywk0SiQ>PwI^43_SqmRoJsyZaX7TKImBW<58m5bTYsX& zE}k;^)Kzz}Xhn|65N9aD8N+d>zrc?^e=wi<@l?s)y*IAl>H8M&x!+t*GOLs8kMe;- z&cpYiEcf8~E9vZ%XkTXVLT(3t-eJ+w+&Il%<_=|af-s_bn5ILiSVfZKm?rcNMv!F- z34@(G)3h|#%V=wGb0p##yLL-7HU{hL+9lE2I;vY1;j~lB{Na`~Elm|pIIc<}5saUS z*LqJFyB4!)tgDqG2vg^n99JNc5V-7egG^fCo_iEt|9V(|KoKQerXd}{755x~DUwe% z9vBn!_2n^5jd#8)%;!Gm^V-+u(RH2AUYZI72ChT3QexNc6!CN;QmH_1U!HB-!o1}z zG99fcdiwIDqE1a!V~tiBh9mJn9toojSUjgrD?A2SmT78gBr;8^0-&$AhrZr!vJH(K zfAT3De$+7>dc@Hjc<^CU){VyE9D2mj9C7rq9DBlRi6@eD?dW8SJFc^vpNaE{*B;Cl zPd$Qfyya+`6A}LK`4_dkQ{`F!+*1Nr9ZNAr!-kLHrs9*pPvTzUV~sItTd zU$Yk1ZiW9L000gcNklvzVvUKTTf+0gk%R;I_|d zG%RsB^M@7A{9%O^ue15nXEhEx&zw`^C{czpe^}v-Uz<7`ZB_)7Fk}`4gRAoanOs-> zMsr;v8*ftaJ=lDkLVlOXqQl1{)JK07LeB{pMS;Iv6=wNK0eP=@oy`-!Q5o4GVjBYY z{I|y9qZ~ruiH9FabN+|can|WQ zEZ;Yf)A@K@d1Z`|K7p;BLwx0{B4?lJQndt5J5}eQ4PkzFV+6+$uq=UxH$>Rotx(lx zS3UgYE{&i4BF64+8OsuQ>~WP_ZjG@1fZ*oZ(BRU!V|JOwisd#-m)Lyv^J&Uu5zm8N z&!>3qiGU1W|E}k_^0S99*b}4|hWjHtdRGSkiHwQkhz#{kpL#g?oUMH6+S@ts_^D;& zdMQMzsX{UvjGe#y>`(wIc9DL63!Vr6^(`MyZ^Rj%$FIM;mN&m?ZiPJ-CeL^ev%$M_ zMm@J8`wR?~D3!{HBK+|3G(}zHiH#wy{Y{iNziE1fh3C1PafZn^zLlj=6zT1g_|9cX z&OCj5{nOuE;fCKy+;CHpcf3;~o@yYTYTzC3471@8jhk<4!nT8J{m{c9cI}>ejj|aR z+lIdWJ(X1YsNr$Gs#+q38{*-I8W6~!C<@W2jv)9rcA0d5eLrB=YFPe`DX}`!RpPA{rW-W?WZQRhpUuEoZq@V(XS?*}iQn2+>-yGZs== z)6s|z?9P?AW#e}4*}9u(Lo-@B%jRvH`RpGbp6D82bMG$VE$vf|FFoJmgils^>=z+Q1Az`Y+Te5C z$E&mIpeJK2I-YL%$~RhE^VS%Vj7Q^=Aj+PIMMpU7enR4||4I;V@;U8WI^o3lzL%Y3 z^Q-s7s1^j49&2;xxk2>0{3M%VpU7|jEsCWJ%s<7pXGd4$(IU2&IA_gJl}1 zp)gx*5Q{}wy;|VN!y5pP3ok5k)R8kAB3$~(AwK)XW)3}~4N3Mn z^YjYmpF6IBUc1I3nQ+;;L*|&HMkwWjFR!U^-L)#8|8gTA{%|{z6y$Ng@ztr7ewya< z(GQn7>ewu{4L9G^KV=;Vs6>_(3|qqUAQq3XV1ATuJp>>5sE@8gLxalq{(FSB<{*Nis6mnFzV9lrFX9A}-Cq_I(;rA6b!69cj@=z&!CxMQo_{a3j7;(4^RI9z?z zFr|t|gPkTGkK?*Nxm>BvsA0@rOBm|i8B~n=K94`~B!)5m<6E?70d1}0xgokUtsrG4oO0@0C>9IcclY?+TM(eNrG+0C8p!YNoc>&hQhg<1F&|VC zn)Md-qAUlctP^tI@s@THt@G&L{1ncF;*?N4Nz<~`vmWn10#Dzl^1{6`Z~pJuwV*E* zFQx%iNQ)xNDuS^ItNW_jazV)uTk#E^==uxpXf9d}1?jB@!<=?o0P7EX4Zr`rPk8>r zNJcY@n-`)*G`f3+k(Vc9MaQ<8PBXTk>$J)f(u$#d#S zZ4BxC?C9IgVEF0U`*SI{nSAWieWtTh=D3qv*tw%bIukhH^!DX&?Wr2x$(V})Z6ecD z*D6#H1j3Q{v^_7TLO_efsg`G6*LDRerbH?gCza5UWEt0W85t>3ELDky+-Y^+AuWpM zx_fkkmn0ck4Pj1bOJKVKWkVvHiIPqS*R!hYeCN9kci*k>t7`@cN8>?TT+76A1WY%? z{EjT5Br!CUr&6g*abl^Ba6u4QvwAhfVlY5tMIo7}&-aDHVb-l(Q|qe{iA2yejd*+s z^XGMt%jdByyN)EwJL_9=pq>3E! zrzPj$^RH|f_-uH&%e^O(^Pb@2p<7i-R*r^9Ged&Ku&?3?*0jg=QYs_`0Sd)3p6`>* zrf6%;($_aa#nfkX!hyj1aHa-BW6+Cvv{;hrs6neZ2TQ7P_((JO8u~s|ObJ0&X>W_y z6lTRjiN3)yk&sI&GV`&U)e5mx!yXAbh@k5UUXgs#QHN5oOsQ)B>jpL^hhqp=FQ{1o&^C8*neH^?ly+M7fDYh=h<9_Cq6F!D@NIS z8%4)c4MACP?hfpsTWZV2_-e%V_pzzxfx7j_QXLTFrzc`f>uV_G2I=;%AN3*1vQXFHEwt&P!<2aTt?x129*|xKXp2*+k zwC%BodZzC&Q^Z|1CBm9Ub5k(qGdP$-ujo@8$R}bhsgALnuNF;U=%rbuxf3zb(PS*0 zk%((#Gl|ij;ts|58b_7uuj?2oPbOzzO8Z7Z(HR*nTuQ{l zn9j^Y({r5}(;u%C{$8EzCZ;@MO0xEE3_dPJp@)G=FHt2yG!iD{rl;G~6wIdJ7<+%Z zzhfa6v#QhE7fjqWHl~Tiqm+!9HQ1HnNL|sz^y>unPogC66?wX@gXcrZkZ^pBjK94d)O9f!5|YRY#**DH4f~ zXAoi`mvTubmn$Ml5*=-6Dwc}v3a@+wy(j!LN6r&TU@T($SBRuvEIDhjBxbcty0M+| zri<|1@d#I5a1nhr441oS*+PJLIE$)=D4F#$^>Sq~D;9U)`#vvp_7hcRpES}U^>ZXI zHG)>uFiI$b<4ny{7Nh}oR-Yv#YP5tG;X4Alkf*o0orIF1DYO935pbm{JIb4w7hQ(x zO|@+k1gJ2=&dReaiLFENVs-B!d6b-ChRkj%P7zU%SQ1}{;*QJqL|-K$B#3GeEOfT^ zZX=ylk=@7)+v=g>6c7+esf{#*+6eh^JR8K2N68&uXEG*6)w(4jDH^RUX#_zeH&P&9 zDA%bECL$D$;^WWS07(r;h{TfQhk9pRXEJO*OiA}>X^Ih#2j{PQg8wb#Jofq@H8J(i0^6+Oxh{@vAx4+s79X#@=T)8~kvMEl1f9?_4CzyK zz`k4}ujfd|vP7dHL@$ari`lE^IY) zi3jd`j<;X1KM^@jQ)mIV{&owd>G0-vtU?eZLPC^lu6&4mzW(@|8dIEo-f9FyLPC@u z|KLGNjo{&X^uZ>H7$!4(yed9aO;nE zgLh|*q$8?F)vD6n*mA4=~gGJ)~ac1TK(f8^H&o0qaJ1S|y!yBa3y5)tMrsBj& cF6>ea3V@;|>0q(VGh978nDCnq>C9%DPk#q*=F zu<2v{vKY_M*#Ra+je56GQC1n%&V{JH7+WXYh3Ob6Mw<&;$TifHC#} literal 0 HcmV?d00001 diff --git a/gui/qml/places/resources/marker.png b/gui/qml/places/resources/marker.png new file mode 100644 index 0000000000000000000000000000000000000000..2116dfdf51bfb8ac9556af035d598cf2c68c44e3 GIT binary patch literal 752 zcmVP001Be1^@s6=bY090008FNklP9F+g_dGL z7b4wOL~YbX6}NhC`Y^Yem;_BVH^=jjGv%gj-gDq^?<8~n@6OCQGh-NK7!h@__p?7@ zAHg%1%k{H&7`2$=I6)SB$ey9%mf^nW7pw@t0liA$uW3=@<{h$6c2acLUNScZ#1n1& zj{lW0thX!xPr(xr5KoZZd4{Yl+b9~?SDiKsYw4jl=ahsz49ascH$lOp{)gvA{a+7Rbz6(!?wYhMaEN_*&FvlTY+Qe#GeLd5Y`1f1;(W)TxhmI&f zGMmlT7dqEPnL5c-$rEwKC^iKt`y;L(O{LEFOX&6M`3tgeo|g$ok3Ur@d#&7y#A^h6 z?>^6`UFq7fPoGtQPnFzO*2?UlncYoA0W+aJ?(31K(tFo2L@iE#B&)%{`ZRITEx!AZ zU)hx!$Bv5w?bcmR&+YjDzHG#=UYFZb?pf8h$W$s-$07?*nr~~*-vC?M)D-<;udDUC zx(`a(n9X1Re>5i2b#_ic_8U43M<~(&X=?Gdk$OC$)?v`lX*}=K5dL}Zz8b-2L$~o) id-3sdrSb5U8~YFSpzHYmbwF4E0000V@;|>0q@p}s978nDCnp?WIL391jps+> z#>S7;kN+Rz{2}_5UF)a6!^}da5W(CjlH3yJ360MKr$|~K*tuf?R literal 0 HcmV?d00001 diff --git a/gui/qml/places/resources/scale.png b/gui/qml/places/resources/scale.png new file mode 100644 index 0000000000000000000000000000000000000000..c4f08122ada97f0848409a7b4de914274d04d55e GIT binary patch literal 98 zcmeAS@N?(olHy`uVBq!ia0vp^ra;Wb!3HFgIj$80DNRoo#}JF&PQ<|Z&(Z(QQpe}ECj@=zX;NfjIC%2Ts>e~;XMma*JYD@<);T3K0RYVMA4vcJ literal 0 HcmV?d00001 diff --git a/gui/qml/places/resources/scale_end.png b/gui/qml/places/resources/scale_end.png new file mode 100644 index 0000000000000000000000000000000000000000..94510b1258e33726e65d4d5f539b8dc1dea5c905 GIT binary patch literal 93 zcmeAS@N?(olHy`uVBq!ia0vp^OhC-W0V2~}Z=?b#6;Bt(5RU7~DID*U6A}^<1tu^B pAL2^zV(}^D?rhdzjZ-+uz+kqK@vYpot*Suv44$rjF6*2UngECF7V7{2 literal 0 HcmV?d00001 diff --git a/gui/qml/places/resources/search.png b/gui/qml/places/resources/search.png new file mode 100644 index 0000000000000000000000000000000000000000..ce8c27aa6e387f5ac9cec3fe14c33dd99caca5d1 GIT binary patch literal 259 zcmeAS@N?(olHy`uVBq!ia0vp^Vn8gy!2%?eOIddVsZ*XVjv*T7=T3^|J#4_^%Bv{A zwD6K*07t6;M{59EBaj56#s{@Jt8X2dy6t9sVc)txJCxD|EG|s5-fY8qne|V~v6~sL zfm{@G=xuWP8-|V zmG|wJW;?gYF71;}bqfqzJ;VA+V4&8%>nGmE{Zk4En3CIa_hnDBN7jN#9LGLb1f?%N z<(47GIc=`eOee+7k8ZPmt=u{-``1%&#EP)zqJjq^g28AcLO?%AlpqE~#2|^N zs~}!@=UUeLVnr84MWeBiUpdLIP)o*%drn_f*9Qd*BsMD|N)%B|0v}*PK zmCUQ5zE20x4-5f4t5Nvb;0AaCYC*4RQotneFYp)_>;i47LHHULRtfL(&n7Ua8WhkS zJk*5uH7i(A4GNeJvc~Q!&VsgSSHNCFXk8Jn!H6^q-wQkzc3-&yxxx2o4t}$MWB9%q z3$9a|Orru?gQJ4Lj$sjRz}Pe@;3M$V5SC2-f8o7NX;i=hVYj7BK->bI(=++UBE8;8hPVAsuriFK>>ro ze-`ssID%X3CJSom3iy_HR~O6|a2Z`uk6Lt}0E=%AE($v@D4D*#zz({#-D@E9TZ1~>dlHD*eoQ!bpzgW zOHfX!E>ozi&RS%lKsrw9*vtff7dWl?F~keMO#bf+X1^2kwxz@2oJ#TmA5y6T`vs2L zbR1s-+JzlnY%%hP?=4E`w;gaYoa(X zkxPu>GrpTZT(F%nXuSR%=oH7vu{ZeHQfzoJ20G#%m=NGR> zAgN1FzYFOvU&JBC6fjp{i0T=^aaIxv=nI|+>CbDX@In2%e1I|~rPapn26*6Hq5AW* zuB;Q{N=y@<-5rZH+iL$Hlc!zWtY3WKc=8DkIrAa=3}#jMQ=AHzB;@2msf`wS2h8AxYmM-^J$OKq z3E6ehX^8ELEw{{F%VIoXG)4!eej&TjQ~0u^8**Hys>0DpRe!c_4c!i(*WBH~zyFZC zPGK6cDr>BXLjfZ>dfTcuRn*W0g<&OLv6}-P6zD-J>LUN%5gxEwsK(4iQAA%^uKT`p zk%4b`IF>?+e!d9fW~DCXoW(E63@>m*uPO6$JA$QJ@g-#*dj6uQ70?*4>vRI#M3Fq= z?h{?-`BS)9scM9cQ7hmVq5P%vHZ`vA{c#s+trm;)P53hEhY#ReSWP@~-o{^sh_x1H zYoLj5J$S`m#iPMU_c$ItfLmchL(SWxT}uznOe13v{{1UuuXoV~ok6Cp + + + + CFBundleDevelopmentRegion + English + CFBundleExecutable + ${MACOSX_BUNDLE_EXECUTABLE_NAME} + CFBundleGetInfoString + ${MACOSX_BUNDLE_INFO_STRING} + CFBundleIconFile + ${MACOSX_BUNDLE_ICON_FILE} + CFBundleIdentifier + ${MACOSX_BUNDLE_GUI_IDENTIFIER} + CFBundleInfoDictionaryVersion + 6.0 + CFBundleLongVersionString + ${MACOSX_BUNDLE_LONG_VERSION_STRING} + CFBundleName + ${MACOSX_BUNDLE_BUNDLE_NAME} + CFBundlePackageType + APPL + CFBundleShortVersionString + ${MACOSX_BUNDLE_SHORT_VERSION_STRING} + CFBundleSignature + ???? + CFBundleVersion + ${MACOSX_BUNDLE_BUNDLE_VERSION} + CSResourcesFileMapped + + LSRequiresCarbon + + NSHumanReadableCopyright + ${MACOSX_BUNDLE_COPYRIGHT} + NSHighResolutionCapable + + NSSupportsAutomaticGraphicsSwitching + + + diff --git a/gui/res/muon.icns b/gui/res/muon.icns new file mode 100644 index 0000000000000000000000000000000000000000..dbd06bbe6df93036a8e1cede364cd76435201aa4 GIT binary patch literal 968792 zcmb@sQ*fb3){Ji>s947M6hxrNh=oL?MqKQ#yr(_Bc_=wK zp^5#CyPtik&)=W;-!nU()~qW#m)5MWof&TIUz#Dm46KD-F{K&zT^NexpZfxr^cUnG zPgt$Kmv+`w{bxApH8t^`xBa>=v%RjUf62dycy7W?s_saEMr3}aS#K`4JzF5TEnVM5j%VZC zgue+B{2Lh#d|)5~nv_(^Ra?Bfj5<@mmkCiCdSs6Jbwcu{-&3~qR!EA zp-J^dHVJ61rN^-cfUni21=0>64|4=_B&3G`IB1Lu8{tub2*$b}#1GDFw^}1TDzZ$g zi92HimqCk<6BSwtAI~ZZ{EK1&B6ND}fJmCxHW(y9z}0%Qy{3}V>~;TF@@{qkF7oX% zF<$J+#MNVoiG2U6=Edlc(qfrpoytM!4>?)dNwlHh7oG{JcbH?Yb1WLRws357FPy!4 zi6s0AtFFeD7I$2wLHf3I?Vm-c8eOqq!PNszO-)wvCHrRfqFR~Fj&#nf(qy8@PY1n5$G2)=_Vtq}j?8iIKQ2<2OcOG~=jVqnlb`Fi~fKR^0B@AhnXi8DvOAiYRW zLOg`z+lfXbBwU*7%gwI20FN1YCPIlhWUDD;`|9t%m&f#rQOF1$SUsv8>YR`Y1h^pG z6c?Y?J@OhY{G~9g?-fG9`{|YPWCzjTh95;58(qGiZz}42r8Ghl0@PS=0>4F0u8zha z9$cZ#dJvxsLKwlSSZUcqL`f^TxdTeklGcD0<2zmE(Jsq7K-gxXeK7|J5#z5yL0(iA zzriJpWT19mschN~*~{mbj;!|0RWXdHyTU+(lG%KB>y2#mgyfU6FzRzrhgnW;4KXsg zPn{xOq~ud8A8qIID-0lNu-PdfIqd?0?O&z z0n2`b(eX90UsL6QA`Z+B<7OCAzi|LL)c&y-$8I=~KbZQeMalpV52ixik#t=%V&~(c_fk8 zLnLk{16C@-dac0<(IfV1CS*CaW5eerv6_S~+?Mti7Z!=57E_5p)8rnHN%!)HleLtv59K&sd@p`#N0~3Wa0| zXhq6D_rdTNrsY*t1Vs>=oIle6rv)FiMrar>EDvv|UsMK_J&d%l@rB%v-okIz50~HA zN#kfUkSc|>lA?!h&oK#I|jlV)d}^geJRf zy$z8U_&62(wD${Ula+(kxi4egO|hhwm$#IumxsseN__KIzJC~)qgLA)KkZ$&Gm`lH zv5Da?o;S5Y(&us%(?5E_51W{zB^788jnGuoRKcWOW#jIVB?JIFp!CUDZN#&q{uKgr zuOam7qT=I}rfSLZ&dgYOUMPFV%LJnl<(3g1X>#usK@pDR5VmyuR_i;W>$lOaG57~D z#qUPxcelzn0i}!0*@G@hh>`k%i;IhOzKz+@xjG0uv^ zX?8cf7N(uV*$T`6B0I6-c`%^IhuQh5G503NS?O%thR~o_`(pOoT>A(yC0Q7{K?Iir zyFIz{$8>NUF-(+^O=7f4h^drv54AH_pZH z&w`885vR<{T zD^|{(b01dM0%uwPhZPq+Cr)Sl<1ghBeBES*vr^LsqPu1*wz;-FnPy6tS^r$G4L`$} zTcdP=U;gxQyT;>1&SB|x;O7=xbaiGhl8={SH<-j30sZL7sDWQ2{#B=skxX?MKP!~i zNE|t5S0o)-{bH~cY4hH_w8_jzL!7gfzfHvY9}ZQmRJhg7llkOP_k`SL`?{3_o^ZbH-5E7IG{-lQ&ucNJ`*gX&M zKxQVt_Hv~w)JwN>Gy@q3w9q-uj9<}udKk@(250~mKBd7~PXFkLLn#{DP}1e7F2Biw z8)_a;D1Ew4Hx_M4-Dn+&Bu4>w)I`yEaC!t$5iP7eYOzR+YS?Zj#~*gS9vHtc5ejcY zAwKIJ)TaBISqsbH8VE?s|1j~DlxjAEEdtz~bagiz?Pl~qk6N9NDN2dITO-eQ145u_ z`A#9N)P!Y@fN#DXJ{3UyRF0i&^7#l0s5Y)$B%CP7o2}qh#Ep=|jE$GRjvxz&zOovU z`Y}f|#4D^j-VM%Yaj{Uy+xf;J7Aj49gAZ&!1rR)n%Z?vZQ+Uw#ktHrsD`zsIQjIro zb&I#n-4mn6(+tJ)o0N1w3OO2h2%QP1n%N%j?noTiFC-H2RqyNy=Jzg zyhu4M;U*cB@^m^x&r%0bpzH zRy-ZzdFispj1_cZec^D6s>qM?zGNg0w}zKz&G@@_9%nN(e!Nm~T4Ycv#Nq@A&&>y$ z9=fhf*AZK%hbD))k?!C?8k}BoHL)lVmRtw&k^MyhpwW$QgE+e|N3bmRt38&kd_Hf3 zmA1BB+CCnfXsQFhS=8YSeqS$Zf%cVVDdO3b&t@#&(N)7T-8E_3`%9d2VS|4n^EDrG zHy3=;!1Y87aav(J;N{aS~(7rsS0Zr zK`Gzr<=_Nez3gS|8$6Gp4mvr?;)`|7@gPA|TwTl0H=ez8F^u309elYr&-JhcPa(k1 zLtL=@-FsF3WTjSCQHL!SSUlPa)TP-HU4b8QHr) ze`ki-t>I%A>+K1yu(XfwM)(&w4yT?B+U_I>J)Q))Mf=nIZYY^-_onT#L*upaq2&RB zx&{3OdO#c7kOW&pK4HHkcHGUx7gw$QiK)l7R3A^wQgI|+1BjejA|3)Um3SCK!PEJ&!chfqK`$iQE%J|S z|L!z(E}kCpnV@T4<~0}&1C^x1%w%fq7;K4o1)6^7tOf=894PNlbRzSL17}~|0dyh5 zc#y{=q2bn>MT-E9Nbj47u1hpFxrg5G^@!vM!Gn##UfvHgHoH7tXl?|-oi&S5M=%67 zM&Wfk_*E4^k8T$ghlC#aL}F6Yc%~dSuP7!29+!i^DSEa&Zd}$;>|(w%VLp{5{tK}; zdT3Rk+{E3UX{+gkz4gGQK`YOVM(azJ;R8DUb8RH#_>o}#$`;~}>Ti0duI)(SWj=pl zl`D}gg)?Tya}bGm_X!#O$a3EsiVzzEPkIbIc)rmVBdYJ4cC?YxV09)iH9qpK?`d8m zoo7P-lz_}Rt};QPxme}RKD5CKY?h&xlY9`5iImhzlJEyNtq$gitHwf8RSuug1y)q< z?Sf>0Z!Ti$^Pw`_Elzn@&CAIRWa7E0sz_Kg_wr^O=>AnGe;ntfU8N(rArvTLgu`H6 zl*4+<@y$xd@{Iiu@jzwwk6-n~f3#VkC70v&lDUJIm|)uU*}fqZ`T^$%rgr>c zkuU5Y;>-P4d5wwKgQiLzO{E1Aemt~7FYu0^)%84c;DkjSXZe^jccHlyew+vu9Y4}q z5R>oX9G)%Mqgf;x02v=E?w792kOd9ipbz->EOFg!0|l0}9lZT7lNHM~b{w2a@^2jM z>MxtkN`^S#!%M@b`$lYLAD9T_C7$Y!CZ$yI=Oof|Oa-`9hysDy^<<3H4_ zjd67bE5!NmV^xH>@T!_9S)hsG;>wq+JHMFrJi`RTc$U2jRkuP2RV7oTAp8{QC8?@k zUalU)3@1;GLac^mvBno3`-CVtR)u=^BH0g;J7n+OM91;Lx5e!NnhMXt4bJYC zd`SCrKOfDlb*J>z+o*Eq`zrRqq24bYH>7WE54B=Vq>eMzL$lR`rbv}@es?Eeb$w7j zD4C4T_opa!Bd5CqMreET{Gvs!3SAZVTEw6u(@qgM4TvEtq!h);1`a5D-Z^5nQ57*C zhEx^sZ2qMUk5z(x^vH^4m&f={I zz<19JX`H7&m|g8Wy+AP}23yMy+K9P9FrIdQ7sSqwyKys$`o>9|oM8=lm?}5yqxm0~ z3~_T$7kv-K^*q^|Dc_JzT`D2H&3u8qKKF*}AF`4es(<`{R`c-^mIJ!{br9tS(XZ~A zX!t-p5?oCGN>6-e@r~{>!+7jK6BqnSC6UC+E}F@4jbOLI+4>Id8|PBdZ5$}vvnf3* zukLCKiff~@-Mmy;NT24q`90%fS#~^<0u?ferTFC2@OTD^W9Rvy)zK)*A|_{y6x#Vj zN)<#-f{j#R7OQ`YybyTbn$62}_&R*cDdEJ8rIw~}lY-0@%toIu+7_}JWRu9wMb$O& z;1#=QIVolGR*@fTb*rR8x)hBS%)k735$xC_48!~G2cFUiKNal^AS+H8>C!e={g4cs zVjw~cHUY@Uj319mud497Vra?=>t<+1wN^?PE_k`VGkav*Wa#aMh2nSR)SzicbTGtW zr_v7x2S{)4M^r;rdqS&oA(9+MjOS^!cCGKdKF0ret*;)=PETv#gGYq(z;C|D2vqh% zK23M*#~00w&04ZG-5PT7)?E*7ks#B?W-6VDPiKmQ(lu;<3U{=0!G!K`KAO-nVp->p zEd*_oQaGrJ95Xj`{VIZgG`Jy%ROPk?S>pmY``s|7d|ef$A>1Ts%xR)JG3bU)WFU~F z3c}^pyAQ<+#`E@1uBhJ=$!!HnhIIwRWor#g8vO}{@%kkg^mDhyc~_K8uh6)U?il)XgHN5%?Fh~WzwL3i@`GAASwXKlx(h!29 z8^IOX%KJeEyTeyTD~9V~#PyIS+XvP&7sUon23z=O43+e>pH%DZkO|0~=ab}w-BI|? zc;45?eG<;tzV}nKvc7BEAWqKnpt}s^8pHe9G|;+je!%ub?+imZy16CW4S_IsIl5uy zMXO*0Wn;sxD8{aq!0ppXnF*XR+m0Y5(cTh>%rpeH0+yp`zrMW|AFR*z>wL2rs?WU1 zhFH7x7`D&0y-7zd)eXo>LT6`@r#e5wNgV{T^4q`1b=>A-1itU4(Lyd)jc_=9ibM(( zX9q;@^&t>ZuF`{^S*JzUQFIrlCdkTqxwt9#wkRXG7<8I9kgGRjhk9jx-tps^I{@ws z<2*Uo{jyIQ2ER{80&_I11MYh(D?c;-rk;_f#@}CT?j_!0gG^=hqm9M{0$=?~s$?Fw z>s{-!-vMHORS5S;%w!X(h$aU9#yXzA8R^EjG@tEM4@XA7m>w~}IS?$Ow!U24f981K zjr!d)bCSL7x#)Idr3|y5Li;cX>UEM66YnzH?+Y~G>y4+x(&+!?C+t3StZ#brsRE#$ zj$7e(CXF#NJB*-Z``{FIsv+QQ+*=2SZHxDs^rxLak)llF7Xo=Dbuw$2YFE3Sh)uH| zDYOw0_wOxsik6HT&u!D|qe!95QJV~v2z~52OQ9x4G3k2SkEwXvQ zIF}I>gr=6e@GhQKw!6G~D5DeX{w}&v9myVPp7Fq}+Jk;(#9-9#$eH9%@1EgH_*a}5 zIi(EfzdxS#3w|u9%5*l8p*tXg@lC2nsGkSG>cfphY*N>T3RzUVy{KD4ln{430F@L( z-B0ff$9(ygEXXIb`-Y$MZZH>Mr~7y_%)V(=y@I#Ui0}u9H$TSmqwS-v^9}+II$#ZD zcA}Jd?kdx8Z#}xno!qTKYH{N}!%M2?V$4%p>jCJ^fcG`b*!Sg*#THJB#w-1%7Cf@& zPOcjJ?JonE=|V5vy?GzH+H4ij)%K&Mr6u_zoqY{W&h|K)UCEjDhv%O(z!X9?@1HV< zXlXQ!blx~Wil-%N^!o*3&N&7BxaXP1&IZH83H$9}PB5$#Xe5-cJQ7GHV>gn3KvLCDHS#U9d6CLzro|B!I)ajZ#reW)dpcgGmHWF=Nq367L%5E(OkKg+rhfmW`C)x z%*c>GeVpT&>!@#>S9O@EJ*w?O)Qjh08xq20=n<4&43u8P#drti%1-sbM1*)1>_f89jc{cI$VR)YQbU#tGb0!g+4Ca^XWr8T4YxjA+-Hjw*g7>{>1T ztRG3i(xu?MCpTpkgpX$&4CwDg`zUG^#Av$v)TIKo0Xz6=Aq8c( zhO39ns7tPyds(z}!^f#Y`pI$G4r#xb_jhF&T1|QF&ot$&jv`9>OKVUEWAuySV#t&H zf~a?n&zf%-nONQJ6aD?+6Ko79Prcj9gF>wtw8lM9$qjJ3 z3XnD_ z=T`lkO8#&ZZ2qC?ol@1eo!^)%T^}A*N z4gdN9V>0k`xn6x7wrCIBl}HAHAXa#VN#v2Ug>W2>Ss;%CnZFeRWPwacJ&BVnFKy>l zyww#I7Zh>B_bA;Q?}1KB&kW^T+Ker8l5a5Zd5iKYmg8943r^B~{;U#IziK{dytIu} zH-cizX~}yJowNu&4v>#W5=d3jWXQDWFnq4ZS*4^6wK;6p7G7TVn{$GHW|GzN* z{|{*O3mA?6bN-(IE&u-wX#IBrh*T^%;6Hly{{tMLv-%sV+-o7WdD($Xa z63H={wsUGV+MD0sCNk1E?YF#ons01jz1P9En|hk*{}1!quhIYN+rhQbbzVRw$;7XG z5=oV?4{&LJ=`34ge>EM8vzMVx+DNe0&UfxH+F2l@qaf@csUdVPxA%7-ck6JI6J-JN zodQDuqcqT_6)t^z#G)0B-}3>Af{YAYM_W6P)naNP29J9#H6w%8NJ(A&XuHFs-hMV; zT)2F(%-YUwDJePm*PE|?*A4mf898_!IZTqn%UcG-HXGOsiC&ZqYQ`p=hOn^kPMSq_ zty~t5>)-xeDz;QOemI_fkSzI>sq5Ab&l_c=X)ijcKpBsu+cIcyFs}}Mdn*+cmDxyi z+NN!fj)9@V0%6b!%lf@#RLW^R52Y7@;j8^BSbtdrs{tbhtKON ztJm;`UH{!Zi!Q#w0NC+#vC1lZm&_78PGXi=CyiZH@w@f)g&t1^R_ezudsGaDPTl|w zoazsc`=dh*HMOk$=l5@sV6+@M8vya9vER%$CUw*w=`jq3f|$QhM^zT#A1s(?AGVu?Ux2l)(67l}IF>3Q*WLwZK23m$xwO-RD*96AA*a z2YkR$7sl?#CR9|MQWZ+2X zY+{82OlL0&aqbD+lTw8DS=alO*SCV-8xTo|wOUgoJoXm-`>hRH=q^Pj>HcY6L2&bK zlrkrCaCfEOdpkn|7iy0G>bHC5p_n(nH+>`2TamL5e=e)0GxQ<)*-$@B$yk$X^->DueZTca7(K#;=W@uHEJhK7b>VF$&ry4_SJJN z+ca_Y_Oqvcy>3iUdsMS#2W6|~s-W22qPhi;9cY}LLv*OKyk!WZnOCD-^6B1OoVs%> zSoo-_T-FsMxwD{whX7UjJ(NC3nrK0MHp`i(wKeTs$g)@>V`93THsJMb*e4H^(A^&y z&(4O#{eQJWg@6CD`s)%W0KQ)svD9HD`qmK)n_5K)U&_-N-iO#3L zn-Yb=5t#(kq9x`SPP>`z?B}i4(D_abmOEbHO&wKi*Q$nWxsm@nrZ> z;2A;^d4COC{t8UP>)jg(8%;+cP-+ONa^T4VSeThrI<;@+cZAack%P*}njrYn5Dmyd zq4vyV$$#nZ)lUm#JbYgJeG3b0_eAv&Ts!t_b)r|wk^i}*ALBg)9>p;^DfIZyCCk#; zorGa#YB@kmSenM!pQ7QXi^cBGl5Om0y!qEk-8xs}E0s1nN#LIY(Djb)nv% z+jshY6KPb%w4^3qyjTK09KvKc*pAA{!HoOGUgNRoTIWezmu*5+w@0&W>vwsAQB>HT1%2CIM95vS zUEFK&oLI=-T7#FG3UK!`S<`o=s0PjhBaJwrFry%M4JmXmE=qrtGCj>ihEPNX>)^#! zs4c*UK#|pjgB#J_YQYNPF=onw#WyTw+bc**OXov+hs;`juy3CS;?1#ZT#Lx`6VQ0w zhB*yh@$urObF# zC-<+u>1k=N+CDy=;ow$SmA6#B+QYX`rpW%0-lwlmqd-dDWJZH8qQ(zGDCT!Q1}<6- z<)vnOJi;&wNp0Y*{v{Nj{&rB`jVbyqmv&{8Qqe&(h5FvygxraBsnSF6%3ldDghZzy z6;3G_9n4Xv9|0C6av4wSYUS#qP`iaRVflZuEN4grcN1k8q`z+Z5eX^psxjdW8s3ZR z*dq@aIQF&eQ7{(ZhfI=8ZgP&`o?h%3?iSm8PNjR4Ef8P4-5!`4dyM|%`GJG!Q}Xs1 zoyfUiS(&R(O!I8EoL6@XcpXn=(E=`3h%XFG_ob14PzHenU&>4?klg`~rgOe^aNN2m zM*z#{DziG0Cb169P~o>`CFLN^1Zly|I9|C6_5$3EF{ZCc0*fl%l|@)OOPNui3#d-q z!Dt0Qm|lO$Q!L|N4oXv+On+OB%*zxRFiirAKp+W>ybGpELJrgKg};R{xSU^+NgXs; z4+SA30QI?CQdS3}cnTzPdn-|5Uln$|b_FE}1^VmTt)kj{c>RrxE=ac&=Ip0gXGA=mP0 zfv)PdCfD0?6d1F2;y%#5EeEb1~L_J4S^ZZAi0!+1a zv{=VBYT>lxs#3_e%W;23{ox(nuW-U=hW?5JekP}b+`to15pd~OR4!RK$H0F%BB3K$ zqraHqxI@0w-(nN?HReqPa8N0nITYh%h4S)p-0{FJ@%`AmQYTpL-vH%o*m}eOPRoJ1 zArU@h4w(1RFH(aAB!m8}U>L?2&OqHoMxn^viXfwFuNvETY&?^5L)p3hWi)^1dVKoQ zlzz?w7V!JwM5N#+UJ&W_MF^QiBU77oe=FFOosK)Y4VFB(Nq~T)Gt13*bQT+#ZRq3( zvx3eSkLHDk!$WEX0_rCoj(%o(dRsO(G;(&D)V<0eq@O?WF7|*%D#0dNP-FgYo#s~fRjJf3N*ztZvV>-_x>aq zzx7VfC6UOmCdNXZHY4K-!d~u~-}JoxAcwQkMWVk~QXFjM9gxP0!{i|YeYE&2=I0sX zQ??!)RXr+Z&4?p%PGdBCJqUmL({b~q_e3ooJ1LpFmNG2DL^PHP?(;CkUzzFxbJ?mI!%SLOY^t4^5h?hou-8|agtZbB&!2Lm)RRmzo-Ywm ztU!b8kap*(kX14t8u08Re5?G9b|WjxZd`ttPa0%tOZZ%Z)rnTiy7l zv|Ii74Yj&6JUG+>s8bm&sONS*@lO2EfBB%+`#eUv?~v%UY}VzqM^p%UdMgq8SRVvf zOyn`I_2L>r7Em5e2(W~0-m{kolsIS8F9>@{r3eTfJ?B)yt z%a3G(2J?-$3%Mk>R96x`X-N7oZ}^iEl5dy)wWa+Y;$!gHap&@XfTcD=p#(sx>~|0E zmlY*gn4#Sb)-@OA30{?9y*?6kw-P{-G&-y^JiHrI+fn@*JlHWjAW9PdDNuJMF*|Xs z=yOPy)ee0W(=8fTj!+v$sK?7pc0%=d60rh69)Il!Fjxo*>Jo(i*=U-${+f$SX6VV z8|6`sXec6$#7c{DqRACCMYz{S7>L1g@amJHWWc3rwA)sPFE#m!b`)JeYM?x$mnw*HkmQ<=K!`>kbnnA?l?fnLRxxc2 zm;idri19`SP?%`Lxy~KgynDp)-G$5IK;IS3Y+^uYaY0XP93Iu)Yw1mbNQ$5byqXGHcldfp}l> zAyk3DEA(vSHW`q_fCpb0Wo6~QnLJU#J1;$Rqfg^$^}JR4Vf%6k6YS5MF6G=j^M@;# zXtyH3SY(kbJP+qlTn%x2IxY=~mBw%cc4w)V?Fqy4e*RMFLg;$^!%7s4Yf+75puX`wF7ZW}Ef*qw~ddg=fJ;12eFu*G?C)RS3E9?S<}!!bHL= zO@e{AI;aM}qLIq~b$!hD2&KGj3g{PZvz9z+9$dM%b3}Pk|3rqc_(0Y2nC|H~1@t^k z2mB_f4f*ojdm^WH)f8i{XPzAT`te|G7d_ zK~>$<^YrU=b2;8u9(i~cvM^it%+?)({?NWp&pgl? z(+30*og}r7wi+=$T{5xmmgII$Up~d~rBJ`%|`4$b&mY2^wVJ8aA#5hWB+3) zLP`#UuO3bpVfhz>jm#-@FSMgGE#+P?YQ$|z-YE1ykK(?*A{F*?EXfFLWQpsgR02C9sI|!0TaKN@t#?dsz3@;&2~?@cDm)~Z-Kcdr4buFX9Nz9 z5fLv0(HY$Sv%;+o@KR6G%k2d%Ic!r(wBDw!i^CAS?WcS-dX;eh-QWc*^_DDWFPaXM zlV6tbNVH3K8BsBlF}1^<&K!FAcMr9SF0J~=I@>$@3x{Oo5Zx@zjwo|r_tGgj?fch5woQLUSCmu_P8@AH zg3T;MHGVXgZ*tPEpHQNkD7|d^)pQ3Z(bnU4?JgG_HVg-JnTWi>q?8y<(-gk>1|8Hg zfE(2A)DA8ebjR(LS3du|r4bN?z~MecwS}}hs<;gO;Ab+EVI?3%+TN2|R4y83aav8z zRX>Kx6n(NDiGK5Ub1cjUJpY~@jjG&W;GL%x>yHs=H)eTn4>ZSOFqMd-xeqhK9e z-@?&w4<_TGXH;~)5KX%&R@M7pvLss4D&mG=k3>rf8xTJR*K391!vW}yL%aP(Ts0p? z-W%^>nwwmTKs51`i>RIu_F(WUX(rLDjy`WyeE{5SQ4FCxRL_NjX)3BMG$v2Ej8rVk zHxgK^7<0FIYTb@9@{!9chKDCf&+>qaa{sR^hfMWI4$g?`JQ%LJAEVf?r3R_YHj;v| zeiN5<6-R$wx41F$d@n`#R4|jvP4M*xLZ66FPpPOrj5tw+@2(sHX z<^BFfx4iVDWy&MOZU^-%$M=^WeK*`UR)<*O&j3E2KFOCD2BQk&?{ zb8!43hyf`)==()y-}PDz&I8CkwPiR~NT!2(*YkJ*u!b~)>EbW@k$_dP&*%i(#UjoX zv*kW!;qJV}k5_VEH6F}L7bw7%Sots^I`*e8!VOzQaFsZDXRs6>QTbC z_3X#L=W5g9^mEF`on^7Rp~>Yiz`5XMeC3;jUNXHVqlco(;7Zcta(ai*PtLN5C3E1n z0?88RQ~v^*(>l{jc#6MlAohd>Ox4l9YCr)fc7cq23=tikekXnm2zZpT=ljBZi9D>k zj%yum7!1pLb8eGhI@gzmP_?LGk4?+dC%UwWc%z0W!TM$*zEJhKn=@tnCK;8M&M+SN z?Q|d|^Ix)@ABW+4#W7^460N*Zf<<`R5w_=MVe8mt{Fr*=DPU>{6$m>NaLGDLE?LyEosx zsn$Iy!7#UE%?a?g6*%88&pnO2=kysk@}h~{SA|X08n?3Z_9<{xUeA2=ZHS8$S)|c0 z^JO*!!r2-}|CPy6Y@V=Lj^H8{VMH4#A+Be(`Sb6AAaxQ>i_=^$`&k4dl|0Qs6<+|IcSJs-IT1o73$uOI5 znfR(N>+hr|P#Q0Vht#<5*2C@^L=K|;dAewc?!USDejf^PaS2>v%5Rq?ljt+x_9hAR$t&me`OIow#QX82w6T`>uVn@pq19}@XoseX!im%Gq>MJqH?_%uc=373Nb&fR{{GY(NUT{ z>IqKuHe+}jZgPHnX79o8kX)mvya$nv%CMazzZ9pqgV!ZLu)lo|L|2NPN)2@G$p>1c#9nBwA8@R#|+|S zQscW6??hjRxI!V21}yaKzRyAlb!FtZ??r$LRI|=rms&?%6#%Y}>8)I@{yebvKqA6@ zAi&dTrKeDS)ix&1*Bs7|%&ntp^CN#83!|yM29aO`V>oggnF-pijdi!Zh}AO?mBn2W zyu@EL$Q&MkMEVD>!?CU{9wRE6-yrDi0SCx7S;_P~(RO%9=)&08noZ79(nXE^#c`2y zS79q6c%(ijK9j>zt3K3lI{GRde-`}-A_Ms8PaS|rs`28S1eoZi>A?^d9k8HK2)uOS z7Cio9iPua2<1nq{C_=g;7tqHzv~}i#pPnC#((4f!_^FEAEm<2$11Zj$ z>OM>GbUtwJMPR#xz7${YH%Ju*jZnbl%YhZ!pG>4e-~0%qD%_rRcRB925%=c!ap8_>=t%GjMi)sYt+V2Yh#n4Mw$(9nyY*@H zVXfQzfx$7&1#b5wEus9<-{(l@+cFT10pllY$$7xfDEm-4Ud&8pC1!sp1T!`y%vcE! zWfj=NQAsR*f_wCNXi?sd~*<0tjI zPV7X7cu#L&9AWt(p~`nlKban+2vOu4lIjx1o)f;%nX+@+&MhJ31!BN_zSp_jZ|J}i z88pUf=dHy{mjm#eO;RUX?%IkXn|K7lE$9x{JHW&6N%C01kd}-l#?LPi!TAb4BX23m zIK{6no(uPpn$03$|FrgwF6W+oev2=Kz)iwrDiYN}de2f;oj!wHIt~JhNmde0TPlf6 zchz(gSfidEbZN#b(o=E9vJV-I8Ga^~IBB-Ts8p#~UJG9MTTP>AdO9c&HPXQ4v@n92 zJR^kHGJ@BR>qlmha(!Ay?h4s@0RFw!jM*&dYw)eMVpKYN7xtq=Ey1L+Ou@Lf_=SEH z%gAKW6XWCegxpSI@nkL0u=qalziGf7hVh$EtjsS8vR)D@5ZYP$w1(tTfOJ5mb{_(Z zBD)|y6}4YM&K|M1+|U@-i!5yvG~mD*i-)$zo7LyqYy14T zM6h$|Q0B;>sckV?1sK^1i<#=ly}?$KDHXrkD_tF9vwV{n2CR6VCziH6<4x_}TS`ea z*`hiJ2~`jXB#=ynbE_^B|u}&Zdd7&NmlRX;CZ%C z4r$|-!sf3iAK*b)TcHcP6@xyA#QzebmOPx;7`9R=3k;WL1wfLilh}AKktK0DCV33W zSmh#bQMneC6Ews_ch>I|Ss*E?XaIR$<`vHxgMcG_8%{P+TbSqkv+h-F+`Q!hjP3eJ zS2Goa&nu`U*Ox^Gc{6zZU%x9?kQm`-Tfv;mSGEUtbE=XafHW}30vY#Gd<=mmAf^HO zFOeIF--tALAa9q3xKPKKo2D!@UCO9k^D~g&qmd+cDknHU_MlrErIoU{KkXhw8=(en zH+0_j>Z*QP`tbTO;4+#aF&6H4%M~rpe6Q8!L*COs1sesAaL%a6$IBh}uXsBOmLS5@ z-xW{(kQ-q8uWH$MB7BpN&w{d@-4P?_&W6H%r=q4YP*v};*|jUj-(}uFsJlta83>g?oMy&X?eQ3__6B}jTw}f8yQ!az^)Uv zHatN*MYO!YxO?W=O6Ds|6s_XzfVVU}g3+z-EYO5?o&(9hx;${%zn{$0E3z^sseJ7S zHdwbMY7F5#47{##$+#_P&d#odH;+N1t5)7wTX7-{LO6 z?Pk2Pk_fJK6LD0SE(&pa(+5vHx+u(_-o5CPgV@G59Zzuyh1-IEuCg@Dh*Z`k$+#Rg zZWm;0fga}xm}X_w9R7uJ^sPy*Lli#(0wSFq)yj$RXT;t*C zvp|ry6N>DdS&S}ApJxSNB@XF^G84v@+*0NcliCuEcd0)y8F~%!u~i+H)X*R^auc_` zH6o~15{O&Oi#X++DDHh-uJK~^PJqr5^1P@`^2aw4dHPe)lKIPaA?_;aXv*!xwngDY zNJGf}yJ;ZpO3WlqY0HbJ{!nW`2vd=h8_S&e8rixa>S>*h&A71g3k-kaGlt>WRYHSp z6QdLJSnbn?jAebadB`Oyd^a+#-LAX4=Ql3F>SMo1toaE^fYXnYTCObA?pcpkZr+wM zOv?VLcW#=d!oG%Q1sB(-Ysf7pGXJ`)W+J9n3{Nk%e8=9-6OTcbRArGE(hRZGIZa1S zyb)@>A~uw02FU;5NFK636Z9+68^NwIp4_6<=don%qBH6Xji=`0RG92%Yg^LA+nVZ4u}3Iqs}OO=v9ME?fB@^fElb zLwWo8b7ymivkzv{?ivZxVyNSYMiOZ)Ibx`L1Xna&Hl_;cR`omhUWC5{J{iuE9h>X9 zT$>Kgjch$blFUNxPxsiLEdJ{CVS__hetPP#U9ui^Y52Bie2c%91Gqp+U>wjnqI=&h%+_QqHwOn~~BgC;fHDcjqC z{cW`QqG@T7m~EnHZ}@H_Z$k?94nm3|<6C5-jvRsgEggD@?=Re&*Hps{S}@9WWFj82 z^1WWp#&cPv&g{tZhK=V4O4I#iZuX@5>gaw5;SlE?sTVDkOh2b89=$tJ zzCDOOxj{j0zCa_sZdBPHm|zO5>&k5>8lm4F_PC78U4LUv47J_W4)e9d{<5@WtMx;r z+`{a&)9dl@p;iW2X2>2&5<<;)(hj75=_k+h8ofaGm^LD%&<##EdrxrKIj(t*x{_Q1 z6J+`Mfh&m+9qP9rcN5c!E!nkWgkBYvz>;>CAs6rG!yRexCct-0mz!b$cRQ}x9idH^ zWCPTfVuBQ541_^25wP-e`vtGb~<)Cwr&6U&g37Q={d7{M$cMRwRTnQz3=O8ig0-jVB4DwpYG(UJYr=}hbiIc@hWS@Bt1h)pX@7fx%`SvN=j$HECT?XfqY zC}XtEe;E4QZS8~&TTur`vGEB;hA zBM1q7(Y=mwv5-1&J((k!`$TamTFcU z!LTN4NAYQyag;5SYd?}FSlAs(wO_gm^;PzR8``mYeLB~P^eOLLmILp``$=nFc}}fh z*vQ#}KVL=yEPEM@OeY>ICqdppW0XR70X>L|oW|MrUp*A2>lW2$vh#yo$oOn~NFOpv zDi+KHn^TiYP7vz@+rs!!b`NV#78 zL!6l~EB3!+Z$K9PiA!LWW{jO859Y!f`7o{50~XF)s$SV_bMT=-t9E9v0!IUq7>@3k9x4PED&MS^)uft+Vvz*+Q+Mp2iZ*kAAY6X^&8cyi9 zqvZQkSa@GC3SCze-k!qNqgzXKU0GmPoJ3|wDS{XMKsHK0p;MmH6!G2htJl1vm*(Yk#s2$6%V+t0fV=`3|MsAw~c0 zBSeYr&C~iIYvxcV_+8O?Vlo?Jto^~XexpAPiICmciv99`e(*%-{XCQ|>nsQr)=vF= zAe`5-4YK8h7WA~FAun`kV6^Aec^@}gt!UUOc3g8dc(G0;(j$72gA?c$2XI^&fkDca zDvzK%q(3mwocj*cGv4RbEFN&?N|k`RazDb$a(U*MmMG&=C=O^zu`A!M)p&3LfS@T7 zyaV!TGR~)8Fe%M5$^%M`BsxZ+pe=54zHq1ndc~IZdLpsdJZMa=a=6<7?#!quRhpyo zMw6>rQfcz4h6;Mrez8cu)@QP!41~y0`EB}xW-(|F)u?;LMszyllwq$C+)tm`o#pkb zztn zj_lS2bE8dJGSsCr2zk%o*LiM7CK4|foqe{;!iNx&SmyY5 z>dAcDkzDKa?xC*|Hf-WP2+_T`hoal+Z6?>{@lI@V=?@C+0-fGQ6?0FzPy%%H&jr*epeW5o0<(;XuoSU4!8WAF_L$DF*l)c7!rz=Y zl%Q;c%@0y17+(nL)ik@S{KdL#dr7_d6Z#xoDw#ST1<#=9(Mg@6ux!Kve zh&c#sT>I|3v3VC95HW)C1T_QhC%)7I8_zHn)RZ{t5aLF~t@RGLVqV%C6hcpk#nuJE zC$uSBbA6af-y;<(((<}xI5p;T4ty^wqiLYbK1Pb&XX4ZxDFIobFc_(J<``GscD~L@ z2A|=v#cuxA#P#;$%9^&o%oR!~kragzAjp|I5X=gDl@t+Z<@6_^Oz`Iax{W)35X;nF zVY5$@7kp??bJS8hIRFbJhNn&P4ZE9%w7*K#)EOhq(DKqqR0;{&pD}PdFMyfB66)ns z#+qoBzdY!+*qWYB+hpeostK<;!JO+IT5*^sHBWz|(kbl@=KFlNdgK>X!HHIZu~_lm z34kn0s{ljFmU~G{b#DUx$I%x63Q5C*?ov3O+JBu-N9YGDBL~Nz#LJi8mwXy~xbWP6 zDBJi?^NXYs-IJp?s~hixv+10(aV|sYT5M^wJRhF21HW-UejdtE5_TecQxv^&OeWWz z_MId5dSj9`W)b+|P;_?Tr-ph$sjCQ=U73>*i!4H?_$n)BpVwL)xhBp9;HDP!7Xr!z zbDI<-^_L)&ZNYQNX9L;6?|Yzys$&1gOkQY6Z-wPpWIyY^ka;zx?VX-+AlFA6#*x&s z8a{_N`CfbI*;&0XQ)m*arLG=u$Hrla|MNH~I6c*lcTuB7d1DEA0xQba zM2DjTt+FMS!Do|)RaHQwr)Ru08g#16Abi|50B!9o-|g|y>94w1x&_=#$-UihE5}R2 z>euk&m4}M_S@{TE5NiNqU0fORrj@!lTh!{hWx()t6pr~FV#u?{HafO8$u_$Hpo4WZ z9&hst+KJ_ljQ}E%WOamnF5k}B8xvwal0(_Z&4bIqVM@8~aYNc< zJ(E{P0iS;IUq50eR9vDFq4awtXkdz5CtoC012odIWn36 z<6n4}qgL-6*ZQ8ml#Zp>$L<-vcksFP_mtcjd=r74$JrN$iyiyzP8P7@nW0OlL#&mM zdryPMh5laP&_cpxCh|x8zXGIKnok!y*{b*5y!@!;t*B;NZd{dt8b@B`C@pL~Oesm$gHXujIFg7I}1xhcX<2kp)Gc-YB`ndHIzQ_fYibeEp!urTx4CxYEA|E-it< zERJt?&UB^}bmVWXRi{yR>e=|VO9Po93QgxZft|@fii$AR3PD7+oD!_C&Nd`k-3yORRmv zoFT|UyoqT43+|Nh-q&yI_VnEN1T#`PKPV+s5)S?#T^Pu8zlch@+$^$EV~dLiFVOQX z-^V_PG~iWNT)8g?eurhMJNM!bc6xw&@@1@dBN#%s-$ZK(3CvOOE@TaAOwWHnAmEch zC5b{F$lhV-=*y>=*q(+G0Ff|O1n8*iIBfQ$P^TqlUTSjE^4zK7c@|}2-$o^)@Tjb0 z_Q&EmKOVMuc!1OTCH*4>&^Y<@+qQ|f8C(vf{$iZ28k0XHl{u>01RSH+A(jv==ILF?@o zEtRVkFHPfeVn?s&N43hj);K1E=A5eUw(0WzqG;T>BWJ%#=bL?Jl&t1FCKS} z*suIZ-I0FVG%xHy5-511+Pt^aMC^Xrm8%r}07E3~%AB-Ybb(CMps`v%6E>Nf9WshN zbGS&q9kL7bYc@CTlUxm~bw3~`t+Fh(ysGQxm*Ky zGsuNPQ#X32iF)s^p5?(Z>-C;`jX&qIp&MlkK7+|b zGE6KhJGm*sVLbQzdQ8!TQ&LpIG|_Ioe|`zBa+Fp)W^_t~Ad@b+o{T;e^=4x%xQNjS zC$#ZFS9i02wW``A_V6hhi~U*)-QcI4^&o2vrA@bfa!Vdf?XM~bIn^)0QM7bE!Pfj4f1Gu240Ik)zHTlodF+iwKa2yC-AkJBOG$BKCkD<=WH0%LIKkNii6Kr<-qV6Rgn$N) zLx4n1*!kX03aKfqEv?79%M!#xgUPxH*iCH2YOmg)>uwv>=|_O35~vFvdp1L{N{AP%C7S*K*7CMlHg5dZW_iKJ_hm2Sh}P8!lfne zkRPD`PV2s*>-mYtRc4IL0x(gm8di-%OmO&meq%96Ew74N64QO%MvFoVj=*28;6Qr^ z<^;EI=XygCqavDz$BF;t@>Fz_RdPhmg0g)P=KkQegzk_6nt%A2VXZTL@7v*LNf+7W zgRQKDm>W|pY`J3H9hnRYR-0u9qB7@0? zb9nW&x^QKaQA)9%c;t>}NC)Hb^fK9ZNCs271!Cm#zMR~K2N#~Z+@L?__%do`Y@$e3 zaNM^q8)-Y)L$VqL#UUJ$D0@qCd=vyrxN@sLO~ug1rQ%j!dnIPFSAXv)T`Wi~`;} zYaQF`Qh>b6+KjAo^4F-FIGh>rso*scHIZ?ZM7u-7s0{Bta!gNZ<%T8LAdaphF%C#R zP`Ez>0Lu!g?!lHbTArs|6dhf1x?|)4iusgXTVgyqI=Wr5lmyT6*VlGp&j+EZ*)(ik z?yb2aqD7Go2l-O-Zax!&d0FKB%%;}#(x}W!EGel#*nVigvVXlixe6fh(JG9D5TS2o zIUYy4cOz%P55TxVN3DnCItE%wj8~Fec@}CB_@Ij=)i@aY8%Kg=d;h+?-m6Fd^1m^D z9+8O>>ldhAiVAH54hbXvs1*1$Oyo!*Jbsn(Q=x8)o@2?+GA*{^-A!?)?x)>9@0VoM zOUy>|9N^|dhFy+!teMThO9(S$=!if^+eghp&S|FNMD5XA&kbE(6~=ELMwoDrr}Thf z*HeXwlbOa4%2HpHYxRqkJ;T}-J;T;?fZbYQ@mDA$oBx?_#_@Y7Bmm#AeMX&cOuQqT zt-vY}i>NrRySb}^e^H$9b#{l*{{4&YtsxKxo6})wD9HWs31{b=F?=lY)a7A<#ru{i zaYS+=TlgHA7s1byF3W6E++4=OCI3$Hn*3Bk$%lrpV;?#jF zCW44K<-g`gG|^Yo4XD^Xj2r@^d~Ps82UR*ky>Qm!ET?IvE%qqbMBX4royLiQq53n~ zwR4A*eS6%WV%^zZ3{RLDw=c(3gy@Q%Fuf)M_3s3F&iPV0$}sJYqQ7wn{!1>3TLc;W zs5J?_ML25w5Yc2LiZ4}BdVQ$182cp^hGp~YyV47MUA9`WPB40-9*c1gi~Ud~YOTayXS?E-fAzqgYesN*+UEQYtBtccC(d2{ zR^MIT)d40d**BYQNahHRDY76F%euhd?TB+B?7sAiw=~3m-=1%td8mC=6h@UL%KDDr zMF^d+wHiGE=7obLXTSes!K&}d?{d8mTJvf`SdglX4+;aaWjSA@w-DUTe-icSvxmny zpx1TG6yFw*9KeK2xE7APqnbbMFWDJroZz;9OZHZhuF>`o?z;MNQ6U4J6_LQmH_txd z2o_`yrsf14)5sFAOK&g!d3(b7$k(oH6TL66rdA)i78l!;Ls4GXKlRPD1-(#t{-Y=& zs?^#p@y>BUjbF(nN``43w(!~+P4i?(O!Qbo3Ch%;~bXdRQvOIcZ-1)M>?`0?kk?E`#9uyMhsK%08 z{sRdmSS|D^Px3hUgyYbb4_j~tZ_Vuvk%J7$ax39Uj3I3zPFZ~!z3C(vKH6_TXP~s; z=dA&ZrMX~@zb5@_@+IpI!|&}iy(YIhh`wh8=tr&!t|ZBegS!%&bjW}y;rqsBZ?qGnfrAQ0@)1F9dTPgXhQK#%0VxL)j-L&|f{qnb{6sEb=mrtq>SI+Vd5`4Qi)_V2L z?SybzXjuT|oR1i8AMBSip1~Yw_RaU4FaD6V_-$b&#%nq(zi!O9Dg9n9JtG8WgJD(} zO_yf%w`#3XY(XXK_d!*Df7Z}XFC-?F3TJtfMso?NeQeG<{M9~NDQ!l#ZFBpXJ5~GA zCooOBccnf5*2$1!Yaq7=TxY;Q32L!?<}Brlbz!x!tI#iB=>x{Qs~e`LgE;gZZPJ-g>8WqdY7&9Ap~Hgkfsfe-1*f^f19^vb*(%(vBa2!X|^& zGEMzMLP|@$uVJ}m=l$&};iN_!t)mRh9Jz=_gpWU{@qv?Ze1AfJrMFrMoDc0oG_7ub zwt?{h3Vby%tR7{q|0p(0^5smS}29)u$MFfpA8(ZClql0&%yO`-{kWs#U~OUsXf8@wacne#t1 zzV)x=z49c$5*b2ZOe2l=D3b@je*H4}LCal}@;U9$C?CO_SF8%zDo8<~D|#Mi`*-wV z=%`vt`V2-07y7=P8m*Hk!kQqZu2ycfLqA zQY@n4d7%hx>~MHoDxqE`UBM<&!Vzoip@A<)96QEH{%GQ)Amu4W6k7F0AwhD*euvk5 zDE`<)U9>#j&EC9-Tm`mBdM;JoNi!s15pc2j8%ncWmm4%o?fi!*55qdwG!mdnpjKDC+i24&$P?F~K0?vPDrTBGU#4 zi&7h()M6-caxUg3vA52-oTsVWiIL#%?M{=Z#Yn1Si_GjsvzD_b-jh+ee%86j(|%;6 z>3N^l{79Acn|?&If!@u>qY4Swhc8#;jpq{o0GsO?VG@P86D z0&ioL4$?DHm_HU(mFGh85%rb$Ns16d=Q7Zi&Pj2}-SqY%bJFyD9#sX~;2uTJSE#%d zJsEqmkvP)9^3WBA0-`O9o#V%-i5VFgL(W%1$w^5+Lwkt_;*9$DYeE_=slBgY93gf+ zF9qes?-E<6++A-wMta~UFg_Az_T8HW;|qh(ryW}sF`O0^*5wqf zVKIGg91JZjq|qZik~fc4unz^O*@r_iM~XeKbQQ+;ZA42?s3Z{ON;l+K-3|9mN~xa= zo~{;b;3mrR8|Zo)(M&qk3OQ4xa$YW<4=}e;=-*wa)oVVm4!a4pJ-aEq0N2AB zfR1ZP!*`ihc&6LJ`6Z0WG1nfbihS#%Zp~ye175ba0&ss1O1%=01)z}`g zyd@p~0P{;>G3b&Fb$`*P99G8Sk>kB8UDYN6Eq*K_2O24&nOU;K~NlrKoOcN4_x`wxm!tJX?2ukDc3!)ghO}2A@fAm7(>S1nx z^QGHQ^?|$Ju+J_i{>h?$;U_=vM4=wsAA5h?4hkip*zecvBW8*0DJVxsIO*vnyaHEr z#p`zuXpBLxWxFWYg0&?;B45HKBdm2a-3P`=iA(ETHtf_(8o|fO06Lzndtvg0vbeH* zWQ>Q$YJjg->Y6sA1xNyKLL+(4F7#UfNKdL>Z8F`*@i`e#GtB_JN_`$m;0YvCM6y%@ zkmcW3pC9Xm++O+}Qo~pn#}BPc4%Lkg36hPYX?bN9f`5C`h#0iGVjo7A=$<-?!&2tJ-c?-0p-M==6eLlLOD)P*|2;T&w;Ra^NC5QZSjDR>&9_f2?7XElgyqp_rpD4tX~&vkInG#Q`g=1(+L=Q?t??JCBVP-%KKdh-jaY<^OJ z>_e*{I~d?H@MTBv6vANUAw4RGGPg@NBEpEu5>gA;f&-K_nz5vuN=aaUz_iMFi2~Q=jR`;lHT-pfx+2%JXNchT)<>z8&aKv-fW%q4P z^Yz~0{bi?}_Rc!`OAC09O~B7Ea~b3t5qyFcdQQL$_diI}|Kg$;nSp@*8T{Y4sQ;`? zfPwxGE=tF-%=Evn{|Ejjz(D_ti~8>mKtN_^*pmN?i@NBBbk|w&Ap4M|Kj}^ak^rFr zP(~J!R7j^9uf=vHUXm!`TBWR>KMj$}-Mz~{c{FrRa~+P8$z5=4ePr&fHgvll0M;Wa zs_B%Bu73f|d1Y=L`)xCG>=-aGWBLO@OF7->Y;d<`d0n|pKWEnxBzTVt6CwuifZZXD z{r??UL4$-^mDj(vn1=Kjy)!+2xi9}a*4MfCytf+5Z9hYjzynk77JP*;4iV`1lHyH! z%luWso%SfojIluEan`=L?ai{;uCtZadkiCNP!75e!+wwV+OgOp`BfdK{0ydY#`($p zE4=)enW&mCx5Lb*{P^Me!0N4geC472dv=q(3c`d~$d3+p zIiqWA#5GR)yyfo)PUS8;Pnre&`v(QcOjzZQ4sh%x_~%X==f8dAOL(_Ot;$I^+ZVm= zdeg8#aB*K9O$g&*tYZFnck;Xw z=dHTpa8J&@X&O+(;wtro5K=*qi8+;zWDp=NbF$wU1h*ux-mFpwBrCeFmwp! zN*VGHrsoV#(}l_V(Sa$EoWQDR*$ZHHCU(HQxU>`!FiDgdQyWHO|2wQ{dK)fn}tHdsg^uU*bd9v;9jF8rM|Jne8G#lgyUg0aQo({KSOtLa6 z;)q`g;6~1pnCTXJ`r%5^1!Hl&r1`z3fr!`*SNUMnsQz9LymYljuvTw;xxG`b&mLk6 zZ0P|Tn0op~4ekE|tN;K=Gk}s8mWG+Foz~_-ir<`)V zYME$Qj?C*(n~(!Fy>BdXJXwz9`~GwpFqO#;`F(Z$Ra5eF*z-c>G@TZ_f#wH)P?MH=8BW1IyG0P`0KSh*hp63{qJBE5fzS;i)!qQiazujlm+e$8gCEQXq}oFS!k zcvu7kerLi2Z?mf>W$PYy2ZD}JBtRq(8HDjrH@Ff0WMH1P?f#3rwo_?5U^Td4;Ro1r zNyzJ=_ab@|d&8>}bqOYReaq1{pDi})*u8H{wQ9rrw~+Opv@Jx|*G&Ulba7DkWt8^x+i=`JvXOgeqZ3-LXOxM{}q7?4tr5#ppWIplh#1?uo7Hu7+w z)3wPJ>=&k4#-!l@EA%c%$LQhmSXnafnsJ1WQKvI39t`pThCM#vpDu-)NtKfATp#)1 zZ?>L$ae~(|@h#8WVGP)?&`^mKfwiM>=nPB+7727jmgWU7o#`|gBn_1rry?fjN+kOz$X9`y+i^s49EDSCUvw=|D_-d68py z=H_@*Aa#QV^Z?A&AtTyfg~JG*Mi`CNm@8Er@)>`0n3@S+@v(+#?Vg^Vz7{&SKWzy< zP$*!`Yy5))31(>1i6zJ&+LFyF5${a+z#Pv)UgNrnr_ERGXJm`=t+P%eF6J=F2CxS5 z)?Tvo8VcAG%mv_p!UP=rhx&kQ193yfqkn@AK^FcJ>5te(5XF^A6&iM#B!|Pod2_M{ z|9<%aH}!rkYuo)AG>jk#*AZ+8&ua(nKIV;7A-#0?LyryO8GpY0`gze*63_SR^)dQq zi+fpESfEMK5UehV19i<9X}2OFp)zxiP-uG9?K+IzSe78lQ4Pg~ZlJ)+1@Jyos`=!< zseQVfz{-f>v;{CR21+w%!VbgH1%M5L$pwfABO{^q!|IA~p&!hPyYAdnB2|7}>wiD$ zbI0Lw4upZMN`zLDMf$gA(u+Xr~JJp)KdxRsh@!w@%dy{wl*lWq} z^voDix2ve85|14lPCm@_C5s5rL3@NP<=k~(HzuDqOJq`Ynw7gg>Vt3utbTwV6}E2# z3D=>8FDa6eX-E9QJ2Yw*K1B@7t1)WasP+NxRFDKB~2FYamzAJA%O1rnGcFlMwE6)L51a|ppYuD?sH#6#iIx-5uNXrN!{2x9s^ z4|C#ElEMDRlB#AD=QQF10>|yZKmmu@azGEyPPx$^S%GboulQbGl9I9?IATxVe%(Kr4}Gtbd~w``g~1P8M=&jUfqKGh zbN_`#uz=C)vV!*yyvMnh)r0G0;z+NUmqun^Rn@{*H^1kF1;3XtzZcA!Z$>t*k|Ih0 zN;rdmdxKxWGz1S1k|ZYs*4Lx3`Ey}+a+%ljDs>0Sja)u#MCIr`)VJl(`2ZC8KgR{k z@0i+!OAERo8kSUQ3IKznhcJ2K#RaFcA^@k0GBV!twcB z*>uap_P0J_=nMJ!a<>`}mEubJCS~FUaL@&hY(?z%{+tuEvcQi0srb-|)z8#yxedIm zFNze8MvMQflyx&o(;TH@v+kbb2n0vp~*ue;@1NPl8~Da z2kfu}LhT?>LkXl)(xi-pCmT>RK^CKBqK03yycZ8$pprugCX824rz?g*;{eMb43ufb zaN><(zqB&d_=+%bPyae%~PKyYw%AeDCFKPdzv!-xewy zfp31=&!;Cd#OGA;PkCCl%-D`hs9aun@VdBt-=E>XjhI0frXj>z#1-VKC&c2xs_^p4>iPK6__Uwh9^)Nt z7W3sjUpU@aTV6gAZaaIl|NRLeqbggTTfAvID3x@b#BlLo_|2i=lWX)CA@(L(K127w z9lgc{XY48(IfPd~fo6IeTL%hd3p&5f`1iLfr1tf2G+&^Vo;`5Z=B7I_@|PtBG2aF> zK+!akLNR{?Gg$~J5Ckb0L|H(ppC~!=qhSrDj~AFyO(z%wAO^Mv`kGLTK|C1_kt9s> z1cT(yq=AwrP}C-1Vgw@&)NE}>gZ+*+P#u@W?S_ycIt(9=WPC?pFsKF`ycV58DUH`i zy^wKOo3dTX9`lj0PuhB3R#DNw_xZ4ZUo`h7{qc44K{mVXOEyb(f%?5D8gfIl4P>kP zvATnrC0`yM1)MOrDi1R56TkZo!pekAmE5CH--SYvYD@UZpz&$djV2gf7P__L``%Pl z-%$*qo%CA#monpo87ea6pj4|j`sUmZ`r!NbD`TwPsN z+i!l7>r_gA(lop|55xN}#rZEGw$V?!9~oN5Z|V!}-nfRrnh+{b4(_6G?o}q223+tW zMw%sF2c{)E&1Gpp?rMF^HCwIVUteF7V@PZYFtO+TcX{@9 zzeUTHuih&_Hu=TwFekgPJ=87cD+k)xz!!`6{W0^+^QztZsI5P6OI|-kD{yra{YrO% zBVG3f)fE9oezcV~Sc{3o33vGc7Vm@9_)c-~(k<{(E)n3~H;riM$7hseL225D_Jg|?X5mh7)Whf8j3k-o2 zz!2=A)}Byy=lA`$_v0_Y_mkZ>n-gL@s>Bk!xlmq${x!x*o~mc7SgPv3E>U)Azqp@y zkN9ZB_BH;?3I_+5EHL~M|EQ8#?N{82u|8wQ@^^wrVxL$w@tRzCXMcfO-8zN z*tcS^jv&AZlDVr2j6^t8JBB^z4osD()sJ|;AV3nFDgkPesEyo^@o8qY`VbK#F2(ozEo!C^gNvxwxFgE4J*K$-c}Jepg9kvbrS2V3BtRn zyZbYZ8AhnXiYy8&0}1K%F?7(X)85saJK6Z)nB8H4hX3~%Y`m%)Hs6O|?EW{S6CO8O z-MjNY=zt}}jyIHk&H(7F!e{&xB_{~Uy>yT7{XeI82KP}1$*qDpw=CmPTU;KS+N9z^ z@z;iF1Ysro62;pag6y>=Zg0?sO<)}00wkby(K3cO{^8Epo=HyqO3)%ObL~6e0y39% zOm)VWL`#0r9Yq*q4djen*uFTEMaee=f2K@_81HY)`0mqTs?u-nk8}NUriH7tW}Y_4 zzei@QdW}OiS#LZ#J~y1SmY93Re93h@s>2X2V}1)pU+=!v9N0-wyaK4OXZU>-g=(S{ z?!agFJ7$uubNpmN@bH|=>TsY^{z5f9zw1~XZhsy+A_pzUShX*)^j>|Wzap6jTHJQm zk!+}KP{S)=vvG$KV)tnyE0n-GO@jxBtF@tXPp}DyD}W>sHQ-SS<%cEVo}8b1J%r*s zVeT*sP!)=TTr%ek18;VF<~pIO{f%kV@6y6<3U@teAt&b7^ab=bTncZo$Hv4gWlkND zJJfKs+m;MP5?03A?a?S%$_9Pr_8jz=TFLnm9{%Cw!=nsctC4u>&^i$BVZs8N?)9_)m2WLYigLzby97t_LU zq=u+RXA2)zgswN>-Gh%Gw6|ToCD^tfg#QjcAYLT*s54PQxN~XmNq*LQEJ!%5U?&-c zIC&}&_C1QB7g7o@zxI9Z^o!iz?olBpekwpYh`v5e%fo2oD|k@J;oT^r?sop(D5TKv zWM_FN->AN`aSL)>xP-*miDl}r%`ZJ(PWf*BKqB-~2g38m;{&zYwf(3c5NyX9%A34E zhD8hEd_>}bfS1rV4Pej5n-*R!fG}Z_VdDI_xBD2e`#?q;*KwPRiLn-|fUOtv?H;AA z>?EllsqD-*&%P4BTC=sydOe+&?!7Ab{@VV2KUnE`YW5qst^KV`YPez+{nZwn5KoMY zDXND5K;U>=570fGymWF!ChQ^CBE*9l;e?&(Ug>VWE9q4U|5&KIRfhgUuTB6m)I#_+ z5cLHkNEF3Vbb_O0T6Mz*W(CD=+<|3AOQi*a%gZ5BEFFrOmzXKU$$_d|w;%L_ny76M`sXgA9&zg!usHT89OlKs6KL$LGVvx*WD%ggXC zl7Hb8hZ`DE%OCL3_*rC^)oDgQub$iTA?Fvv!&)zy<5HbKp1-Mn)Wx$m1HMZ2CJKJR zC?e8e5_%#+lLCh*3>z*0Sd(lSVY&+1A1>bGjXn}Gp*kp_V9xq6?G@Tw+}QXS z`tf8I1qfK?M*uyq;3Ch4r@&LGzh~I~7CZ1eOi?ef>-~HpD9mTqwWLY*>5;7aGBIDkBYwhCi443R)cnX@ycuJ7}>%YD@rBq9(6%JnBa zD0)H=1q{7g{zJ>;yA~Y5Ut?5u{pEP_qqh4g;ms(%&1Q;dH` zTp`XXc{;4uI3%YZ;Sf-^mPh{r;ppzr;979H^Bn?Dx?wAJZC$Hm6R&+=!NM#@a&yr( z*+Vh-?O)emA~TZXw!94xhFA^@2JB?m90fE3ArxE|K={e@`&H+)KC-e<7!hxyJ!Z9K zu>57^k{r;g_{Kco8`1A&(4q?S9H=OXT~6`{=rSH_jmM zA&lyPkmuExX^ZR|pCSnsYGLZ{>;0|^Z8i}b0>Dj(Jlu=GnbURk8#bWu5S<<3mnR?b zF9~l_UZFz6609OQpz`rQ?HtJB3caRN8QgV8`|N%42_LYYNu9f=arLI2pPHdw5zzeUHjh7UDla|IpP? zD&>3vg#aLx*aC49olwUsz+q#@ zlYON&G&I=p-A^)Wk>|AsSb-c>rT~!;`&A6ozBuK+Z;-Hj$pa0zSyC_?#ZB`Hy3s$O zD%>rY5j*9>(lg&WgH@;|Z_x+5yzg4^1*`$$(>W(~48JBS!hj+KkN`mJ$|NxQ0USeM zKL(~_JfZ0y5NJt#8X#0DLQrGsD4Wl zpbScB(|68$Y8!qH-xbuKnjq^(j;>c+06ucjNkIdB-;HinS5kHSA!2`cpSRbH;NW*d zsoocSV<2n^Z)o(vUlRfUBbGZkl{OH~MZM3X_H<8-y-xc5M@<3~uR4U^9Jq=1NqV

*Q|$mBR9h=1rvu`PUlXfzhP!!L$L*)Pf)^@C$tXnb0T1ZG2ng;M6DBl25)p-f)X*O9zY(PwOq zKs?rW`mJ$H{=G+PT$Y&tV_C=l60whQDC_{YmRRRGxmQR}h^vN<;?2BwJngT)0GI?n zFHLAp5JNE>k&PQcJV+zSfz@;wNyp-lcuAx|0%fSWY5I^=t57CrYggC{E-$N@gaUx_r0OahP)`UR zsU-Csv?Jzo>K=o@w66-^W~yILtB(i01(Kx4M?KFkEw*--xZ>WApQ`tS)}(dJvxpIi ztR&f^NQjyRg%gJ33E!!4Ap|=&p`Zpfpl;vL2Fu?Ml{_F2Aw*tb${NSJb%|bj{z;{~ z5~8Gt_zTng4*+~XgTHy0rT%7hSFPw-_o_8u=EZDBGV+r!si;2e3n#skwo+&5t2kyb z2E5G_ACcxeKILGi(+Cs0s{y?q#hpQ3xeWd0>1fLfUg&3Flk_rJLa{$OQ zHGrwGHZeQX^p#pD>j$A|J+oJgqlb~U>j^1r9u{jUmLREsI~ASh$iuN$XXZgl2QeSA zA^VUV#Z@Mu2}D+Ql}qrtFG;+jO{8*7>RWRA&9<=e@qTb3BS8A2vi;3{(mWNHTSMz) zy|+Nh!WLPFH5Eo=N=_8}<&*Cw^E92pCCKQH6%WJoHarLt9Fs`@AP7OH#4X6lS7Ay&VX*wC{I&AGCfcPhY|ESY5`ZKyv0)+tGMgp`#W*!0h6{%z z_U6Ay+&d-FQXoiqBV_byK5?n=84rj96l%s7{#J@Nza<4*2BdHcR_meA#$L=+@JfpM z28adrCM@w)fz^P^P2zoSKL|OLgRML8q#hC(D&hO7%?H6UO^=GP`?#0}E=a-QU&zDV z<#L_BOm@fHq$T!#pt}`+Ttz7H7X`uTGz`kIc(=q|@B}sn!+GhZnWZq2 zufx|MKS%iP)1DgXMYf)IygM%;jj(9(!+m|Y6P_`BVmkY#+}+`qbuN=!4??-$T_T;8 zwes3+?~zFDx`f7F!wQZMG3W(?;F8I4q~ij}p#A*Zx>?v)lKUoFOJO33j8 z_R)etb%`2L70H?ZK=oO9t!ckh?tDv(4zwE>U^FA60~R+GgcFlEsa%1P?)vH1=r8R zVEc~-O65Fc{w$u~8ESc(oaRgq`4+%a?6S%4m7pxB&Ao zFashT^$!*>f0_U=9XrGY>KaVr17i1hq*&yK_W;1K!`Z<)RF;61j4V0L1{VJ?UnA>kR0vrke0>@ zsVps&LMP@Yv~T_wBj*HkQ89?6p}-i{EQGfp>4nk!C5+`a;WpemI5eVf}yk%U^nt$L|RZ17&uB$3?6>S=&CPd*pG%v<+!(A z{$#veCSl*#5YBM>+xN7RlYvx_lMRENVmP}`iuyX`rZ@J=`$M~AJv8E5xazlg28V~^6jQr1fASM_FkBIg4FG%IDc%@(?5Vr_jmmc48gDHC7Xh9;6 zt)tKZ3`xX22J%mC8I>|?FT@fm_6%V23t#@OY@9U8Z;rKr#or*cvRRto2%11wJ)APX zHVhKeX&4gkI%Whh3cLCWs3%K2mG<@5=_E?|(`x3$Z*jcY-$_|fU# zNr$v($gP$sqiK*E$1=wBjc^-=oTIn^astUjfJ2%UE;O`p%kq}1MF98}gd(?OtsXS>2=1;sbfW z<`*9L4{4l=$o(VbvK3BGHPDK02yK$`80Sk1>%zGF9afdn5D$9C-^Aqs0J1 zhb7zUM1BSxL;vAkx!AQy?!RZZI33XbtF&RMmB8c)E0urjghY{M%vjzAKLJM-#`Hg8 zY(Mt;>#rB#iBtl>O0LRKy&437y{0!JKii;KeN%MMaEv{>4&3F zHW<;bpDXa}hfD8KMDkt4>bmcUbX}Uor#2j{vcWweHT`{3H0hG^u}P^uACM*wX0Iu; zw8sme4==*(SqAjcT@Z&3J1Cf?IU;+y!?MNilr3?GG^5ov3>75p%2-vV3lZR( z*AS57#oaPp>Jf8E4sGWx*o+`_RBldJO-t8wzt|_OvZkX}*3?%?MOl%UmH)!r`nXy$ zgNGtPCtM^THo@!BXf(WwV|(4Ybqk0Qw`jPo4dp$BrE% zLHG(bVn5jZ5X8=Nus98a6X5KhzEIomhI?;Upi2I~iFH_2*8yLD{i^iOT=QoY;=^|x zaBp<8}& zQ=3HUF})X6V(`zvk8=5$SEaD-tQ6Hx0$I^T?4{)@z!q~E+T?+P4}=Eh9Vs2`mmA(Z zB#%Wt3faC2C~sD6PA7RU)C?;BydZERSW)OdTK9{yJ|;z__<$UT2f<(fGgQ3ODns2P zGJJ7DLeEF#UAwNAom<??(`St&pF# z+BAj8&sBLwK>)guzUwUf%zZ%qD+<9h?OKsjWW}Km5#N-UeNe&;Lo43fFBM(gvf*5p z?0}Qg+PFgfUOzPZSk-r#SdD3T{7;$OVyOffbYOIF1TLW%$+(*h z;;L{<@8~d`rc5%7*aCveY6X`vPbYv2h#-t29bF9Z0`y=77qFXS9ck=-wi-l%D@gzd za)MrS02Jn6^AYF%{ricte~wL={38A-xcYX(UGySOq(^?{J`Yd z-?@GJ_Q~?{vTxx$lD8rM8tnbb*@vt1#tEDG9YzT8{0W%)I-uEp6^n8XBGT_|i~RiB z!44@r^_G0*T#c-UbJK3DMOcNI-U&3J+e;?-6GQw85P~FfpWNUTIp(`G0Z^g4>g_D|gB7=p4@qU`1$kh+O78PC zs~NHe>^{BTmV*3*w;u$c!#E`V%9@1vjVF@}JpT;P&YK*N{g+GYpIm>^u@StWy(*3X zo{%)U;`put^z!8mPpkzD0^pPGsv)^p51k26Et~B>sW}TCl8~4XzTj?lNngQ`9OybL zgJToo@xV_7=&LbUR}_o-RB~E|u*axd5xIwBpE!VH3Kzr)9&0?o;mViGgK%!`BNp>L z-17rT)~Wb&e*NoTr)^JZ{psf)@{UMwstXejRK;9L}cH0Ve<1q5Ae1v zRQkC_WW$9XdDr0{*@(oY^)TjLZi!-uju>3>ALc_cUIl$r^_sa=as;cS9tgC7>`$Bc zN*31dC^pOcj5o?HvIzquVW_;Ecap>DG!BS)OH@j4fQ-)3w~U`biO8|uEP+ivInsJs ze){S@IdJp>Tqh{erWB0tNZ2c$vC}Yg^eIsncYI|A2b?%2P7pVAD>csG)XJ5W#vBc9 zjr{yLHTz?^?%)SL@PXgM?`rz_lQL4{&zyd=|7R*LDEztt74nU#HF6d){SlY|-`0hB z4*JeY>y%M$gJ#?b#yHuGx72T+hH-45ATB4iw2P-4{H#p{Th6VHA+|8Zs#$X-!3<&( zoB+FiJPHE0R%r8Ij^c*$?+E1oP;Ef$Yq<2+a@0Dv4q7ox@GCI3$K)kMMZP$6SdN~= zBt{qJl%mEtL|dk+4|`!Ej76%61H=W~n#=`gB0#9GB;+rX$4dFY3_l5Wz3JKC0rrPV zz%TF_X7eQh2-E2&JUwfL;x%13Au(gy1nm9YSn=fuwEk1z1m4z#A5BgC=tZgUM4=X| z#uTwU-%Q&$oa|(xu3jQeAiqj$l?+Y19E3Tcgk?iku3(imF(Mer*5j0F zO{)Mn-!IJI0ttZT0yMs?P>U}?cLiwTY~^gc-uRwbZH;D&~y!#O1X*8aMT zHo!NZYlN*JI#GlvyUiwD<$dzkulz{P_4LcclsheWs1OWHp9gd0!T60BhzrCC+?+}T zG~`#TwI=KZgbQ>N9PW-LK zVxdlq8bZdpQw}Bzv69eNV8J_(4b9<4}>FBskI!AhCYA<>IP)R?UCsVF2pSl6!1aSjxq(U&+BEXjGZP`CzB{={# zS|dNF7|=&VlfM4?_1ND=y}N#IV_!W%F!*BHIUCQ*Y=;G{pn6CiwXGKqZMbx z3e)uN^KG(a(^|3Hh|@_001Y952u*^v;wCIPR&X2E71$0vK`-tiu274(;#|N=5CHbL z-ZTMFtpA=pd&W&B(?8<6viZ|PiW~qJTF6vl(DLseFOma&F$o;~Cn>)9tQ2mHh`9t2 zWN=OiPr1Z!<}W39c!LD@ZbK;RE_izZ`3hmAEdW7af(eGUk}yyWoOZU$^!B9loXt7Q zBY&LQ2OzR}rx7NGymIIEAtB^zkVr=1YaS4{|9ujkhHSl54uH>L_OIu6R>yC2t}$bQ{9hmnpsDkk#iEa0NvEs0Yh!jTA^=vKbM{YXP_G#o`5F4q$OsKN5hF{Btzuf~wf< z#%ZGzLi67oseyf?6zxgAN#DG(5L5$PFck8C>P8WqE6r`Vd|k6+>!b5%@iWr$*HKu1HJUScws?8<%N6 zGd8_QK60k1Q#yzH#Rd+vp$_9Nr7+8N*guF3>sjKO*;@36z?EOaI)gOLP$8Jg1@N|I zE6WX@bjVLiW_#(Sm+G;2YH^bt?5z{8X9xla z3cLy97%ggj0hq@OMy?VF&jUk9jI~p6iAA(pY#K@)nC0vdv;$Qk7anC?6(bLBA>y%# z>twBjn>NAk9NUt_4fHQXjm`s7H5Nt^j|QOX@=swU5GhKcsFz7N$l;_G0v9Xx#1Ul} z=!37o^q9)eU_dln#Ek^4(};@O=YX;8ZV8ocm1yO!fD*5VP66C2tp^n?kZ*U3=L}$E zjfu5}+!nwLC1D(rlk>GAY3i(#yFy#h5^zmvzL9CXdSw*B%6)hXEd*pGIK(m+`ZpYt zixRDlAb<(qxBQ^X{BnJTV-lMYz6a*!xSa19kP>5IS^}WPFeaTambN2qSgb{RfGced zhXb;u;sTNh0Fj>nST-WC+ynq^Qw=28xsh+RBOTJT-ERLA9HZ%R(lVg`}Qi)0mBs=E}_MEE(iE#m#dfx25zrK&3=+jJi0SjFgrd1cLi02cu$d6O*9Q zL$c#g1w&Lhdobap@`cBHjRlm#*}M2Gc0*DLjp4f{u=H48tHd?{5vp4f6(!x1)1iv@ zM{r5cS*e(+f!puew8)WDU0H4_fvvq5E94rmbe1AG>F%Ze1nGamNUs)!k9!QxEe0zH z9ah5$4k9A%M6E>H?~+*k?IO+4?NVgW1v;2`d9(QU!NnI@gj7LaC}YpKLF$fH$l8%Q z*&@wA>-ocwGru1ka37MD?2}VS{<#sFF)X^F>rb=iGd^VgIc@2YNEs4wz(Y?VSekpU z#3@cz21uh94-89VK~-WL;sersLnJr`b&M7H29P7sZvQ-R=CfzcoIwXDT>xeTg-@9g zW{Dp(AM#7A2#@i*^rn%YB-`=gi!TB-MAkHPR!^5gQ)dT`{vz&K^gi)x_P_5GqZlhC zdh2gVykRrGnjG8`3bOmyM+W3qPX=TU5Um_(J(kP%pWK>ySQYA#?8AKeH3@Infq_?v zA;xY>DxArkr4qmG5%CAVEwX<|Db%Kp@5EXhnXvBDjE3+TyhnRCZz5F z!qVM1B`YMz>=` ze!g*^lz`u~Kt#*bU&+s|)Uk=2DRiQ*o;@Z7&_&(jzg`^3B{;K$*qqlgnJBqa?y=0+ zgGe9tMJ$QO5sTSxRu@1}X>g^C*g4hZ{9`!@0AEVP=f;u5x^2kw=R?HPXK)O8AKBS3 z^G72dbQg)*{K81T03!X4`Ag+BZv~d`0#jZHWgeHQBK=#+XKRr0b;-x`fAWsS70AL= zlKHwDB@kMVHSgNN^APz{UX)9%)H}eGXzn>F+XFSy7%K%J7p{kcpGhwuO+si4gKH=Q z@UwSq3CzuF0(QB(Gc0cmA|)tIsO3;-q!wCGT6RKH4LNnX8q5!7|N5IHYTW?jU!P$4 z=Qt9fgM#>uz7t~Xcu|VBLs!y>H5k#|p3@L%j;@hSr&{H@5E6OE%kXvczfURhF!8-C zMS_M+Z20U$qU|MHi=3@wv< zoUNtvLl7TG*WWlb>}d+ke$!z6Pa(U{L9FE##czdBMPMnFte)nft91&WKv5z*0d{q4 z9cD$${H2_F$hqZOPzgG!7gVbMLcKbRFb>XvCwC`;CXKvi;P0d8qpqS&Q$ZX)|5H3J`GP@yKgn{ozmx z0zm(O>;#Q47{a|njtQ}~VK6SH3(_@W+0H>^fXP(C9@ z;Nvs6!!IE&kpK|4G@fyP*(Ezv7gxP**zD|&#|@7>^2i6Vx5gpc(%#Q3KcsY-N(k9~ z4?y#O4!Qj?j1;+3{G%cmS)iAx!WBHv)`X|yGXAtr!W$ok%zGn_6Y?o%`RKC!om0-Z% z7rR0BzVeKOdkdwDA;ILdbXqW0Kv{^9f^9d$#{w2yjz8s7!S0?Z`VedMsrB}r|ArLS z?32>>VP#%a=Q)Q|SclB=nV)`0?(}SxZShvLl4Cl383g)2FNms>ZV-uL5CE*cy8s73 z=I{ude~#HY#oh|FDd)|rTw<6UB3Pg_*bQZ7RfW9XvIFrP10cQW2{e`BA?Csex+P{b zTZuc5KKkg(_zZpx{Q~$PsWc(JEXc6j1YpkWKV$m)1R4v4n+Liko#T()HNQllk#}PW z@0Y#h(gzE`>|Mx%$5mgIT&@S({Kv2C8Gt`L7L~vV^AO%GvC8cU6IiMoovBqselF2< z@ZZI0eO1iPi(=YxUN)RAl|3WtFzgxlyD-~J#}~%E?}M(Ktn)U3_C3e3!TM|BCG!5s z_0ot{aliM%6EeE%-4d<<7sE9H^|ui4M0##4N>PdNh!ka9m=h))_(Q-_GS(@^(6AIW zy&{g<0r*5jWqMysHk@pd>rZWvyFJ^a88d$Z`O|eIh$&|N|%7Uw5`LqCQ|uo#V_E`SyR;@B)|;P|r2au5LaBsVrp697m) zVuSLp5&JFJ@KGQDF#j^6KC45ywG$8|5mV{KTF{$AFMH^>bb`dDTXz$7@c zmxSk=Uyfr%TQf|V&EeXd2>|OSa^2xuCzX*QIrQd>5-n>IR|pDC23paHM)^o!m?-Lt zwy>i@KzQ_}arg)ld5&Xlg44wW#FwFCNRf>twcp(X_f}-!^&>~)TL#&5wpAYJzDc&m zn=zG9lb^m5iO2&W0Vj<;@{0L{d?b9gY=9Y*&txmi`#%K&)&-)|Q$H+~1sFT&Uy-ev z%OZWm0000$07*naRJ#Va#GvGid5sVWjp9RmgMY9VZt9pA?)WtstKJ}fOPvgb2gLyn zvCst0kDi$G3Pegc$kCK)E3Dl@9KuS&oc##|?lqoiB9N|r9-P`#+As+v%&7vw=#i$7T^PWq(~fm|e&La2zg-6Z)wY z-}^ebnhg+T^F2_8kzLQRar`uR${9Vq@U?kPiZ{W#vCbrYKlDrKXenGJ+tJ&ZS>)so zqw?>pX;6A@z6X8?LsES5oO~pR_T*TIjI;=pBfrA`9;lQbJ+W7gl)o%L-dQD~Ew{m* z4;o(Eis1+9M5_QJHc!4R#?eDkYWq7R+6XJZf0G4LIQ$pl;TW8Mf>Qc&g{(W;D4(4C z6={z&N<+LN>o*bkxj@OcjlYm1l^x>TV3b`4*TYhPB$^9+3pt?k#(oKJ4T||X+?+IY z7I<{oF4Mx{JrNP_`AV5Swo#%t|7Yk))`{HH4zUpa6yTo17~^la){56@ms+}wr{&Z@ z0DJ>z7vNd84psx(M}SLTJ$v>n2>|hxIJRtJz;X}(f}4HBjg8~TwSVxj$HuUSO^l|$ z0P>+B>JMwCWt#oDa_{M22^RD$PiX#e=WKyY8mC`6Xdd-USD}Arn=*TVb}*m4IS7ts zxC4j+4LZFF>F-UN%!ZORRx$PHFS5#-U7i|6_J}iL^q&=Hix&<>F){hfvibO0SwBz* zx7ZQ@bD?3MXvw6w<(TQB_}Xq09|-K3X}65_1f>inI5?lqHaFV=-{nBJHNtiJ-GO%5 zGLF@PkHw^W@VrbEbjZP~r)9dbPJ)HtL_=7Jr1Lps3qCET>o8Nn0umm^+6>6(v$n5V zDqKafd8`>W{#t37sF&@bW_(RiR^(^f#-PMJYU+}sH=mb_b|}IC)&@f*^dMMNV}Txr zH@%!NT$D&vP;Av#cyyqfBXCvsb(zG~bGw9$FpuuqBk?u6V2OYdm+>ewq7?b}7X!r- z#O%KZ>sJ(-k#ao^H&10b^<+#Mg0%%72QK~3KmD)&wGxkmZBXVjjc;nC;oOqTIrvW`lqsU5cZ3hC=VCu4&_X@IPm zD*<3#aC3s#fpz#~y==rcZR{SGW8Gay8$K?RWhZ5DO^dk7;LO71$Hw;}aHR*Xwhl2& z;PW7z1`!NYceGYoCu`-w_|4En)IoZ$M2(yiQu>oGOe*yF8!}GHTaL5Ry%TzWSVT<6 ztV#*W#Z9smYX3d({Xb*rlMtPM&?i@{0R5r}k_t~ET>V0!xP7-utmZ~=gtsLuS6XbE zX%O|;N5Xa~4Lemjd#5o7IBHJ*QmctGQ7Fv0ES}j~?ELZ{{n70p0OxTBCszWLAE|-L zJqf{*%H+wY>r{-D6)B*AHJrC@dOBhZwGN50j4BHX@dK zk60>#V3TnPlL0fyTH2#xE=D#gAC(uS8{l<0A?P>qS}yqk_U%`igJpCAl{-$PTk%A`9a zE>ln@;%@k9l%tQ({(b}QwTT^Gn-n2xV7YN3ZXvPkD3=^v82Kr`ACeAvq5h!!$WKCX|8HJ5e&vQ@Zt| z_%|eW39mmNGNF*Q#GK%eAZJFv3A|AGtXPmBWwWQ3$z`;QM{*e^6hIF-Km5%|*q`QM{8|EaezzCYS1!A_Gnno$owSHC^=-YfYVZQwfc z&Ni(0(g@amhMOaj>(~T!plD-K!*tvE9rzr}fJN+GL^4{v6G)eIciKa80CbWWD*)Hg zxCzjPjtH9j80`3mD|~`<^)lu4D#Xmin=tK5W=0Nql2lC04gXqzT3@dcO4Rd1xg<>@pG5zOHed;a{ zfHQcz!ZGZrQqV8sUUvx&b1#=mF8N|^ngg(I+qTUM_WxaMPc-aPioa;oi;tKu>#&*L zD6;$_59tbC(PU$|8QLsf`I!?!N!bNR*mn`){g~-pa*JowF>@OUF!U-OToOxifi$m!& za_{4^f5&F|p79kp$HM$NU#ME>6$@V1pR?eNX>MS9&copMvyy%C`5oU7_-FyK2a%Ko1&NGP?s{ix}v17X@NAX8T`^N+tXEUv?FRNMWlBG=so*t63Km4(YR ztN|w@NFa*UtcM}yWGql5hkRqOx=x{M4fhhaa4%k@W)$Mw<#dC3?d1>v{c?@`9P-v( zyLM64|0ruG`x2+)1CTWnZ0Pno37N=^ynj%K@v-@Zlog9B#wxbLYZh`TQch9NwyFx7 zuDe9<7ib`vqR?;*K{+s)f&I7OF9QVT)THd*NO|2^S1LnQ5E<;y&T9Ze2^pod4T0zh1&9IQuLF2g46YcfMP?d|hU@_BAr{S5P%%tuabL3v@f@o)bgIYajw31dQp(!0D!b2h!R|CswuMmbt){7}0?= zp96l*um6L>EfRoaJwRq4Wv+Pk3Mt7_3Mr1>*Z@TUYHDgih-LmzqC#{yWPh%Ll8rJR zhuxpsf-C$`yS`?dcz@Y0k)d-^xMNtXW)OiZ*y)MyTAu$<@``cXBx|2-kaa^1LalqY z887**Q}FsfXu2qY^>;!3Ux!QVisXXd$VU*|Qzm~Ogez{(h>Y%iS>6-f0pnZ+^a30| zSFRvel8RG!8L2v+YJEdq-gs0@4~C?;94bW2+-!ct3!>g*kXs^~kouz;r*JY$@q?T& zQHXtWTuR%)Iq~-Fk7TKB@t2t3#9RW?r|DT_M0!&upL|K8J3k8I+m7HV%z;WI$Xst2 z9KiF;bzz9YYzjDF50&t|2cp4oi6D6mBWbNh>#qREzCAoVoJ;`pmvcYAf_XL0J+V{* zz*_W+X9+-ET^-r~d)baS8ce&tO7}hYo$43!{e|)2r(qL41MNRQKWpI(hZI$@;x^tuf-DeAWClBD%+;kNmaN6l0Vu1g};Tf=%~pn`(XO=S3o(+y#8wR zr$E61=P5)`PHfsHoh5_vg71_V&v(f>?|^KJwSWv1;f+)eF8t1vnsffiS$`TVe=n>R z9p*v##pVNYcFRTawtJ+s0sIbSb`o$5+c1=B!TzW;Ml02-$Jt)OQO;x`XF&jBRm}W@ zdM;}o%=WhQ*Qn!RvQv8#EIk&Cbw5Os$j{&ubsjMQNRG00s~WF~(D3=0c za5_>br6!M<)0hO+>OoKhGJ@7*HNG1-_V*wFurn&i@vGT^OYX#_5&->DHh>%JvHrzh z`~?ZXu7vYXQ0V|Nng7TFd0}2U8ga-85P+OW7d---u7}Tj2(t6bVk<|wu4|D1aKMiv z^UI)FZVzu!VZXV|{zNDa{9da^eo-|hJ`w=tN=RGKMYIecif^=TLjE1eO8b4^la2ju z`Ay^j*d8%RF>Lm9IZnKL`A7jxg!~IZtJ7s3lGjYf<(1;&^45LFuux}Q%GZF{!33H- zY#CMQyI_>Ma8(WjfNsM+IbZ^^Rbkn$3Jk#|qd;2V<#duF2RQ*tMO18ShQ)pGI|%-1 z5_j*-60&-yb`5YI=y9blt6qdCgLE5zfC-O|Dvj*Tk<_%=_Y?H;Y?N9#X zPht-~_#njq;+)1mjgL8@5uTeZOCGo|iio2LJ^_d|&%FY^c@-3VuOfVu|c}Wv#45 zEJ(Jc!4h1BPdW>R<@;M-mAX2MSc|U?0nqT^_gLVMQF5DA3O!>|I{b`Gyz)y4nRZFA z?zdnixF^94r14Sk!}4|BUn_O?QE|Z0DqV?#07S5Ymc>yi?|ILAh+`M95$A||Bmx?m zI9yy=3IX8D^v0L75f;cM@Zw;~ZxR5|e=LQ})Zdv(7|A_`U<+k{#G(o^?#AsU5*{&1 zjBm`DdMxTKD|a)nB<71t?O?ey_96@?R*X3~w{D;;-HEgp{m8l-tGy0TUjX^_S8(9L zojO!mi^xU0_>ht57|c+kNI5<+8j+^K15yz%sK~o2<%wWbHh)Ip(VLI|sgTo7Idnnh z9}|zzIfyeoXXF7mzNs+5S zHU%2RffVT3lz)6LlZ8y!;potU2oeXJf6|FS`rEI>eg+#<3NXs@Z~`mbfb^u^b4VZm ztON(j5!lnJ9NJQw6TtXCA1sucvf%;nC`x<+UYRYXUBI=INqPW{i+aB(jL2=|rM5af z0iccYZgnetnYr*GoPaWwAk2QRM_89^|8k)WEGl^(NO+9kn*@Ota^$XAb$yE|bnAn3GoP|!eTrX$F`s9@(zmURx zFG%&oq}&(3LAJ-CABY!ACAQLNq1fV>)exs_ML(G^NR6n6dWZ-Hx+m_JX=4bh@CFex zFePusPDw8Uc@Atp0?{KPc0}|Qt_9LtKsxw|Y5Iwop}0Uu>2#6Y5Z|EOkki~Y`z0hk zG;0pqC!}N(#Fs1R{4?8#EC=*uFqRvn^fm(!zYj4D-o!UcHY1a~x0 zC=WB+RfeM0(0~ZQH7a0Ty9Wf|>&vAFSS0qT7P5c1vBlgJ2k`jgkHZFnPR0EZlfH{tTKu^3zt4o>maSih4kQk=>_fO1KQiW)gnHS~p^5vWgdrn!Hha zKn_kJrr!&PB8Uf(0a)9i)rpUzn^T<}D^ioSAr68XiEM@Dzhg6*e;m!=Os=5w zPquc=UYq$&ri-`LgBTzcnD6`FmY@Z}J%K$C1(JL=@DNmpas)|mM&S!n2c@~wM7DNr zp-3GKPb-ny6p!rq*vCE`{_JOuC0hcBhZ@RPg#)1bZ;NU+?EePzYC`@`AEyuj@>BNd ziE4-Gw48y>Ph^BHao)%bLqiVaD=Wgz}G$2XOwbpF`Qk? z(fzr7KV#k}jeZ%au8^q;DE{dArxAK7pT_JyR8GNr&{T_76vo8W46ngSaBmFp#X5h1 z5)3>L04}Z)I*qw^6zYUx8!`rg2e5;c!4mD^f(;TYLqE5IAeCTUhJZz?AYRb*+W;g` zCDSKzr~)320lO4V6hQVb1UxvF(-*S;OnTZ~Fe1GrWAM7fy=f9`rhobhpT##bd%V$! zk7UA>5Ex|Ty~dBe1Q0lbiVK{T7m08g6z2c|xO7#w88;!OhJ=8V>woz#pKbZ8i#761wl3027K~6 z81!<=JPd`}9kBhcK@Sl0msyyv0BOBUZ2_!wWKhXFnZR?laQY^mV{O3Ue+XhB5D_Z(~cfom$9W;q&8WDRCDWqw$#HM>;6aN>44Tr?m1T(EB0<)D~IslD8KoN8g zd)G?aP!oIQiBYp+Ef8N5q2`kQ9tT@BLAt!L8DQ^sC-&U#z|4XsGW4FYhvh3g!S zUlh~nABxRBF4hWmWl8}^NyFn&a4n6yC3eF{#dqruWFq`OWc0#s!V-fi$om??fqx=~ zsosQ6qGXMPw|rcJ#+$`^Is#Yllsc1s(smw4Nbx<9ZL&jJvm!qqqZ{!#Q@>a@aoI0S zuM2}N>1|i=5HO=&!*#Ss27d(i^;>>V;yWMC%C!x{C3qAY80fS`nbyHY#JEMHO*1%0 z0>F;b_{e7$1(n4T0Q~~}LOyTy`FzCqyLeH}{)}Maj|{~NR)^b?3r$-HdWpsn7!<4m zw}EB==&QX1kvS#;>qUF8NlIg6cNgv}vb{bqzJplytfRsrks`>DOI>tC1Bjyx>kk;* zU1BZj1^0wG2wZ!nq8K^G8=}^-TyZY(IQaN_RHmt)}mB==;(1V$-vjdPW%y9A-Vi|rxD()E( zYc*JPthSuB&=niG?bPBS8*tnj>oQ&B{9hR=#LhiV}Vl>_}Vw}FIk909~{na@Z77H10_a8_NxH_^l!>^I8j zb1gDGe2>K5{du@$w*PWvX7N zomlmlY02aW7VI!RA&zRKBx?sPyTWPfQVECIFHBFfa7&M_X7 zEBrSMggwe9Kl#aWEF8igq=cFP@Y146qP9gnGKbPABCux78fE@t567@FOgxMEkDU5+ z)QpvXEwkfcaj#FhyQm6`hF3zzkW!%nqlyD;m5mFwmTVz)6m=8jvSF$o!8pvEv+xYY zfltNPIrE5&6}DjEk-7xulLUg?4vBH#!zTtHt9OaTzfbJ--AF|~i7;HarTgs63+i2#{TO|eG!}MU(MFmEx5b6te_1bMfe)Lz4&RXM9lZ*o|=obSI7Yt)m zno?p2A2mR{Wx@)GiMV;{%2RZ;h#A64RrZ>XRVr~H$MB4Qj zoUTZ4O(r98?j$yLfaU<$n>qI=?o|(RpG(md>z613uyf~5k|Y?WQP9sZWHOD1rqs{W zf3OmZ4=p1V>-pTpFbrQJ}FItcUboBFK!3k}egWVx!zEIN z2cT>ZSI^*HDgof5x%O<1Bk@veSTQ%YP!Rwu{sEE%CoWZB)`8t85d**xGq*4VI2gln z-*g1Zy^V7#N&cl+QONyG&`blheCG;4fY7{@i7NS#D}5Xff?B%}_uq$n|32pYbLRZz zOn7k-X}JRp>m>?h=i+&F{k4Dz)+-=kj)%$i=ioEJ?jv^(@*W<7V;8tK723+)&!rFn z7{?y3MjeP<;3z?zia^6MP})^26+@8{TDWMNVqIs;JvNM90a(iokB;?g#Qdzt_cANgRW zhtpQchn8CSB2!042fJ2<0Mk}UO921UwSylRLI`RA?!U;Uzts26eU8y^?YAKod#6mj z4n>&@GY^1i82FrdEMUD{8AhDJ;Z5h|!iIh^(vx}oZ8;^zV{K`xOO+#J>&pX96BGYd$KO|CI(P0Z_vfKUF$@Sq@j0g@R4yp8oOP_U^2E}k4BH<|YE@s50uX0(= zGA(#;*d&u@?-Y;cU0BZf&P1S9t^_hoD<}d?!qYDk0pKGs%x*NZ!!5XE2KO`o^`5}Y z4A7MKE(M&raz1N%=%I%|>i>WC-UH08>$>keVFoPL%fFy`Uuz}T-M9~%{S;e+2 zM=p7eBPIEsm3)?yJSSfg`8~flmfwpl*VvL3OOa%oR-sH$g%le|00apF1V8`;FaW0a zK6Cr~{m-2i#kFZi6Z?20jo<^IF^6;G>f$onRnQRaG&k1E<>G$z;p!y zr6upsq*R2Ua#)GtEf(%CCIlCh0PM+Pc1hGhdHYElW?xS*fng;+_VJ4!{OPq!B=$jrnh5qT0#)v-F{bXJq`-Py7c@B{?BhBDYvr z&8i;UGBs5GjydA5V(o)^k&@TJ==e#fs^axYeF^&3)D#7cl)tw0E9jhmn* z9<_L1#L6#y)y7ZHTJX)FZHctlTGF88D#D*~{e9N^22Mwiy^1HWnnf>A(cT3eckf)t z{%7`L%qC71S>n#0!5FPQ)j!#9&+CdPEn}^AXYAIz6Lg6DSJdDAIK7@P+h^9a>8e+jRHNx5?-H#E3bw?`Xm{^FF0>9f+LIU;cAzMi=_Wb{{=Cjqd z>0+zZ$0||(p(@N$Qf$z)ohgmlOAT0#zS3a9zA1u;4r2s_((p=WuHFatBe(1raTz3& z&}!}@qK^-UGUa>B2|`S7#V`nW*OCdi&62mTP044ne8);oYk{1_9w0Xbkb1xB1@;=) zjj*}!sM9MdEA7Vg7desf^VG)d6?hd}^MGu0&fUIVG6?pnSvDXDkFP8LmCzpUrVB>dB}t56(P z35&b-ofanLdSs%+Vtp4Z9*QEc$1E4Gzv<~cXdEzNS$|JT?r=4%hudVnAz8D*X7*QE zb!Vw<9cZyKjDJEo2vBw7IC7AFfbv3PJ;_t?g6r?M;+|pDfFLZ5?G<#3lCdPw6om<_ z8y!RCHXFoGAHbi+x{!R0UOyiC^o1vfX|#ly@kwG*j6lHg9 z>;Ny{Ce)Z>qWylqU=IV2`JT`OTYi#Vt}Mq0q}??4)2-NjiF@3n>rT*u__Tg3eRA%M zFxw1?Bv+jRQ2konis4yf`-m`m2p85nG;F(2G@@z=~hd%|jVeV5pUNh@d*Yn`QN ziYx55WHXX;EQ<1z<*8*)D>lXeaWa(hLY9CjFkkeTWNoNt(h0kg7u{TgBa{ju!mY2T9eD@xvC}d4&feRoCBXF~U+sdQU(u(nPiL zS{1%kq@*O~Q8N5Qhgd<+@QveD7Mw1$`%YBZRwDn@K^4&$aav$xyPA5nTRjF(_c*FBiNHLk*~~8U*i98wMD@}W(W-;2kWkS{)snhulJaDM@@{`@vgsPEWl87{H~wh2DFHX-Rhh$)XE zlh+~dl${HZ45A9cs*siQS{AMFn*7?XWudb?I3kr#Op`|3>qP#^g%H&b1Rb+;g;Um3 zLWfJjUI6QoXvWy)UJG|Vhn{klup_mtO;( zrAg#S;RARuj!%KiyAUQbR~JuLy@PYUV&eD{l_)#|3myRYR{;Sy3nU+rdx4}soa{rI zhz{)Ohg#)+y}Q@-Wy?wtfGTufroGTm{&mc^eMN25JM$|-0IU|_6LpxH5@~iPaqL!O zZmWygw1`Q?sA$CDegZxmfSeqzv6;nX9wM<#mauoZUo*h3v-)`Yq%zarIN z#Euf~>YMfFZMLbE$(ir7`Mu$W-8D05g@e8J_=zdoHAy(MWDzj57_u(6PGP^geG~TV zt&Mhm;~GmU_kqZ4xqolC*QR2>Y17@W+r;Ppz-rzzZiQ>(R?v<%LsjOQT3nMGv0RG^ zp8BsAZfLcHB*rpu67?u#@bD*WrVIDz7YBy?g~ArZz4&N||4j z*I7-Hk{XMb5|6#$r^vkftcB{MU~10m)hjI0i7RAvbbu(hiIC5Cuu1`}PHy<5m7PCkwWm(mhWNvd>2E%-#azfPVflBVuF@{ucDKbbZgM7N zJ`dmQ_e>CR2w~$L~;3n-QyN zv61fY+sydeRuwp6A!OpYLXbIC@ah1vq00MlF~0CD*`|?OJ@|>#3N9po#v(R;zfF(y zU|RkoD`+NQX$F;Yuoin0938yh_yXzcqFB5?))W zHuCEp8UJ*9hHap{&?Z~jK&w|bnVj}q%^!!{fzQ!i+8qIhD6Cu)+~G^-?pK5$ZE@BJ z$Z22y1#3&x67{bnCoUF`JBcFnB9VWhHCyRtR^{|3w9M-qY(WwY^z0BCpRs_2FTM$2 zqe<6tlw*oXd*CfhTJc7|OPMr_UV-PkUkJ`!%`rNcxTLZ|$AxGC!I+ zn=b;;-EPJ1Zx4nDdcjKS;C2xW%eG7Jxbo7x34u|_2LJA>R!J^Ae-%M5C8J6If-JR* zw~t}1HvAMeXyZ*bIr||<`#X^>G+J^~3o8ZWsLMAm28ak5aC*+$BZKvJ$C%&B@q18W zjpd4ZLuBtkgkI+>cbm0?Sn>!Wv0S}Zew`NKdTP_7(4;fy;}CRJvb>5Em$oHS5uymQ zni6fu#s`Q50zf$1Ff7pl^PM_r>tjFb1pdgy|H}pXqV?O8oI4Z1P#<-cv**?zO%bpyKxaY$~6hX#N(EJXVi` zPhCPDZ~(UNO)Dk_p`!e{Me+arL_w~6@T|>DR@lgi7tD5JJ8_k=0O$&)sU~V3lNGcq z7(96J;Nl1JdRX7GLf~~if4=g%I#$Be+Ui_b_76{bJWQ1N8kT+H%5G5diz-Z5_x!p| z&OBlE!>6tCVfeY_yx=s4FU4&9b&rh|e#YWeNT3_`r6!sJJ17|GJX4tABc{o9e`>#N zo+z}P$#sCf$d2X96yV=WMxDQ17q|1RU@8QeS8G4XF)0PZn>9jeDJoU}mlRTe-}Tr~oO#R>8? zAkM?FVBHK!KZuW4pD4u^GCRj88;F<5`TJ}W#y@)>wds21mxO=Wil`A-uOwNLV%vVv zW(NL(xpm2kx8yOcd9+|H-CQ(o1&6+dUBq_$BRC;*XMG#NJdzLmZ#LDn(IN+bU{y2E zTVX4?4jPd)s6G47thOJd4|Mcc15DE4@uCGsYRt#JF?> zcTIBRO-x|zra%fgD&tGylSFkPR8?&AE_@3%q8?fY(C2z+u0BWyFDqbiUyoIV8_2$k zCLm8tCwupC;=y-T7ui@DlOaR+=p3!S!b^;S$nyxRHW7V2(*q;~Ic?s_ldRl5{C?9y zl^_5jE(LTEO?VmEAFJq5Dv)0Tcn*-b3bkd>|wyd-+5!ymCJ= z{$9kTnD0UY9whTk5MsawjtoA)imzt^#VIzJXQVM1eIabE(K@>e^Wtn-eqR2~+e zgF*McTo1bUEZAp(h6VTJI#3r!bpy@fFDs?aWT6S9;S4wkV8!j!D^^}4xT;=@Oa;e{ z18W^8p-}S_f+E_g<}NO@JBcYKUMDFsPzE0PHkEjLr9(q@=X49Y{}OnsJg5dLSM?`} z`G1JWKhgR}Qb=cUyH@j9f;rNu*|F!$H*?yG3!k&XU2mbv9wXO1Cc(v^ExJv8m?AzXI#O&6-PP7c67;3=5CD+La+-X? z2YjdOYsH7Gr|~CkwyrS+{HaO4{MU=(D=fD}%l#IO5LWBV*R5z1#@7I7t`a47f0%S; z$&C+y;Sl65rZ)8Lio(P~kl6Hyg-3`!H4eM+;wuDHy<`RTL&R2O!ZS@mO$jThJ7}{$ zgvPyl9Ve)qavTjj>QO(g&gFMZqjl)A!1-2)kb8;!$Te9xW|(_QgzCfa!IQE+6zmD& zuDH?H4$^F z9F{2kNsOqN3lpAcI}y5IuN1yz&r}@2>+k(QljvXuBj2KX`M|Q66JM?KfkH)}P60`E#&YQh-#sUP4RocAdu3Lfq%=17~G8Gxv`7rng z2L|W9XuiW1AJ1P{{38<>EWRhxvHJqG!eIdf{9eevj2}E#gQi!x9|2J&)RyTjt8q?L z0C5B5wmB0H+vt8$i9HZX<&{gXpYia)+xY?)EjWdR*VMmY;1LEXAx5S_oPUK{yJj}fBSIXS`Kc0ir2T#N?Z5&1;=7)* ziA@vMy3KFhU;Q6MAG&DqmRpgqfe@WV#eFKrUMphz4vY2_*x)xGvQXP07SRa{R&xIG zYf}}deRu$lAFQ*nsdrnxW?+NqAPFl(RJyx_HVO9lx znZXPIa+R;t1c=~j>pe>lp(rd-Qd05Mcg;XB%He6h_qd&{>9*%~zHT%3z?L-)OysOhoIVI3Jpe+?3 zUlIJjX|=wBvDF;)liR&yD>9msuaWeE0H@7czzT&~2gK2rL-Oq%3fkUL%tKLgWs`I- z{7S|AkJ>43w@t_+jliEvc+iCpto%syqWJyMPV-?u9|}K#d%;Dl;0ou2Wcuh;F1*s= z|H%mCJrl6Dm~#HG+VKyxYJI*Dyd4MZ$&v$hvAxIMdhnc;>_9wN$RL1kOKw5H(A8yA zr(Se~Zw?Kw{&xW$e`nrCLs3Pfqhf@; z&iJmNFWmR&T>@}4K*=a8zY?#6r|{74GJD|*ARe?%TXqvr^&ve_$N`HLaDFAhg1`Pw7Wb(aw^q5h{*LL*Tst5qcIo26~f{!a@ej#)+R-&@%|AiU~1;CBIHwch8}!{8@IleXq$ zoo#rb-P)t|aI=N1`LlMw&e#*RFWNJ$uUq`XgetGYYL%g1ra8W@XI>2?&^3ai@-a5H_UQO1cSn(kuaH>VxGC815^uq5a#4-%s7J z4SBN}?l&&p3z$WHXwy6+eOGX+$BJ79tm-{45LESfo9WzZlU*M(yXV7>&fmGO^;Uw$ zkVfopwp+=@<7E9M50n?3h$DMi{1W#VLux;o7Wg*79%uDonZPa6Ik%Ge{guo(RqSpg z0*YNqApj)7B9DZk95f{~u&@X<6oCNzj-X9dqy}Z-UDxnP)^*-eRD63aR$fl>#&R2a zHy6OtfSl2D&(G%}4X>$szr@!IKerp0L3(&>GR#Ng5!l_OxB?Wj8)s+JX z`8Dy1-YrW?g%xWg2f|&^tpGkDy$S4fB6!iB-+hG0zMU3XM`WM%sDsfUEC{?oy97&O z!^(CdVC(z=HcF>#_QjVi-uejS0Xj$G0yrkS0<>%ezB}2r2Nhq$Cg1#l1*Zlow|fDR-?FMCxIczDpvK7#fpwY9K2;EEGWL-(-uGfHJiP#mdI7S zSCoU|E>sc8`p#dnnb_-Ssb*~hIUoy)uwlu81iWG&c%NX8rn~DcUzZUPD1>H_eYz zRifini?FyPD=9FGmD}HAk&8|E zt&CXP`Uwk33zD%UnSL5TEi)b)AD1a1?k1NPWEU4KM3>Kb9T&LDDARWAA8JV^(~N(v}ZMnppXbZ{{E+|xc|Rd^&>I9feE7# zQ~zJXl0dQ^@5inAPdrw2zTC0O`%k;RWcwd|!v=n?-$Hwkzu;Nttj4*9o_4B>165w! ze4z$*&0>Iqd+zuTE&j~6Eir^D6RX5j;!RPV89q!gB5^y8b`d?O=z=9@M=d((vC-4_ z*yO}}i8Az|Ikqmtvsc?kY7ZKN#Q3;HeuQ@DHlKy+y;jr)Uw`g7^Y#}Q#86$RL104Ix!2Mq2d3v*HR7S`B+J^%dkzx(Ace_1Lg1P_o}DS^D! zRhKH@XYR5R1fZVMuxTpkInCGt$p7&Ve(;08&Tk6*)l?s_p#-4_b21c}0K7i6#s}+d(P7c!U5p1~qMJk!q$2|7H}9i6JiYrZcCm-mAK_o< zy%uYHgb30bQqNtBKGC~H3B(W%PT-B|Imfz3hU9Aa_hRe?DgkhWp^1x^EZKJv%|X4D z6qVS9qKN%e`32ZyViT(23yM~MQE`RHIX5`e_Gdr)+24EPjW>h<&^bB?K)^4-VBQFT zR<5|XEz?U9-~H})HS2L3GYp^w8(3DcWh$D3em<-cRbUksWkjRQbldekC%J{lFi5hf zwvIP!_BcG)be9FIrmU0@;{{EaZ5EKC>f{eBQGpw3qRrt)L*3`Cw7ZAwc6)OMxJ>^b znZ1sCrtB^X2a_gWV=-Bv8SzfuIC7dbE9ym_;r_z>H>#Fuy=QM?K;se#aBTvWhg))ttt{@}Dd z6Dby3c5@W9w`vW@07_uvUYqEB%shkVZ0xJwvZ}k@u)^k1YijtG4ZrjP(Wu%8RPh13 z|JBoWS2r;vz9^DR*KM+y?L-g~3Ama?eLmQUY3`r}Mf%Im;X0LIog9F? zR&rYqSqh6m8A3GP+!qTA2u8@E85Uu1J8a2ss2ujBz_xB$`*iL!h^XY zp)bi|A}zm&VD2ZFn|=&+9!Qbg^N7N|`5NqTp-ygp)Fw|6@BhLN2@?CaR{h=?3qtu9 zuOoc@$4LLu^QQHE_kXvx%FkI_aibM`Sp73X1&&KW=2?h!Hr4h+g1!EJLQ`E{@mCB^ zD?tFNeDM~ao+kL6Va^Q#&`A4a`~d%-ZPej{tj0gEUI+b7#>XG8%mg_V~t>O6V=z3e$|ebq$eMJ2g#+1|x)uF74^@KXSB>3T^t#1|a{|Fc>)n?QGE322;LVf7p__j4u*EU(DBC$= z#qhJi!7+;+Ibdt!o2?Dy-`s#K`#B1BIST?f;p?{1QkF6&f=qtMW7*2x8$8XzI}03FVe%J29Rxp2<(v{1iK9*7?kE|anWjt5m;(A^80!LzuOMU znFwDd)nKBc%_d)Bjlp%g0H1-vb{N9AK7`B@9PEud zhnK-ku$gyRDFRT%dVw|}0QER@7OGwq^>3gM7C^wA`Ac-R67^SA04eCrUS!9OCs^{4 zPg;2JtaX0-udTf0`&iVCSzTwPZHlb1b%eOiw+tcvJ68bfbJunoS<9qctX9moqHOm$ zUCyxdpEgf{fsfw~n7`B)QG92mw>gNMa2*VD?}hT%QIwJx_OIM4AeA9 zsDjvlNg~t_ zc{$>k{5o=@mDKYNx;HkAO+Q|T)`B)b+L@cRh!PP?AYmm!UyR~e{V|$ga6AYMON+X! zB#66p4vg&uwgg`)ot>RW*rB6Z0Q@d|>Xy99N)UhxrtV9$7xsyN?sK0T|HD80L+6EF ze*qdYXixE5@(Ep3^nE2h;=}tVtrlr#5AKhM3~%0|5mBHBx#>bmP9H3@hOYDWFi~zB z;+07Mg@oO%$^97@JOus-j9Fs+2jG>F1cCfky$E5EsydD^X{O^W_6%~rMmP&zxE8Nl z_4a3~P~EGp%FxZ>PV`@7)3I%}AXKKa6Eig z!P{2uP{kQOlIs$lr(g@qMXCVaMmeoYGEo4TE8*tFWhDr}eO8sbtG`|zd*+#EBwf9kyxC?RWXU zmhL}{^nZWRd3(BY7(F!9Qn8TtH7G&=w?6{#7hB{IPPY@^#Rz5Aif+NO5i{rODHP24 zbu?u`agW{ZWQIwesm&n~b)L<+tUY9-(wm37+DNJ0Vjf(*JtN(znyc^6O1fhbPFpaNeVJP>FXTi}a%33}Ez7z{^`di=nmPi3-0ag#qZBF;_ zJMXem1mM0vdu>hwf$jxIX4guIQ{NR;659{d+uVLbG!G2 zmw8BvXmA|$T$ZL^{>3Fr5*9ql4WogW_1?PMW(aKSnB~qR3f*=6irC=Ifmti_VCa-l z|IfDoPaa|Xk5dWFKZ}F$ZSp6^BfL&^7wcai8 z{-_zRDfub0Vx<+YZLx`CmF5{ZY{5h4t@7>&X2Ced_+bmAA%OOD=F{Aiae#L2w*#o| z?>WGAAWd?s7!NXLIIg7-0$qcl8#958^UgeG?*Kn>_XNmE*j-&0(90JrJ}%%_Og{1{ zA`f=BMLin_g!Mk%k1RPD1z|-3Rx(p*h0&0e%@$jEyvUKgD7|a>ojlQ2(+V)X0a8B&nIqdDAszPJ7QXFq>+g8Qyf5Qm^VeUn^81sh z&=k-Tm)mKE5+IEOjI!oSgi$h0AYC6(aun=L2LT{}F@V4NnyE@_n5nUfXo=OwtF0ud zG~enCjC1&_eG%hXfMK+bwNm?%xLb2Rlngre1~CB-kR@7E*F%7dAm@GT{jh>THf0X- zv1f5~3SYu+&U37~92q$0bf;GcBdw%p08Zopg9zB@5;WOwoIGd!(H=YvZ)IFWQD6U3 z1RUI6G+;%r#o3CNwgm|^;yBxJlVFXVu)!S4U4R5QoqxGn1mGfp=IfUw3n;ivWc=GD+*%1+SNf`dV*Lc$_NX!Atex$P)Jc|Wf`ay+*z8J zseHN1f(;=V@wp&n@yv2$!^;7X4KllwN{F6M)53arWwGG1fGFe_~a?b z=P=oh$>-+*5>UAcdYB~#ta{cl=b!H{(kCov)Uj^roT zxdfqv>w}|^|5{746yz4E7yzmEeg5;GzsQ|hIrWe}Mw`HA#UQj&1mM2FeVJY?EEN6v z*S}r>0(gzzyF{v}!7>WM{*q>~yeujT4_+ABc#;2M;Xd(D0FH_D$xr6 zPNItFnj}*W#DH zsVZ4&t^MQH>KV75*$GR+mL;z<0zg8BDm-fSp&{}LWTOD+Ar?|EVm8SFD6f6#OJ5SH zE!tWSEe3uUM!B?nSt$ZgjV|zOua`S)05-{z13bgFi;c+(NeADem}imc9_Lj09}T<2 zGkXihiC7b`Q}J4hr%j^tdvEA(NvCkTuI%fx_n!&bT6j=JxXEYYiu3HoNV21#$I9-4 zm)$9MSP%Z`bleO9vBRVR4}Z&|Q{ThV&}*~j$ZM8Y+fV zUp_nqi+=Pa`-RgLcI(&!c1O6C#2u9YeF5aT)@FSfW5>S~Xo}$0N}alLL&stjU#_nz zgbgVI$$1no)e(TK;tQ6kN`QA)VA^)T|CjrTMUjO9@MBmP0QmiQJI;jye|8SmgaBL$ zARQ)`dGo@{SAqakgA4pZ01gGv+uK_~h@wM^4y58tBkTd>9F$rK^vKfEz{fYB+DI_~ z*MBuw+M-2gG%-;96^xDA7RdHeCXGnd{7MqzpE2w9|;*OL3|IqZ~O6U1uSnB4amW{@VftENVDgaZG<5Ri)+}>{vX0 z5LlA{aDYv)=fYxU0ON*SlMlcJg6^y10B}<4}XCM zW6(a^^)6eVY;@Lqw>kfq_DVz6?-{k@jea}UUT!hDgI_CQY?hAo!6$7m8e$vHa)(Z{ zXoPAAL=5{jhoA&wTmV?+$$!CLIy`cif4NeK(+l-tZ4L{-KKj|uem2PdFq_k0AEA-_ zA=FTgAkaCx>97QjUUIqS-F@k$VYfL|pY35XPl^!4>Ymz_6z{5JfeDce_2B)=Hxu~HJ2 z-g;r&ZX2(#jgeXhiOo%@6;$@lzE$#=Nu04e$ir|nKq$7hLK|AMmZ-z)n5g*-%<6rA z5er=#334j%h%L_I6)Vou2?2%ykoR)N(C^K`n5620Id>6GhshN+^h#I&y+AKqi~yoE zt^yt9cd-ZfP2D8Dr4T@%2*K85Hv&NbVM!t88(M&SiihmAXrWz_UH8pW2;S)LIdAt8 zUi#jdI!ED^AK;)vXMEoDbXb%aZ&jO6hprUWGABc8=s!|ykN(k@EQ%yJQQ4A;gO{&7 z00icLYrm~KJ7oXt+!|sRG+K2Mw(O=a$VZ$uy7M|U*)BIbW!Q81Sif{{%IYuml>0Ze z*Lb|`>$j&pui7hB-kTRLHD@kJ|}tfB@n%GVbo^TMUY5&q#*fBbpdM7y?N`JW%~t0S;$ zAm;zyRlaE5O$5Uvd+e1^n353$suEW7-X0t8dd?Tg1~;%ljB3lWm6}~BJf(=*$Y1D;Hz|y-^+jT6E+d*tp z>%04{He5%<|8xmn_I7AuY8sB?@z_;AVBzwaD-X=U+?2~eL2Jyylb47@^g7Nj=<-Wh zwJI7h@&U(6>*5%(EF4M?#w|WlmbDE=taVK4F4^e`RuDZ`jDOe1SCy|w7ACS36^bB_Q1g)JUMxm&Wlr@1Q+L?>$A0%Ji0sl#xMSvV3 z2y3*m#==mOaR4C(?;K^tcG`^~EehCGTUd>6X^b0IR`?;Ey23!%kxWZhl1N?^sw zVdy!F3qgnV{R4?J3)Wlmb_|FbH$Z10AudAnBJV=SXh_qHZM@$Jp1CX8ZtF4pA5Knk zme>mbjaJ54oKJ)fw7P0l)xQ*=>zC4&5#bk`d9Axj?xDQ^Du&U&W}M7_cPBR>P+S9G zXYZR?o_WRlmc7dM)A9Q-HmZS^%5F)iHT!k{Y5TWDe`ezm>?k)pV95u56+m9i-xGz>i90Z^}X2JXa z^}qhtI@X9eSS(mnkE{h_mx&HeFGX0=i*7FJCto^AE2pYK01ViTD)K46aLlT@`t6~_ zZB`BN=R0i#JjW3=9Sxkb0zz_oDwlrim3)@s>H9FX3O15qX7;>A#$O?+q~D@L^l2B- zZoNAQw9t%#XmiSLpy!l@-~7J)_u8<9no6ypiqI>V8VhKW0F8h}IMxZ?B4Ba=1RxSX z$!u8nIrl&ds0J`vZ#b0wZ2*7>0 zfM28PB7pFp{n-~PKmcFm+{aTblT{#Lk`*je10w!@F>S;1FVJ(wN(QE^g%wLSa`_ak{z~|Hwy4KWlwCyi=PW?^Ji6>X9#n{qy$V9b zgu+UbMaGAkl7QHT2Gyc*K(4ThknBVBGb}>#5>(eY>keUCK%`zEB&)t2tdQCO*BpT^y%YOSS&q> zRp1-~U``cO;vSAUDig+)@uoLc9a4dFkOyJUqoE0V8q?U5iTnUBy`HQ7&Fb%&C1&B# zm#l#mwk`3vqc+Q@UXj!zo=JPD@wmOvdd%wU$P`TeyHzVx<)c1d0j@Mmhr)FXAM;4~ zG(OdVX>kXRI|nQ_3O0t<3`1g09%j`i15)gk2jP7;rd*LTtvyaN7q`_tX51!8wLK}x zb&Y)_`k>vH*p3OY!l5rk0Ae3b`7YUW#c$Ym9(ln=$%9Zj4B6jJeOe}R6scKdqfkjS zX5WUpQf|%HSxuLtc~^X?65!v8x_d)$x7D%GElvC}S2aK{t(n+nw+NO5Qyj}`C=>sm z4V$=CWZloBn5=i?zMvOt6Y!@~0kO|~<}cZs%v}laGQrwae*|!( z#X&|xXa}A5_{)>n4JefvnT@v~Q`tkz!gu?v;pb%9q=aalNm!mxMSZY0cvJqZQvr<{tsS zzd)`vPMMyAC6~h1epOa~)qbrIK={cgpCm||eL*jA3LocT!YQ`7QX6M05(w4?C#@Q6 zS;p@?=S;ThR(>A!nHSstwwV%J6D?(utBaOzg(km5WxdF}V--yL8lJh@-p#l5yvjug z3iRPCfn6ZKp-hZ}YZ9c?0uK*$K|G3rTtRV2i>P@<`>m>{&suxNY#Y7<)yZ;42)MW= zGA1}#k4}|bvX1(08)!$3D%qVlGAYBSYrkCU+-Im!m7~yw<7tM8+=ys zA0e)C|0&D1lL0u@&@arv(yEjHsy;g;re2=UUzY-KsQ{5Ev!_m-s-2mc`AT77;iue6 zq}wbkZ^QGAz?d-+2YPg2kz>T#!fty=ngfDP{M~FBV70Odw6MmN9eGCjEO6pw+ZAoK z4e+=r1dzK9eFZsQtkW}SPX`X!X!E!gwqeL|y%0dQ=Fx4+!s}!5+1LQYBf%B2o)l*w>`q^1HWIM{v=WzQ4QNs6! z$bc;4Id}D#n3(tquq1MT0d&ZJcl8&%Ed?M>uB2Qo0#F0oEgbJeKTd7std`m@}drA!+G{J&!d?ahh~dt={ei?(AySk9BnJ$!}D%=a;AGiTn$6lRq9 zbL#_hs_ z_cg=K%lARI&P~(hfj{+Sk}D{hkVjFNgtYYh!dK?o1vmUY&E_lssm`vbDMm5dv_LfEqh{ z%TB@_L(QEGYPm(27B#=iXl5tH*9?^qZTP8zFWSw|EtsbrL`~;$~!UJMRefF zIuuB^A~l4kUXBqL@B?(7;V!Ft`;2WkbYQ~mlRw>up*t%9!Fr86ZP4CXxvl32Qvlb|kHoWnM<0Ak zFQ1(E z?$1v15WNVihvDZpN`HM1t~d6#9Ta_)&E3M^GHa24OJC9-So*Yu(1@aDl^tKPWSP8nAd46Z$MY3aV zhGhKcC)(92XmXS67c4sjA6MbB-xQ8>dBu?g1kQc;pwOT+D(<)26L}8PHjG-wgE5Tp z$f!7mrdM+!xyfl0bG~Xbw@11-?+Lc&iYI2_*s@-z%WYaK#Gi^)*NpnLyrPV8%$tsu zb-E83$iA)nE8Z(5hW?+Scsdw<1|3Cv4xCqbm|BWpbK-_`8Hl-Y+3w5DtAPC+)7ci`*z z*Nu@=l1Y$zfvGirx9@b;?>jQQKCAbFQ=Au#Y6#k(Stx}%YL`oS&s(JpnbOJHGw`-$ z#S=ARQO$q5=N{Ew+r+tS{OjSAjOAH7U$oixlu#S{_}jVh2Noj7vRV-+K6Jyx zlX>nuTn?gK=$$YGn(~D0T6%ps z_JAqaHb`4b^Uc&>pFWswN5%SYfPlg4H{e2m#&!n0x9WyIHVDWNh3-}=+rX%03mAnd z0_0f9Eora<>FfUB;xl@mMHT^# zzye!~#a#O%E=l^O_3XC8wL9g)Oc}`WsIeYjcDr@i1PFaC1hQCa-*zLNip(uvpELVS zJE8v>GZEEP%ZfGYQQjdH&i(>1P2FB?gb}hLKfy|!^o!-LMA>(qHh!9xsIJ6+;9`(| z%RyMr_cJcDUfdWE6Xsv&|AZW}S&A?d6gtXyi5ypX@nuSe%#g~WAuH*P0j_H>}T z|I=pC+&k=c+4P#`U5CpoD6P@>ezA{Iyh8?TfCfE2RyQTI(q(UZ!moLM*GTtdb%AYY zpyxO`@6%C?Gwihr9(@byu%u+wTPjubC@h#rm9uvA@au8|NQn{=3Mdi&(|j4`tfTI&%aLMUn{_8++L)-pgrh5X zogYyLhAW_z8H`5_fj_PD=bMhZT?eW=W=K-V0NgS4W#?6o3h0%sEla}7fQ*S<4F6AR zH-n`cE?w-bmrteL8_aE{WCpNll8s^%`AXm8B+mRv6MF0nFJtlI7Hvbn5YoTaX?%Ni z)8VMisgXt)fL*3qRi%I5S%6bnx?F@^f}1G*RKZs(Q`nYju^g>B`&Wc4`?9trGZ_^R zZPR|NbR)M~Tty|s;R#L`CYS#% zsG{&gNRD}3+GN4(($MeqE!z;O_eL~JEc+}{D9uAPA;w+X^+#=5U#nAZO*iRs3ta{e zQ*1=DX-xJB?aqk7sB?=Sn53G2k!vK3vM+^qs`P&P-}UL&goA%Ej5>Ssm?2Mi@Q7V6 zr&ad#wjZQ#&^>8J?&S`sr0NcHCr+_)W%F!PU_3mQaHuDn3xzX+RXfs8xM#70!P1-g z^Se0EaNcv8_hScfgZq`i-o@;rjLtA-hO}9X(Qn-cr=pTO;QJyn=xqAy#kXH zzc3?%dTD83ce8xtItEGeBeudH%%9g8*zwYVV=6q%HIxH{C#5gb-|u=$0)4#DyTk|x z=f7cHszCYWBciP0pC+tMpm%M&Z1C=8_h6?0_>r$?mJ;a;t*>)@Usc1_D#YT&M`y#* za*M3@77%ve=DNw#Y{8u@IxbZ*1sGT`M26!gTx8~P40UwI3Ck|}AfH|@}UAank zog(HChOfuJ+OVfaHbC$<&g%{v?XYcbd_f3$WO~xO*tjOYtT=r{`n$RZ0d`*S6FkXrbpa$>gVbGME*7MFqi99me8V zrBjO)mfk$zSO8*$aeNrp?XO;Lb+3_2|dB_hl+A#8?=-(Y`^(M%qTL9CYSrY@J$@eW>$6f>HCb zqbCy0LHAt0R}GErqph41{CisqYFeIL-T5WP(W_+5s<=(B#Dtzk>`Ch_Nd0TKAb4_@ zT++uz$f1293&Fjo!G6+9c`<3P&SLu5_69o3kpb`#TWvEED|>Na*6)~>WJwVGBP~53 z#MpDZQLS>>2g2^F=G=c4|NnWHt6#AAM%sAbIP=?wD8l@vy;yq=Tk19&D3 zGl3&C=jh!KreN&S>5}?eH{cCaRcqG+#iOzMH9Ho@fU&>_*pts6csv`+=H^JAtyzM{ z{DszOhnWycSHj$4a!iZ+U>Wz}y8y$GD7U61Ft4WZj)P92H2Y2<^5F zgre=Uo9|#CpI-GfUhKs)u41drk{p0-DeV?w{zyD(u>WqWs3nZ{$W`R^0t?~ zn3PIf^I(xzcnKWZo*2Dj^DC=9_EXh|?C+O+1Cf@Eq_O=%W;z(4l1h4`w{y5PXbNw8 ztEQb;X*j)-haFdAPdtb^6=($d@7vm+9yc5FYdb$G^Xe;hk)+e#;mnSU^$TvE<<|r3 zL>=p#fu`p6#0p>hh|;#JEKpT$9X@0RvnHVS{p@f)ZJnE6B1soLKYRu8uc?THfvsumb%+FqGPE;`Rdc>N{}@$>-xD)aere9>=m1vbz}EV{D7 z5E{;9@y;Nx{dTGz0n7*8pS?5-8K;hoM>;4@y10De!rF^76;J8UZprTyLTt~dOe*9} zptk8%c=&8b!{&9yBwuFMMsEya8nH+xl)PyQZ{Jqe;g01NT{lu3_$%ckX067kF6+I` zcm~AYT|OhxW&gD1;$oZOgjSq&2gE)l`E}nWyr~#Q-MN;ZkK0oL%y3UldT+K7G56>= zduq5Tkeg70?^6Q5T^KAc4Cjs6OIWTh54XD%t?u(5_w<~#%v&n{u|i?U{(x*@V9p_m zcK*=QvI%21h;&LurW` zFU?2d@*X@;yU~CPZirK3^p{+Rs4_XvAoEn~Ly@l5NG^>L0JfSRj1ID@{0akr1 zB6tpk_IJI+vDs-sB*gF-o$t$cgJ`jiAN90AFhPV!&0@9`TCx$O)DGoc4LW&b%vJE* z$JU%*r~4c4MzYP!SCA?;g2%6?j*)Ks^VkQu3;r=Bq2L!Tyeda(BMPXEmj^sjHpyQ} z@`Qp1ukn*`h`RX1x__tAG?V+I0*79ugceuLq9ef!aXdKUyk}I8eZ=i-kWXTouG75i z@Y&b;H~UEn44kdIW{k6CsXVW@2FgfyFxUYxKE{2co_g;~o-0U@!E8%t-@n6 zguN){g%5|wyd-F=;+eoaXSVvwE$@xVEKjAbah#;TY#nc>=Kx*P?qrouaIoXYSDj7a zMe{Yrg>iDygbf_RfU<3;*5mZV?`|y9!Uy${&q;5Ux(VE-lm5oRu?ic7E`vvomZH|mHpL!y;yGG=7P$#Oh3K8 zk4#poJ&w#&afrMFm|T>6lOH_Sx6P_c!$=aVE~6hRBvnRt`E5rahi2sLhNg07Km`wk z{@epFLflWzHe>09-ktc3;vD&B6iYO8PFNr_mIt`UB=j~foOZn0a+o3K)ZwXyq~|?E*gA<>}KW}LyV)+ zFx5uVmvlX_q`B1+F*W$y(8}WsD*fU`e^4hUn1PrqbQysm@>1sn!kCifiEA9ei6W@% z-93+=WEG8}{1I^@%DUX>u}M!r+3#0!*II@n=r}##Rpwlq_ah-sX8rEv)$N)C) z^0RO(VX8o+f*}s&PV@<#ziUAEyVzblZ}Nl|LFjMKZp*v@)vWi6;D*^P^2oYv`{Y3K zBFpkQ8f9bKy7Eu4k9?gS0So0su|zzGGs(b%uSoT2y^YSG6yfIpUXOi4JmB?jT4%^7 zrb4tk!{?*z6A|}bs2OleTK5w!6XHnC7*OeVEm1ZjogkNlBr1d=Ua{X$jsTh({g^08 zO?8ut9&L%}01Y+CDu|kMiWL};s5_<# zd+rVVDAOTj^IS!L#zvvI65KthFY_|*?{cadY8A8j$D^-t1;BziZM`A7Ok25<3f}{5 z$7r^;-4~^9uq~8zDkr&gHs6rpwR}zL?e{?{e;3`Jot@?3k3#qR`ouSFBriVlePK`( zV9o%sewoCo^aEBaL{y1fU?>vbVWaheoiZ`+-;-(UGt~yf5IS?YI2n7WVW5xC$NDaL z5W5Sq*UBRlpo|LEi$=q)Y>f3+146P#UNcR)OKVWw)MY5pdGnV>*#Y&5u|b8y5+ztl zCbFhr=Qk`P!b?5Y4gbT~4>nPWFBdDAPcm($2=0+X-d)6;KC#f{0vFHtZPu6kdM(3d zon%c4O6dbWyGk#L4$TCy6BzGQONHf#i;+e;k0l|7cyX{v&l2nzKVZV!xNsxN3UgK77Y3M;At?NIL=xJtnOjMJ;7{g7WmH?2;LUW7w(0nl$L zFKmM;Gd7pd&?ese4LC{&ywWNq&^>ec$m9W27$I=upWD3K#d^ZPQ z!i*XuLQeUOe%!v`%&3YmvD#qcxN!Y+S1PZ@K4XRZZv0!dP!3C-^8qD!$9&c~m0poW z!>e=XI|j(H8=V4HZ6Qbcwqm}UUQgXRx+svh^VtY~BjFXoCOiwv<#nldv4fVa`;!#5 z;Wc1d7(o|rVC^IoBt~z<<9ck7a7o(i zAw?dP;xDawZ2@4W)`nAmQC@OKU0N@9Cr8w}_M)X_c~Q4sz+0-CLZjnc4Ef;hOvA%B zpfM}Ql>b5#6f}B3Mz@AYx_!GeU zLEYZ)h8bwJ%*UULC3{5ZuI=z0+O#O}YNqDo5^NieDxxzxNq;Dih+RHEj4tQ!v>I5Q zlFia^l|M_iu8jotr*(_!BJM`wi^1(JS!L}>xEMgZ>-l)3=p9gl^y$S!V-eI)1{Lwf zipU%DQ7e`ksse1Dw0)MBk_8uK*9rbOwO4!~Jw5)5z3mxq0wHLC?KJ!qcJsTJq`4U> z%avTIYkMws3?4g=#Lj>YtM&hIg+I78rPpKby^}-sEwc6{q1J0{|Hfnjio9&~W=lWe z#_q|XQn0g_OXTmza)9TDy5M)~_Tk1HBLvrYH8nkr;wI?!)dXEh&d|8<_NOGv>^~_L zO1d-GctQ%}H?eBaet)5lv1~*j3dS6CLed}Ia{qd18RzksIIEv9X;aDinZMSPiIZQMobqkTEgI2Y)S8U4^a>b}OQf z{I%(hcuhWUU_ITY{*IAN*A%i%3x=g;?Yh2OPd^i&^2>lQmY2)^?GZg5BAqJc^4#0o zixJlM?Wr4vgLbzhkSqW>vQVW6u_@*V18LX1wa%sRe+Kv>7;S6SB z@wb`+ujUi=QVy;3VcF$W4bpL?XHs2m6u0ZOu);Mbl<5!O0m{Y~mG6)vYq16av3m6` zjLxg^_rcN5iYR&D+V%ByyHf)5;sN%yF6O6&-SR0JsJE_GOT+@hftA0y%KPyz-^dxO z=~2GGF?by1dgJ8@xF0SU)ja~-y9%Pp82iOX#~_3h;B`F!6CI9Y;2CQZcZ`9bD z)dae?ZqjWT{7`JT4f8(mq`>ki7zkK6s(B-$LI@kag$nB7pF9=w^2<<0+ZnwZ9noME zJ=piB$5*&eWP}VtBMzRbI*0YPzJKrAwK_bp z8YvMOfV#7tay@nVxpU6*xRqv{X7B#*XZ}i$jZ9D8&^x~=KR#sCTc%ZZFHxn*(R40w z?-6|s4_AD%3mytw8tgj4_5v&$6L4P~1KI1gZz4)@#*&An2R zd`Wtmv1xAxg943{MyztKR>CXlr!R**TTjphExeun+`MS1t|eK!UK`Ufe&)DxUdnhl zt#ddXxSFx~)n(;7l>aC^ZFXv62_)6~4_X$LpG@JP=}!sFu6NJ|piDqzpykwl8pu8m zyy!YpfIQAUK@eY6kr&UUkk^TXNgxwhPf*;af4tm!r5a&Bu?<(C)%>dP&D;V%W(vat z+Bbx83MPoC8TBW&eXp4do$UCZ6G39cJ(a4$MX7JvdgYbt^l+mxC#WOHjU((Xzmvb@YxFgvJqe~w_AXWCyDxcbz^bHvFGhU{Jp`iwSxbjph(h-a7XYbz_}8LR)@W)2}b3MyeY5@afv#<0pM zD8_2r?r_Jsst1qW6!oixRvvs~Sr}J4A%cV4OqR;3gJh;-(IjT9+!``$O?<~Q;CBx> zEAqAy_~jlKrh^c9M8w;pQ37^wj#qwc(J#Wh+s2~V6NCF;CiM?gwI^$CI=zB?x?;F& zo~n<>6?Guqd2WIRj0UY$aC4!bH560*3V_>LAz3z9&N<{^J*oS9dHcai((dAFDE1*s z0TEd6+VJ9ID(V@*izxRKX803uV{t-_E_TZk1P*ajS3lb0(T(W+aG1`=(~j(Y$Z$`Tc;4r&es*z9e7AT&-1xqzj5V{#V5^y4Ns9u8qgrRErLFEh z9PGb^o-&=XR8d^1`&%P$IsHg1`?3I676k(!jM;EM@mH0TliN!m73yiWM84-tsE;LP zbW>c16vNc{8NWwEtSw#WAd@zc){Yi^DcHKzr+0<~-CK@ub2JXp1>KDs#Y$a=5#3Ltbd8#1~cMGx8({V|9UlQwSBoaw#{tofZ$Hcn&TB)*DJC95O zEi9nN+=$1jKwzjVacP5>Px0|?2F(cp&U6mgBNlrU0^A9mRVXrweWu8P`O%LvFXQ&U z|E$CzSZB|Kwt$!0uPt?fHUEr1CW4<2ii(O7T@7!;CS(Y{orgdmLYiXz#PFU^kkYki zz*Za5ID(OY84{&5K}RGp=Z%enNSL9NV+ELG8v8|7Bdd0s!Pa2Hh$qFRK)2VZ29vyD zog|u&U^m;W73+%sy5pe;CC@n9hR(Y8yngjgYQDQHlJG}2in^s`khsmCC^NR{`(Y?m zUNWU{fcu4}=t|?!C~#)+)12Px^uBUBe5BEDT>}33>25-z?R_!+unfigfz<{*uLl{L zI7-7ZM#Ka@oXS@0?C1!BE8I!_?5Oq7YLF6}k+@b0WIr3$O#5}_uJlaQadFIM=T0x$ z618N`@0D7f_riJc7#fn>(O;OcVc3FL9<_LTH>l$VE!(QS#Zt`|k%$E9(#yW}IsdB+ z;}tE#fY03Ks)vZL$2gt}HmJ2nm%rB!-EC_A z+x}Tjucno)`d3RzsDp3cJpR$BJVY}yjBJ*X77Ti{Cr}g%%{?#EHgG|>0TXZqe_U>7 zc(V1GW7xOxWV1Aa>t&`B_4>Zg%E`;yo@m~}-(U%wpTqM{FBU>3iG>l}?712GiTga~ z?ZmxX{7VX~{HNVn)4pM+hG~twcfdQ2sP&^j&-E?VzE$9cu`3}}XSm@N|M+#LcxZl? zao!jwgy{x9xKbH8@30%h*KF~-l&@LjasvO+A;lv4ARqj8qzWE(ev5!%@b2U*z2Z@G zs^&pN+>^#}ds)L=Cg%1**_fcaMV;UG9;56;HqR}$v2oupZ&7y_**B-3Jy_v5o2EEjrVvE?}^S)=t!c}AJvnd4E?jpS6i~yQZ=gDows)eLw-L zo|Dh%^7$dgY#x{pV$KeK*D%ECY_iKRO3TWs@_i38$=~PM-ZezFT3Iw#5D}js8J|FSL3hortk znkMYuy+JUt(}Vfpgjxg_CLdlU0kct$yK2O5XQ>9YCEb?`foZ`4Wg>&kXx}V-z?&_C z*?MCBbBgth&l%yX_&Vg2EUrs1ig84_bK8)aa)pf;pDje3)(_y{V0*PI5y{OS)y16F z5svdUJ-0E&hI7qzUvK`#z+7%6%D;Cy)l%z#P+zTn;dzqLr+xI`kE7s^1>p0vH#hmg zPO9>8SsJ)h@7*?*+G63uit*GGe)Wi`@WUryeFeDRNFa3X?XK!$C5|=SKqJP5;WDgw^O~83+i% zJOyb9EsI6!c?=^Cg(MW%K?IyV;;Y2QlzK}1*-cEe7__LNRb-KNvIDxX-6a>5@x{{M zpGSkq(fiI4L!FS|#7>2UZus{gCclrykT`#s;LKQ|6Jdl`jXq(bx#eYX$abghtQf`d z3BZFs;9;V^48fBm&$zcP?K4!OS^_Zo*AtP?*R!v?>=dxa*=*7Soge)1d{|mqDkir? zxZo5G`~8cWs@qDc9AI_mfB(l%TTv&l=8ZY?vF8-%m-{|_H!7* zF?K?j(XSSBZp3>2m(3Le76PYIkE#$FLsNHOB5~@_yy+b1T-%1aCNs&YAv~Wead7%{ zP_CV267DK)(O%V_WnQDl_jKT|@eeb#*O6!NzElsimyw17ts>J5aEAE0Ya%~R>po78 z#NJO-oexW3fir5BM)2(6}0Z9sR3d4t#+3Rawb((bWKSzT+F;P6272}3tx^k zQ8sv?4r1IpjylHU{_YthLFb@i5&c2N-(@FkP4tT_FX7 z!Yl{79r5Tcy!NjrFyLX3X$_vvY4;&|UKP%L6~}R(MwokV2a@*C;zPnbgJ5FLJ}H4j z)$bx4<%Yhg28~es${F8PcT*{SPiBcGkIXAt&sAAxMSRoneQgwdJ_Wu_0RvFxjeFU8 zXJFn~fpxeexox)2-8W)DTbz&$^HU|y$_xpc^$yRo{B6Ip8gI9*;cn9#BjH>RcQpMS zUF6e+hDEwr`DMyOG(+q)0*}=&ge)kwAlQ1ixH58Hsq=S!^=SM8uQ8Yp0B9PvwU$w6 zV5Dv}!Pu3AUgf-t{HM5y&36I@T(hM4el-s94QH*Qd?e zgyNYh(Sva@CNVDs@ry+j-+5+n=J+WSB{>yH=%)u%&R17@R#x6W0=rUj2U-H_E_PPd z#z5QFz&nGZH~YF4(7L@M5yiDtJ{_s49K!eP=YkZ87pT~Td{x-3?p25|nMrTyAJN(n z<-%Ru`FVjs>QLFr`q#M3uPf|>ZD9;u2ZKMpK)v||k3-XT^C?8b4mBCf7#oP9L$jK8 zZ4rP&I4FD%n45XM!~8uzEXb#-qR9pAFM+6Vu9kXbj*-R`pFlfFay8{ z%vTV}fWPiKZ%rZwzdzT^fcrkJi*L6-dfAHed!5bS%^;uvz%%p@*M>XYKha+x2{^PF zV`uw52PGl|hSrM&p-bKIQWQ>TngG}wn%-DzAGsSiWCY;mhCA9-A9M9Uj&?-9Z8?;C z%zBjAD%R#?)-@B-OPHTQY_x^H*;QTX9CnWakC04A^cS02$3=Gh9XDBW&Nl zVG7;n?7}SyD=6r$x`}MdYxHDZcCtNfUuFMW5S7WabhZNa}uS^*` z$=wLo#<1A4PokoPKgN;!#Dv=q`kck?Cb^&het~Dt#XEf6z~AD$ZQOLPO44u?l56@s zafks={~{lRyo2tWP>Fk{5dvHWOmI*K5+aL)_F&(Op>tG1NC#czkF-?l(3Pj97LYY0 zcqR*yO#3xj5B_LXCXkO{3q$6hhu(>+Es`tiN350TtKoMZbMMpCoAAtGSPOYd93?Cq z;3R1S2soF_BP-0AgAp~ooMk7C!-IlF;@a@ora2cODs27Or2Yt}J1p-ug~u@S1lFEG zl$z3zSwzjKJg06rgV(X0d;V@!zhjfV`PDnvSiumSaSrCz<5#k}wct$1_IdS5!}wX8 z79bUyXqubvP0X3+HnTW|DHtog=Z>`$>n((9rGR=3H0Z9>wt?4!pg3M<~? z3Im9UvGI%lzU5+%r`gHw zoAC?MOAU+#w_iP9B+DE{|MCEsL1g|GN4zkD%KE9^Vl!97yG*1z*=X)uFVb8>O&21; zo_k8QsH^W%cp*NUaqck}!7o}x<4|S_g-82SjxaZM=M{upIOc7%(;Ff<9MfT$4lP{3|ep-r9cDjgSei?CT2W7 z5UD}0=s7H;@8-iDq8Qjo+!S=;(!)uJzcOazdHKjMnAq6B0*<3=Qe_^_^Wns2qQSo! zQ(F*Jgn*&!(;-ROhHj+Yzr|HOT?F+oxxJQQz*~l7BMwPAR<$~X>IifmVI#+p-Vy)?i8W?N4NMT-I zSK#0DO46mN8hSoOMvdg;va6dRm<>f(6G>YVsSq>8f7wsW=eEjVb!}^DgfqC8;T~!h{hm=|yj(5)G zO?}OnDAm!{(|%AvdLB^5e%JfrNIq|9FD7HW2Rq^E7gwltkeaYLBs2@k#aIVTlg_tTWLa$)xV7sfKtj%xS)Yjs(5lz2Yt>J-PsmGx#Wl9 zcQ83wCEmsM&wFZCb2j~-nz&P!8;G&OAY?)NFLV#p)6eYyz1*9!N&Y~)v*jAjarwoJ zo~xNt%{noL-Whk4*kM7ZE}DGAD8fs=Ny4 z6$NZ+l4(P>#zG1gt#Sjb90# zmiF|?4&&V;I8+8+-A0~DsWbTK3N(gAEmL9cKT+WBdc%F=m6erb%a-D$^#>n9PS5l@r1{{wlb?86gMn zSCr+wpaDdZCYlt8l1M3(t05Jj%-}?F=?MjFBzP#0FdN__@=e&qB`H?qCA~XFA3iRK zzW(aN7%=sB7Pvv?pup-s7Y6-6Ueq6BVUN@#@y1x$Q{y7~FhmKmFs{d73P4SN@f#zEYcsbdm>y{ei%j`vq0Sef-s_@q7hf#`M+W3pUYPQE~{E zp2jc4@~ZpHkTqC`Uj;>lg@xgT{ol<{dxm@5-D!WyqRhj`ozntwgD!az1?r0!p3KrY@pNoRl!)l%YzVqUKA4rb*vFih6dh4-Rm#9TmERNYmf{sz7}ioo>7Ws&FBDZO(9h zisFz8@n)051Xw~E$Mr@$DebQeC^25&31=8}^U_Ihem<|j`WYA{7WOo8xc->+^^Ui1 z#_v_o-dmn43l3m1fk&E$-gqJpcm|T_j%o0CJke;kPjjj>I(kcjVu2S1>^&)a6q#1E zlNn)&8h!J3H~cs%2?idi9;Cw4Laf-o&~1Y^7(3HTgx7XkFob(Z5Web0iO`<3X5D_* zNiC~ez5E63H<;!`#n0!kC`Sj_2NeWc+Yc`g+cmHp!f>x#W=f(THO_(lLlv6zFm{kY zlt8-M*O#79W0Lt>8`16Gxf9!KzqfjE+v`PAE1(%^5iL^SO0f84Lq1lTgTWuZ{AlmA zj(1~!X-8lzsCzRJvT9JiVbOe7XV2n;Ch^ zpSS>Z+g>dw1sE&hQU8-a86dIySt;~+5WDZ{*c7*t7t9zd9)~660u6E|XxH+XB<4kp z)C8xn^QPn_FG7wjnzM1=o)fL`=$nFf3EUUQM5yg$&t>()AeXTs9RQJ0`cv&qMK3nsx2t zv)*kV2nfjWLW*TF?5uv)_$FEPQGdCcq5DMMec5pqlRz#en#v`=_>Gr3-}eFW?ewO& zyJx$=KlWED>ze*=5A;KkBo4@YOzA(6#0>1V;&BBQYmM6ZWWw!7-%n>!@RQ||O31Dq zZDIN<5PfhpKp-0$NZF8o>`Pm+(Z53AshG`SR)_$Rb|2kVd$>6E+PP+>;#z_n!0`2D zeo=R-O^=I@r99bdnn(dq!@)$IsX_3S#wk=sh;w%jdH^)w zF$!~(-$u_awB+-eV4~vTjRJ0l>gGOR^i*W1RWvX+U8qnf7{(xG%Q_J0VzMZJP)+zH zJSia}5(9}U8ZJ_^esMQB?PAgQtkf=)^PM}yzB1D;WlK58h~rfGZ&V&{k`dRNvxb*~ zfpk49mz)-Wk>ahSj9 zO$krM@so|wvEl5n0l|^g@3NE+kM}sWD;X=44M>`ZP`_++)xCbg#D)5iPZqX)OF4T= zL)$zT^4*!sJ{psVT=RZLYLL-&lreR4`g?y#G~qpl`~Hxuu8Br4gI#IAaX6)qmn-Bg zt7OpKjbOFgBi3x)`zRB1b~C~j>ic_6saW!PuB(u3#{e{`4qf;=B>t1y2>XeI+GO+T z(=F}xI#1VkTAREIRwAR7?aeeuvFLpq38N$8knapvE}wu@@Kk`7hh+%olybyqI#x8* zQkv+MC(RBEz^38hmof+I$$kGR!aXct;J8$5-wDxeIMGnS>MVQ|dL-@Lf*GVN($RbQ zHDS*6ukW#?`v%lU;(sACa^U9|>XWCuS^ zox=ylv_qMp!3aoy-O;xukM$!7niJe!L};-Hdbq@Y#HL9`aQ3FAfIdxv{Am_QDbl$- z>aOl(0)bS@U{zo$NF)H-o%2ecW2QX?uYJPlU-=S+Z{`kb_k$WFeUB3dtv4K^u z!6%)b8b4~0QfCK#p8gE_mZB9ZEe??qtML=mREF;D7JT4}4?6zm)5(Ek9dC^eZzrVo zhjk7R2?&edh$-rx7v6Cgf|r=7nDM9G&SGR zi(~XTYm=o3pdI)-kQ2PRuyFTM^O>!B>yv&!us_Rw%tL~NXtoqOk=ai$AyTESN^Ui6D^r4)S&S(uRJb^G+Fq3J3Jl8=nccIs=@^AA%4LNTzs9c}BH# zX_J8{+Bg!AO^*d-x$U6W3tT1sj#wZs=t>T=4Dt&F1)xtl*Ld^Ol7{!X-24k6M;85j z`VaMr#ircX49Qop;N?Y_mszZQr9@L8|NN2zIEpI3K7k zw%ykPzFvJoXmT^lY%@4^?muy|!w{cuZ^BRx=rlT9UE4|VKW>nerTWV?`YX5RO*2NZ z-8)RpHS{x-s((CEBHso4-T@+@Rr7e}bIxqFOQ>!L=2_xvZK9o;IMDsNPP)%k?5o4D zNKX{IT4SPr0dNnbh{OJ!kh-4Jj-K6$VoY4Ax3L789`!z>62BkiyD1dC-nPT~?oh0A z@daFC7aFaEQYj4uIP7h%P%3h}^Ksk1FKC8D+*mo=&l$S=;RVi%@IIh8FLdiG`E^4% zdV`w+Nd3rdQVY0ZV};WDl_N}PvX>x?1Byx6@S0G{?qGbW?Ck6)-*+#5W#Tg@?$2~& zAp7BXOLZ&#HS+ITFdf*~-Te;WwCQ6kr@1hf75M5kQ=~jO2j6k3-b;LpdK_f?-whkH z-6b=Y9_3vd$+`Hr3Cj3l(yUp*e64RA_gN+6gca8)4dv6M#KZmRQq_i_px}2t$MwY) z%Zc=k)6>(IW<{-@hyX6%YFgNnLjcVcWm|J=>jymR0)4CFhR(Pj%F<`nD*Z>oF@^Xm z#p4;AmjYA|t8)QgnA7 zqfst;jthti2-}ps?AL8ev=8nGd&dwN7a{|vs;8^zJ8s;Y^65r40sPtj7*fnU$nL8+qtAO~ZA ze}D1;$8P4(CGXFPs6FVSPZarn>QV!{MeFN?L(&s0+b#AP=Xfdn9wN{cwI|TN^&J=X zJ7nc?P}}gI+<6E=OMBcN{34$xPJqd8>D8A%mQHo-jH_NPo3~oE8Et|5@f@%bF9gF+pwjz; z;;Z4-_xZY5-8o15CXfN5T}bO5N^|D8lA~A7*VirQ*fVpb(0@S$<^da;FSm2vhtB9) z_*+NA#JIvV5O`K!T4E5 zfPjp&g@F0*l+T6ebAf<>E`Wr9{#--;x32)|e~v;z6hQy~@_#2VC+g$ps~pS^t)4CLb9F=6K-_{_zBb-y;)6l%-yzx1Ad z%&j9&4j7Z7Ko1p$xy2a$zb)7!LPgkDG(5Ljh4-4haz1?cEUzCK8=Sx2*^lP`J;jhG zh56Pk@eF4XF5dC+RV3pj8@E&_<3WZCe}U5X^zR}tfP3q&!FC4V2uaGM0(uXL?~e4j zW3fl!qb5=F5k~7&;9Uqes^W-?vPLw&!#c3y=>BTo{-t|t<^J#62cr~)Cx*enVVAja z{yO@LcSqo@09n}w9md1+em7igk1<$f%U=3G^nw3@FMsLLvZM4$Vf*g4j9BVZ8aQ}} z(xhkCc@m%|ML~%9;Ch=kvc^kY>%J#a@w)F`;kg6SE9%?ZFT&&`taxxm;VUIObKg8O z4^%A`0gl*L&~E)*^uGmU5JHiVJiA#^Bq7al zn$}fNP*}Y1lJocTGt1_6jM@6MFe4t$R?4Ln3?f}>!XF^@oRaE!at1uOa;DIe+m|f+Q(2$N?sF|JEro|pQs&R# ze{=(1KlSC%h1IkT47%nlI34>Rpd9|J+BLM8*bnJMIWi3Wh!kw_G$rom4WGh~msS01 zP|GzVd^dS){Jvx?ldDp8&>xPx+}9_8T#M~Wy(&+l!KaLIFPcVh4D|6p%jms(ZiK>^ z{ow{%86@{D6J^DMW@SX$jjW7H2s1~1rdtwpR@=$?lTh#}BltN3O4@m-IuO5B+k7MJ z!pi~8;ak(w&F!~_+(F*3)*hJt*=P9RYxuC%b(I``(;;7F9B$KD|0xNZOYtin%2|J{ z!moK4HuB61qP_*JnrT<7b}6P6m?FM)$$1FVdlu41lNA_2ub_+2scb%Y@a5G7n1u<236Tz6 zxf_HK*F8xQw)ysA=)Cg6gOd6vyo^w1?Mu}z>qpfk`NE>_6;W9k6QC;kY+)%QGZfta zeAeI^++yv;ZK{VX5MEYKN=Qx~d@4o$GP`6>}rvPTFXEcW8CIKH1W_cR9}S{nM-<0=z8M=?v}Nz&E_J zv{E`;HTOFowu#B>V$l7ZLWx6Q>W{0ZM){umUtc$W-KhxXb23oo-Fwu9OHK!_i}QLMWbRcn#5o*s=XNa33H3V zXc42yf_reyV8Ai(5YHI#+i1q;VbA9;qo9%UJt!BS`_{L<_59!b&EMFL9Xm!*fgAy^ zY0f}%1)0PI+^WO}?(-!F2#Z5TQsav5kHy5*GNyqx7F6xM(@7+ZqK*B{p}lp z^dG>vk6CVZ~R4*bV+ z>KQy2CxI~HK11TqNbt;5rr)1^PlW$AzVk;P`N&7!dhx{<3x|e=NR>d@=7|P9g;sFX~eHJzI>lUjMbMZjY0^FN? zi+XV8UmOUma6b7Yj#*2B7;sNS=M6KpkP`q`V6qm07}&&OEfu514tio2v#l7{tT<1a zm|QZoAo(5{#IJAm_V)hMyWjn8AN&$13TUo?gn}Q>Etw-oCI+~aXekf!Wj+LQ>V^4_ zy(7+O*l^EHBfj42*`7#mtEs6m+<4=St{?yS$G2j({}|5w3bvd|EE-YB9t(RE3m=OF zFqwOS@IlPfKz3}L>51&o7$(9Q!l2psoL;h`H<4&S3;>5fae&0Y0B(XDg~^O#1H=cT z6-2>_-ws6_OqN2$b<8IW85{a@a0UPP@WT(k{?=P>6~kePB#2x=vWTF$0lnuvic}@- zahNX}0(y|^-}(LQw5E_g75VjyuV;IEX=!N`N-Q7P)kgrl&thA*5D*hHJH{wkd$8eg z$na{W4^Aq?kA~b54NieQ_bFC=q54++b?6IBMjN<+GBJWnFj))53@(8L!vs!&L_-k} z6Tu5zL^>Aa(nogS@T(B3{_kJ^^=0@z3hG*>{5Ae9K@2?2nTTJi+o5=1mC zG}3dgXZv}G4>mvYo$q`nykp0XPvE}KVJo>*RhA>j=V8qB(ZG~MLM{n;ht;0)x*D^T z>$OOmD!XT?cJ*HZIDy#w1LmW-+=D}~6o}PPB_>;mm>uO}wL|F-f}pNv|0owO|IOjU zhyUTjAO5ff;sH6bJR!&qvw2rJ$n)jWXd^r{((65iSEba$-cH2--uJ#2fx`}Gdm=tf zQyGh5-@(d_V?z-zU`2G7c*RY#k;$ZE;+t0}LKzL~8L*5Yy`G%G9 zE*6FI?kbmL;aE2%85sK9mE6;+VTR(+U@j1|vr23Qb&5kEK}d)RG*!-U5Az#F_Wysq z^wLXTd+4D@9MjXo{2X!wT2DZ+Af0G{)3XGD$M2}3`}`gC(fHWp@75!VdyV+BGk#T7 zqxpA#_tVpV_=kV^7_R>@Hae!HDL^RJ@tqBHv#Tcfo8amDuVexpI16*Kn68EZj861fC2bu{~P z_U%b;zPv+aLIh{P?w~@^484H`#J~*Qffa;-io=B8!E7UvUr5p5OMmuffA+1feC6*; zMo0T-CD4R`+(0rRAb`jb=#mUReeP|&PYc1f^%q}4ettW*WW=W&Nq&=?9f3G5gvQ>9 z14!36ib%D>k39JvI1IDD`60+G|r?nx~g?N{w0|ZZKw-P|P9$Y@wJ{ zLUEJ$VkQYjt>TXv#REk5;&%j}8OGj^-^7M6e`6yiL{N_jP$0UQfeWO3W)K1g2!O>H z!?ll2=???wA<)lL`K238#{E%l*A%D=@t4w#7##6ed7e1#( zA&`^%C}*9mn=fXT$*4^{VY^Jn%`z6X$XLXz2txp9 z?FCWb6sUM&R7@4VA6q^%>?=<_R z#OxC%2tkp_t= zEGp&VysBS8*!1UNq8&eZ@+A8ho>8-6fhGjx0$9D~26+6AD3{wO*9wsIcXH1ydDc&6 z_bvbM4_|e`*8KnCp5M*%ag_0+Q04{Q{czHmlrWH!Of?0G%5_ zIAbT2252=sh_3YZo^8G z?~^d>^kM%vSbd*j^@&FMMXAp&^gE2%It*lXMT*27vC0%?@s6+q2yO$?+cC>yb_ZMU z#f(0JYhG{xoZa1cBN6^;7b8C02_jKuiYQT`#u$`B5P|{_gaT7QO2HwNoBXob62LtH zDOOyB7a~Rk;sg1Sr57X2hz65GEcOZzfHGJTpg^R!KxJYIM*y{KZ!8-76vC~KoI7_8 znnlG8kPu|@A7H~)0fgC%l_^Udvn$h@<*$|Br#FrKn&Tz6>!_-#vOfLv(;lSJ`b+%& z@cbsw-+m_0ChQac)J28xA>ROQUHsVK6P!<}h>HP{!`M#($$gOF`vNsG8Y+~&P_euc zD3)#@{V-VlYrPafjHrg*;C}nGtg*VK23wP3ObUzvsjzs(2Hk-PP@%rTz->t%3{l2b zuDAh5X^SEPbTlHDkQf4UD*X=9oBhFi-t(Tq(a}*NKSPzZZh&F|MFA}qB)SYI-i~Ey zuwMO;(BH+qMttt)%=!%t4T0|N?yYd${U=?ew zLgDashYMvOP$|RV5;@|ll&690JrRqN^%dI=!a$9^)=(|sHLL0ob^j8q7lylLXS_k1; z{L!^**BP!5IS4K|lln*-7a!cb|Qf`|}- zb%B%e;)=93Ph{wnDT70D0$#ftS;BMGzp(s+qE zEx%@eu*0;4fE4=OHn+4`y|UdgF6#^Wr3AWzBIpokc2o*ThzPkCa0B29tVL^-)qtXb zNd+pA2+Se4Ct)f0NPT@hk{?gATaqmWni124fUkes5CM%axx;kz-l@hCn#a9H{A8BD zfQr7eXV2b)>ty*k-jYgO+48B_3ru%GyFac>e2l_dAUGwdj>Mq{vpmgn$2~3by02VL z1PkR9e$!4L#nADAE6A7h5O63l0TdeuUk_8`W{Xema!$z3qHbk!EHzK3OyKG3nLP`l zuA>wgfoLyoQ5=D_pc1#t8UC~ee6+p2{g*QeLb_`viv*ew5c&0n!)v>6c6>XOWaQ^J zanme6W5^4TRd*Ub{C|$)|1onNI~1_{blM4l)epM*62Uov37n(%9+gsa21(+XdH>^> z=^bG6i{zBIL7wq6$&21PdEHwjM}v^>VV56=rawrf-`qhrucmkU3FWi|I0Zl?1F(!t zVH<#mbQ*e-bHP#xL<-Tl-~~WT?XWViWbGlXo6|+y|5(QR@^HMP#QKnh9DZiTMwENu8}=CBGe9b%MFQ6IRQOvtPVg8nlRZ z=(Z;#KUsbvzq0K^-Zzeojn$jY<|lEkI=OD9#EKxRj&I^DQff_u{hz+%!KZ6Zejw$T zJw6>NhS{!2_PSc+N4_!{1k$@8^ZPJ6ai(7lHu{uiU(-L?xdm`XwnH?iCNZ#0%bg|N z%7Rd98z(u={reb-jMxGy3!UZdAOy%&K)2#cWh4@be5kUrasYY(B0PxzMFJ9mR8t{N zE#~FCeRY%^hWhGgXi6(|yEXD_wx7yA_F_RxOH1VZ`SW{V;(G$Wd3~nDRf;VJ>4ZH) zVEqTwtRGYH`1+pAd-~pcAkTL}q4#Q_TzWzUaxqvTCqoY9drv_zUsfIhPUs5S;84_R zpOhx(32uSXu+2USCnGC2a8j-GkOLA|4ZgVp7vvV}^7a~cA_t2q3AH}&Z&8e1l zeQbg0ULgLc1Y8$pWWzakrTw8a`(WuOAd8aKf8DiCzT>HuPI&G`D3hjrDt~e%A&?jV zacO`*!9$KIxx3_oG}xxV5lpIRMp_qgD+aL^Hi*Sh39(>3;ti0)aBkS~AK!4p4gZAX zBh)8(uw_yX@^!hsl=oisqLJyUHzdaf==P>Ve&&rYLQ;sS?|%2Ye~RPZzEme8_M#Hx zjPL1}pck_~qV!arJ=~-#y>$QFqbOKkpv>$M3lxPp^$Wx)%FlfZTW(LN!LI5;Cxo4ZH z?bpb!W`1~cO=IDWAK?6b*b;?~Juv%3q3m;y9EORnKY{$S{iJW4yJs)bSD&{0PJfL& zHL*#ab*+&nq1{*JygcI11=uS3MFs3JL{4`5E2TeFhUi2rl?)F<3y44>*-5s>GVX)p z#iimsjOIdRD&(RlGn_yhGD6+d+}!-cQ%^lbB0y@Pi2(Q491+lnl?^Ia`$cl&`zfy9sA0=QoXpS@fUF<(jeweuqZ`;KnG1W#2RVNr!~mUIdBM{l$Kk}o*@T&N z@(w(iVYeEuu(wIHJ#fIH)6h7SwWQxB^rZ#y%XWkzXC&vipxgp5jyP#B8k7s3P!wQ7 z5*#!li0IDy?z`__5mQ2kAw9Ej7_DlAPwlJKP5{_P+|nZd4}bW>X{;FY6t3^qA4Zu! zij{Q2{$cTrom4jdME~eJ=I^QDk6@tmhbrVCJo$by-X{MZD3c2a)6L8I^Wk+Zogp?3 zB6mV3hbJdOjl+NPHzdLZe}(8Kh1CsmYkRI1xuszh=#vJFw>C zH-GShAEXk2YX(HCnE<3iewzA}!Ve2bGMev4_&v+^)4ek=-7P-&^82SQ0Php7qSjc zIm}#P{>rL{0Es{lA^m05`-T^2Lv+;fO8(|<3CmY5Om@Xw6 zX?@^<2b%Zo+xL@>j*cR09wNV<`8DzvB3?U$>@AwBIVIAdNm9JQjBqGH}d;t?w z2i78Z7HbhuSCz~O=mzo}$NH)u0;`Dt5I_WsX8mW89}!s=tODDLYhUM0x`dFYFM^Kn zdwKwB254n3ekk{bf@SjKi4AfF=DjYk{HvlDvNwBmU*+sdMC(5*hFAZO7{`xF!A-+r zF2^KajO5)`c;yA-67|O=I1rIQSCNFqt0jKJZzDc)y~qX_aIA>mGO^p2v5*7t07)+% z6YHU;rEGXe?mOd<&9Qn3SuJv)X^ljRt0dwmk&Dm+3_}b&h~TbuAO!1WC@TSAE4kcT z1fk=GN#q|yAQ9IxoXH*Wb&S>b)z;Q_AQF{CfI}>Kn5F(^byuzES@)_nVCKbaM>6u0 zFsZ0M>8m(qFb2d*3?#7qf$58wQ6|9M`8db$QrbeVzWzY1{D-R%_I;%0 zLIj@|4uu$(`H~6&B69%9Gc|yzur@I})AW^EDC-BIXg#x6jH8E;YWWBdQ%EA^|hcy*OWJ*pH`{k4GHA&#sheT>YgwRMMEJzIN zsyBG$UR#g6&)zAm1tU`EFpI-Zx1#xl!-u9plerklM;pai)`o9JAd$h~MT)W83knLz zTv8OEMjC)sVZ_u$&Oju~pv6sBqO1lEKog;40zesx1fUR(K2t#cmvF3*pH4ne4AKaE z`y+_skAdyi72uwEC5Z4{Hx}491a|*0DEw(8=9~tT!PH#&0tgU!D7$m>O^b|zoASZ# z?VZ5v48*slL4LCQA&9pFXT{>$FP7LLyvqs@NcSHL5tsbQ%d9LH=iC8a&1va>TN%^ovs z#Aa!ga@hWzSk%#>2!P7~MV<|!hYK76sT7ogv49sIpaJPJx#WZubvXtlRuYgkwPn&! zo1Or$rOMSDIL_p;k(u=i4Q6`*a!!69WA`pNsZlmaMS6}tZmJ6GuUfg<1VHyT`9E%2 z?pMeUjsN7Wx8C|KoZmnQad8eVu}xt6T^#^^cIlm_zG1NZr~I|@zb4wHFKo-3_!595 zFtK4G0y3K>2gNuwB8CfxB=+XNN!&Xn(NZ8tc_U=>YCdtP@EH$?0~Bh;7yed?H@_tX zTLz?X3s&o)(8gZORPaiQ`UZ#v_9iUxRe{xj%T3~aZa)Y)l!L81@T49R87krXsm%w$ zGEI+)vHQ4~1};d!;a|wZ-Q{wfzf5+=+oUD-exSP*e_TZ<@fQWb=`;+=v3R${UGM}v zIs_O1Hz)D!;2sRY5r{3P<)|YforN~Jw`7;xf6ET3t}0XBgPDjEvq*)Z`v^=qRi+_w z1Mm~rfU*0p7{iY}`|PvYQ3wrJh)?8a;qR+T1g_?s;ArVy&S{s?c2U{ z?%Z+e1IP&w`85GZKAr{7l{~-~UA00`a$_%XV_P_k9CdYd){`d>HR1S6*c9?Jg;&^* zWSy}0t8iXk$WWNI#|78V!(jW521?~TWd1Ck-x+Foo1ErM5BV0rQ|z+I@0FsFekmUs z75n&z6rCHBJs0EB;&aGGeDaB6Xy!|y!E4%_(9)}wb#Q@Nbu4>s73j>jsRM6`N8@K@TFfaom9rX_uFn^i=FdaL@1?n11;{#&%c%*u0Oo}d|{Uc*? zONUqX;KdC<_%+D*Rs^(X!q9XDzI@_>C_Y*?B@+$fQc#a}J3%5y06>U1^3;+6NCd*K zi9u;O+3l6?*pM9U?~sUjAgfT_$1Q*AUKd``h=ll9Pc{kdqCAonknW*<)y84a&kk1$Qlp;+l>6rdLSkk29JpK^)E=}uXv?k zBM`R;U6&r;a)T*)-)KQ1kFBH70SrmRJqGemZW)y_YcIqSD)tOu^9x`8u56q%%5RRf zfyLh-wX#{7;0T&PS3R6EzcvgK(`gtI?>euTcVn6JW(4Y70dSPXQ5w-n&(DpwCZU2+5 zCM=OnHPbt+5Lw-$(BcDmz~&bo_z!8Eipc#V<+2q{Pc_hrZwPIY@)+k!3*=-QI=}?O z*Q7jYcvU91J|eOnDi;eSF^oyd+g>=w9QwXkhM$(&U-LtLN2e9yT6!E<6u_wyaMYU- zz!ef7?DJB&7Gg$^m<~TLcfN5<+FUldK3FI1?hi;Q!nEt-h0q4u!7g&H&%FVN50wLk zb23%s5ql%_0vve@6r;reLWd>W>O_799Yg=&Ub)z{N$$UAw>TZp{;RZMsg=Ow2`iO< z?1V&-X3SXL20sBu6~^>GVr)P5`s=S3;fYiNz)G&lP`w%ifW4+SB0t-pSbrp6j6-w! z0sMX!Hn9G5@kPd7=IMu{Pc|6Qub(UM?1xM5QAF}x#Ok{5h;&_=#iuqLtg^v9AvOJd zQZ(t3^07&&J|B=K4`#0^v$V$xpbsy?>{$l%(OnRS4m&8L2#h%dM?G&9Mtd1HjUf~t zfRL8>Ii$+E0OW}Y@??MlPubZ8(rQ(pE)9Xy2G-?@02ZZ zhcu(rHVhRc?aEkHrVA0^o7WJKTWc6O4rqT@<37oaP- zqFlh0CII>)xlf(_oyU$HBSH8IHex^6{Sd^?bFerKgA?HFpT1Dr?}mGCSD;G%zln8N zRo4MufBmZT&s_6o72?Bp9dfb(NM^|+RbueZz>jkInOCK-?yMBmPXbxdMeL>JD!>+V z8QSE5f)9iS<{c>=?3WwfJS2}rJ_^~s3Mg+@ZB8e7FVqYw|GXe@BUn-BKU(*Tvpyz8 zrTBmxhX=u605ep)(<(#VBQkt(LPF0+q zR&5H?+y`5K$P0Tc%q*D--AvtBVDn9Qa{X+&RW1VgJ#XiQHp!Axp*IN=R^KTp>g|xm zlZWIU7q#IIY4NtmM%P9ujoBgD7bxT>vz)9EPlhE;V|(R{ya6wZ@D4b}6u@k)2Q!i1 zI|fU^PsFmeTWrlB9qhSfEPRz2M8y=I5;=cJr1=J^o({?#k#^`ND5j7(TzVk^7=(hc z*ES-~9nf1O(YBmxB@qA@U}->Je^VRf+2Z>LgRLnq*$ z>V$c)Mr?(3W{mOwgR%bpZ+`Qe^ba5xkSq?cNmo=9xRL}w(MfzD_nbrcZq53~kkjwO z_`Mq&W`F2xA@4^Jf31+8w%Rm>$j?=IMnM3&k-qCJ{LFno{woT>H0@fEQ)I=V4-wy# zn0-*f4MQv5+bGV9 z++wK&8FXNDa0D))7|FPs4dSYBOYi6~oTf}NjMxH#%4!9dGEXOf3y2_$A{|`}@dET< z1sAZJV;yPiezqD!fh$P>2y%j6a{v_PVDk~@{{8!jvwx0FnfxODDY*J}!(H?uPNYYE z-b-`eG|YYfI=n*;V1=GDh~>|GH=nqM3pM1U-C};`pQLrzCBN2blRfcvX^6E+Q}iaK z7)#9bWbt#Grm-TT^cpAR>CMIRRvQ!mH7)3&q-WvqV+;&Q!S$ms_dzR9yVi0Sj0h7_ z_gV_a#8Emafy3oeHd-&&Nz0Pt{nX}>!#Qf`gm)hTf?Dx1#3x)<0SFxJ7_z zH@+8_ZLRARCr|`Vz@+4X`~E`g65 zubeet1$q?CpI-=dZv4RH+26T+`}WE5^0IH?Jd(E|{~GN5%Grmj^Tr9A`5i_G@%#yx z`Z}Q5eie&y4kFU;ZHxT;+QAMfJoT1*=3I@ehjY_ztVLLbncfLBq1#I)`?msBhJQZD z#^($J;##{wA}yHxlaZfea3-S8Tndt62XyCmMTVLec^dVaO5@^a4NJ`nXQdg6wni|6 zl>INK5c%o+^J?uWIaq%duEtnHkT(CzDR`XbLlZ=am@Ot3rg|g*QOWU)RUW+eCMhm< z!tBQ(o?MWoE`)p)nAEHV7069!H-Wvfcm`Li8zO%^sGpzRvkpF=LLCSyh`r#G^-i12JAk)-j;&=gts3Apu;#M{>qw!`Hd%&3q1b}(9WA2 zko}iS>z`bI(y2sHN!F?ObAJ8nU#D$PY5nQvAM%b!aHjRs@*n0yGF}CJ zRP~y z(YK7BL5aw*-YkJlJ~`5QT7LTKJ~?po0$e93(WVrP??~7yp0U#~bo41v7k7MR1_zut zCQcAHbSpK^;MB^MmBt(mZjJo>I5qoYx$fWxKJbCx!|!VP`I9nIVyc@Fx{O6!zSZi8mr3C1|tjJMQppN4U4pdc?J z1zXOojv=-%#j06zCBY106Py6Memn{Sw^nHLUykC2^6v=b|4?l}>}$C6*K*W4w+>n{ zOz7z1+NJ|LlzkXWevTOm|3LWyaF4t2;mCY_-HIo;DO zUO((B(Yc%e6NV(xjAN|B%uTBRINvYK-~tJN<^nXntWb+DL3agc;%wz?yx#bpS>$hN zX>maV`sKuR22uE7D?Ja{2)5uXB?vA5%hPM*2cvD!{v)QJtQG~Xw`(CM1jiWT-k(Ta z&!B9IH!YiKYz&Dp#%vG-)?NqUn|i1;h1>_Z0NsmeZn@l3q%on9m^7TPk`KOhtF#8I zq1m{60^o**qr*8Q|JMGxj5feGpKFAzAUaWmDZ9-kUFCi9*RT9Y&h_-m#FRTNc&HEz zOrHmH<-z!k7>EnR3EZ4Y1T^GVtmQF7&3$c>WS75h2gG%EEJ=4zf7zNzuuRTVI?^LHd-S;rx?&jM3cV$`t{h~M&yV=`14~WpGW|aYgrV3lUTW@ z(`}Ql?mZ8J@hvHL>=ox0tloPPDZ$4I#nV$M@p@#FVV2o>vMk=V(uH1n=x~|n7wI^V z$fZ|OC9?HhOK%UM#~_?@2V{429qi(WFJC6)CpZF_WCBdw=Pb_LM&<&v7NBc@Qk;tx zD3M8My1m%OVqz&binR{@16-dwLt(Pe_<&Jvd0~s(JiJ-f#p{+$#5pXTa>~&ymNk&i zFW2^;q5bJjD~k#E+oKg{#R}8(?(=Q3Wz$-*+lbRi1po~pfe1~4w&Er%IaY8R))m+e zJwY$-BCb%2xZ+&EN)Q0{xZX4YP^|x+J$uGYCeuISy0ZDxLy8;#7h1?vV$kyMA1{&v zeK83f{U<5D`K%OfjEK1e5oB;q2~WAiaON*1czA;Z_ijTd>n?bE0r?7Hq%8nJV1fyT zwvsSV4V-qi%k=i7^PJ5&%OiiB+6N%Ad8ZL3hP-m;_8}qUYmi7r;cFfcxBq<-o`!6_ zR1Sd8VfL@>IwzYCyd~?y4?!-*Qq{{y0H`F3VKtnLDt`7L;1)OAB?7yAj5B(M5)H(~ z-w~CmBby{N1=!cNi@Ec#*v)&T;(iC*Zxf)O^Ej#tjRFZ?Gspw(-LfOPeul%DbJwDO zDBC~C+jDCV$(hzJu~)$ad?%hkFg-DT11oTH_?uaFPlZ@htN zn*RQv{FwbC2$ke|>Rd{6E_@m^%+Ex|W6 zj{6|{+khMdtSa{-_7bZH*L2V6qtz$!h_(>&4;) zVGdw%RzDJelKgWt=z^-)?Z#=N6hiag9I1hQqZI8)zDeJ_xIGD*58i)+WfL-5F)dA8 zgyiz8U0fpoSjHXrN8o5RIwYPzKuTb~wjo|%UQu|Eum}Jdc4OJ`8z2sJ<38dHkz+-< zfHW0>R8AZLL?eCMI2vt!U9_I}BQdHZ_L$fhxiyf3gr3YSs&r`yCp8zkew zJcI9}wtrp$fE`7U>5C;agy1ZySdt5x81W#_-a)u-_m+q|{xON}em@e4f&kbGC46zM z#4a|8zw_^rUC1w1al2d>ZdQ2;lB?IpAU#SGmaAJ3y&F$U zk2tQ6N$F-J{#c0-t{azWKQlJHNIr6=sZ%fDd** z5Zxv*%xZCy9qg?WuV)AX2nxIj;}|V!eF2!q3`VXJ2+spUNQ|{paEV26q z5wrtUAr~HHTooe^ZXx2aiR)yogqt?O?;P8b#0~T>MUBn_QZ*Jv5|0L;>he!vB@ih} zqNtZiILP6o76KP5_QVlo80dqq!1S2P&tO0_T*Qq8t<#8#+vk9>?QRK`Zk1@|uYeM- zhfV?9E3F3=Es$?_i{}hrWQ~cnhTImw3?*S4l9ThbB5CTZleB{;+~7y36GlZz6qjv#;u-?#jr%lvYEg<}$%5xxiJ=D3{i8ITfVVOj#9 z#xN$GFqXC>Zdj~Edw?r#4u=D>rQ!mT2>_9w09ZC6u-pUyZBq>-*twB!wIdzUwB2t1 z6C9)Iapmw6R>3};g3^~DW`8>UyoIEmW7C+8k><+G>?|4NImOL$BDbaVI6$RDag4e+ zoQ#x~8U%v-CKN5)~!glhdJ!_eXF^&snLMs)5_@+O)`#Q(akZDuJ!N7%Su&uymFpIO*=C z{sifN!bqe}czLt<_rb*% zS%g$UUnpbGxIyZUR><0sI@u!4K`NxWe*zM34|5(={W*hdEBS5F3H4-l;!X+4(9_MhCE zdRP_ek?g~K`ZWn}*nxppi6O>rN-CVmouv}L?Gf<@zb&$VNGa5&j_<@;9GfKiz$cKo zu?61>aVi=430!g&j3%V+0K=AWrXFGP2#Cl&oBV0d!_pS0SBrI|11V+s6PU?+u#^W8 zpD<9wH>r8aheUoCNJh6~M1H<;pOk>#v_M45)L+TZuGF!KoGEmoubw?71<*y^zP_C+j-#}SL!Z&nvTP-$?bjMzEV<@{qg2>@S8#OKD5 z#JX+B^XEgv(`RrDc^}!?F!M(v9&{Ip+Wf*uzW^frj`>UFHE#u$?*da^2xT6ZsUrPb z%4chk@pZ|^^MCS=#TCfHRFe6+8zm50k2UYw!SfLLQ(lxyt<*cflxXfbDcb`z(ikfR zAQ!HOgP%z+AWcGO41;SZ1MstVZ3)cHYXWw;yE80r3?d~cO{nEiXrvZeP+E3EQw=$F zx*E(6X8-z|C2HLOj=mFO?08X%wnJCah&33|-Ja7BX^yUuO{ZGr zx)2h1$II|_^S@6i@-XqeEJq;(#H1Bp#3Y~#6)yWV?8JJJoAI&&%sm{5SF_;#Tra_2 z=NDI@SH`EkQg1^nN1Dh=`T{VmI0NELNFN68z)u5rzSh}^#19Ew00Dr}rZ9l}Whu)A zBKD%*Gyxz#X#et;zYHyte4MSN^Ft6HNY~#uHSB2$&3@Bh{ZApg&q1u^7R7IcP(@%V zm8_oTp{sQYpFmL}JOOrfY#nAr%>1RCddRuuT2Kj1i)zsetkBbUMr<8NWn;8P819=( zApsZx3Ft%WtBY`fVT$jC3iAjwB5CD)eKx7;?G^J-7b*1o$7nvSgNfB~w|HX@Bi-7s zN~9IazODBlcOVFJGV*hp=Q7-gUNjCI7IW{jQgj{Ue`v&`ko%2?t+M^pdU>e(7Fmn$ zqiHi;!3q#?w31^weHjG$ zKQD-?lWq`+Vh{kVzPkViK<4lWoPUnlI>p`!wJGP#t6XB393ohtG}sMgW>tl}-m(Mn z90MS|=?OHI;vwe32)ZR^G+T)~k3Rb7%lHg_4gCW6AgMGVzAVVF+yr3G>_21r`ve*b zg_{SuCY|Gt-8H{NppkcD3GbJ^<=}SRJQkI}2=fr$ zEwRe&2@_bV9G$6EM1C&Ob@1QCX?<19&WmE&a$Yu^E|ona>oDvY_`5LMOUD<+z3+pr zoUHRUf%ZMevBCOl;wAF_$@S8RRdK)f!V@yO>)jHr02jkG0rj^K@I-oUEJ{&{@rV>< zT$mFk9r#1QQZm*l#?Y`7HN7H^+5z}PL}hwkOg5ZslIu@xkh?wGq!}}R0{PQ*B#0?y z{^Q_do|M;R9T0yLd>{+)L^eH0BJ+<|j@5L@$)<}+_Ft5qDDhRx@;{+uM%VU$kAVZ5 zudhJ@<-4S}dXKznX_W^d<{6Nrq|lsUQCo0f34H)e%ogV-fI~lqNw64=qb`6J0pi#! zYT)>?%5o3@_9QnpOcMY|K4OFNuMzt#*zi#x05JbC1Tr1*B02NJ>1Pt`{~@sdqlo-d zg*9{4S{JpXxGUYbN!)p5|D!1pX#PXvg%Wby3xsJ&u*A7GknA>m7YwJK6UTKg!((k& zkp5oQj5o*)82VUd62K%lvzLVDn_rG&MO!mWna$zaoCyHyCvx54TPKx~AvyHsixMqs z5?2TcO$J)giAMQIV3;WCi?*<%LO^)*rE&NO5_yheZi3Ur1jLu2V@Q#WCAHt(1NT;B z;PoR%<68#VbhcF<=)Os|#+xyfQIns(6N$(JAOR0gnpn#&@6!~g&QKmbWZK~%d2xWu63jCqX^360`Ie1m_m7H;a8 z81DEr8LQqPeoLJUg$Km}4zbV#&X1m$^9n>tILOhIYAdYWLL91ZijCEL;4nOWrI52Nz$tZ7hsZoUV82t!hQ@|=7mi1y@Ih>Wxdlq0{w{~oB6 zA3d>Gj+DPFKi*j-p)I$;o(~#c+lt`_>O`vmBQ{UIEXL78Qfm7UXxaFAXqWIcw6CVidnQ6C-_5`I2CO9~s z&NesO0pI07w>83b`rUzc*)opRf{(?dd+@wW6m-bJs;6bTvQC19;6y`Mh@|s5WD7nm zrt2_M!2%K<#@Y^nW&fTp=NwdQC8$<+s2^8JZkEaqc@+I zi*_i&0M-UWCG;RzRAYf2hc~^PFkF;KRZwizS9o-wnl_jQ@X)pNUqj4+Sx+9UBb zyI_fc5|{BPGolpv_ZI`j62$Dk2kTc9nvrrn4L46^IrU^r8iKV29|tb|&p-XI|Fsg2 zgKbdeGmUR*q~Y9>%jFUP4Q=j|34r-aU;N_jIOj~5Hv&)&W98HgtNYOO7Xr)QfmM7@ zBE2^)0dopxAKKM1DAE$mIX7RSA84Wlp`Vsu5Np(*kXU0|f-gmKPO{@L1}=jnJWQcU2t=P*nxHUWW8*}H*M@5mt);sNE<#blVvAma7~N2 z%HYhx<;TYNB5T%Ee8x6>9%I@clny>5~whf6ymatN{I@2$Bjq$~_6elFH>00KQZ=hI`g$!z!pAMEyO;i^}u|)>OIu@AjERnEcJ0!gcCRJK)cMK#WCrVQv%KoGO<62f*%VgSEW^G2LTd71s}6 zL?|p8M~4`$a}Se_*)}4UdXHEtf?$(z36lXc$y(Z@VlF_oUAPpROE7q#CAah%p1Mann9bTIhA!=Z`aUyOZ zvFs?999t+%(g1=+9YwY>g-P*3;h_9%3syd^ zkBc>zb^o$exQJ_vkaWL=9|81KW-1JvQ7^+Dj&mrkEP&5=)KU^33lLznrrWj=Gc1c2j(8ym#lCWW$n z`qQ5#`~L_w5CDYif;FX$GgI+H=0D}FmT_qQ>G(6JkhWDe!7S1)fs0Tq6(D&+5npwc z3!2F=Q%h+~O0IW{t@I3V9-oitoQ64rAp%0>1Hl5KIHQTox^OF|E3--|jTi#@)$?;> zU3lh{RocQ0Kw(gb9FUeWGri>c5Ekv)c!R{8;E*6^M!*TYQ2DG_kRWBVw@D$;;)wvh z3*E`JgIS8fuGYXdjUkEAR|H0kibl*_(9P1}i1(6vpszl~iCo_oK#e`dG5OcV=j8Ne zu<*BlaE1+1?kSYrfi}g#EW`;h@yBQZR^FlWPa#+R4Z9hjKxJ0-UM zekg)Lgy}f7K>v*)js0FIND$UXfB(~;{^CbJ^BIZ( z$y@;02O`W>;Q%zIa<6B9HqQL1Pkri6?iKrw4`J9ZG(%9Ls=3 z>|I1MTD=oUmvnd9LvjFgk{K%i*U`8M(1wl(n)?{+_=hWef^_vV<@GAW%*C59?Mr4( zCUgWua2tYlL1<9)h|`}kb8F5!5-{)*(qS2pXV)AMSKG8yY_uWCOIREp2LzG&1@#7e z**K`sq{A)FCPao3bW3ee&Mi;e7)9cf@R&(_V_PLww?m`}#xCU)wQvJmFn3ebbt`U{ zp{E)rXw-|3m@n(FncgU}{37J^-{AV&n~4CF)<~>;qfB48RRTj*h(^P= zF6ndm#uX^|dd3%+5UgY>0!0Td(qf^Yq9K&LpJ@U!?F0rQvgg8PdAQ>il@XUL^+JWn z&#>2LWxwn%9D%|K9*CTIV6uxt=`?ch8Jx?+ASbcS1|LB zzcVbZ!*EpF{i`C^-38dQ(+QP@%QUP3CnHE8iq))#A?9Q(P$Y+ZW3akTp=%BI61Q+K zUZiFe;@stQgL>`d5CHvhjr<())?K@HQPuw_YbW~>r{e>VH4|*;_B#og$c?;zP>1oc z`Gu4fiz~(|w!&)`aw$?yQO~xj3Y)IGMDG`9Aeo}ja122?Fqwh%Bho0WJMMcvVGp^PEdW46LcG!EB!RQ>BSxJ3d$T%#PUM_Mk!Chco7 zLpbg2^G@=4Zd(4gVx^Py_zmqpH~_dbDzBz_k6k)301DWTg+5}SiWv*#I$8mcV=ok} zNBSuc07jWzuI*ao53pw*}~*1qMmq%6xvkrYSkOeUtRGwM(2a_}W2&grKHX zdNyy7pWm@ro-XW=eWniOEl9TeY87%V)b>;6-)BD~Uul0*etP3;Qv6<+QY+DBe0m&- zTz11_a9ht>wKf1nk4%L`keQ9&Y&|1K*TVymp}$v9HDs+ZNBzw8rhW&~+DIo>wc?h!z?B%$fi#~3e$KD|gTgHmfMh*DW*}v*c=ie@$x;d_j^5Y+ zMF47QYC?!*{!pSqbU0*xu7Z+{G9HKBpWA{f{7}2TW}A3_*)EZxb5gitSgd9cfh*YQ ziSJsT|4{OZaoi+ppKXwJLk&W$d$t)b`K?p%`afv8D1r5NLH=KdOYDl|g5StT5ZqHH ze;nBc@*0@J7IS!6_d zQzoB$NuoPH3gX+2;3>?3N+if!Zx|fF^UQT&h{9|NIA9Nz@Vp12!EuQoc?~0Jtw!sw z0LQ*PJUpCC0Q8r0Kfi)`HO@V;R06Tyk z3>4vwR1Yrv&Xk&S{>fQ?8Z3V=tQ8&RLHWhz19EoDMe(+Kq_hG24rO){a17fplxo5L zs5C|^)vCwYUcyn%WFcok0Af|l{DXQfYaYz@w)EGi<6*K>dlM`@7L0X2M3TtQ;1qQp zF#t%8vUaN)uZhs``E~Fc#-I!wh9Yn}QYfV+kC@Y#1l8(6Py{l9)?_ul8#wm&AONs4 zD#-Dx*?~*$#HA7d{Zcl78|$(D#b5jd3Bay|^G{Ie05X~X$O3s`UOF0a$O#aDoJbcv z0-LUf&wL27^UGo@N4l0={__ z6nwDjEL5KRW3nyMlJi=4RODTNO0NT~^Vpt;CC1sGNS>|GGZFViw%skq>e}VhILvOx zUXgoWeM&aMgY6DzAK-GMq7N5xy2$8h?0RLbtVJwHwxz)mT!l|M3x?(UTVIvBI*V9~uMPpw@Zk4Y z;Ez#qn^g)uV^TW&j7+@pO9`2FNwDs>U?sRG!40JGQSig^b>3eqb@owlz|ksQiGu({ zu!5GwQ7P|v&wGet7qAiMhMbjGGq5D)i%acbxit173@28MIXJg& zpe)^qv={xzx*My#4p3hJ`Sn+D;K7|bR9TD2MZ5Trk?9!BP@_mWJ~0}RrojVJ5iqF8 zyDH_0U{yAMM&Z$$kN>HV(@r^bLFOM5kI*@YGd*YI0XXGMK|DFt*d>D{i9q_> zuf%=^8&nD~%JOgmE8Kweq~3E#AOEZb2g(uH)2bZWQkxUN_&*;kl$)~Q0q`hFd;(sX zEv8+-wUbGD0F8@!zbK5zZRDl4Iz0iPjq+}FD}9-{@FARlGL<0Ae%)~XVFHjv6}nkk zk*a#c0z?7@;OFwwuaQFYWf*}o+k2X1`^EMd0zev?z3?-MXh%&wa^Bg52)*?S&;H3( z5=ofYgBzTMPPbeyXU6*El_S59!hJ7D^~9vy7r#Na$DtpH7fU6!(rBUB;+WMCr))(( znJ`F=sE2xp2nM<*?w4s}2&?c05i>9)Z^lkZF9LZEY(E0gBO-Q0^cAiJ(px|}_=#!y ziJ76eKuGCyk=zj9pxltt+&23qBtA524%;WBWD~@fE9m?)+lVX&^kp!X8>I9$0}#It zF%93B@P#soHr$y=xt78Oc;N(hG*BoHGuu^$qSnxW2*5QeU|qWh1mNq-r3Y9f_Nf-K zf4H&5+!P1!_~Vbm27*v_lo&*S2y*{1|9__90Rea;fPC@*z@iF5QsZWD4$x>vg2xev zg2gzf2go*R7WIOay_s2J0vDpvHr*&U$2MYiWfv^mcsl+JnmzK3x^_z2ay3-+o9EokE5F>;N%p5>8sEt zK0C4xVwPi8^@XZ z!F$kDi&hlI#MKP1!AWp$4DrP}e}NJVJP-gbt`a(pxpx%mgkl>q27w2#gO$M&?cstA z5-USLw}K#*U|oiQMXDfP(DmB@Bv2*OCvvC)9*zOK6iyUC_AdlHIF{2Fvj0qa+FdXr zy(MGty2QO{5^Sb_`U;=LH#2*@(TR^_!jupgWaYiakG=#DID?7{oRt@ea2XWm00Fpk zRks;8A*P0efRpQg`7fVs`Rr%E$e_gmh1wmk{jWg}5cHQ>n6Ch7y-aNZtaM~h z$vc_AbGC5$CZ1z$z~O%gVj&O^gtnj*?Lh299b9+8d5s-3iDw!Sdk`t4X|u$pdtnp* z7laLm#MT5ettJAqm0mgkjX*#VbPs#iO50Eqd=!`kIqChEZdFGVfyTh8yx4wRPHyg$ z)-s4Q^RXr6sjK&st0af%ALQF6(bzf=ZNMp|!6XMrlrCd11y6uWD7Dg%#knii{6A#$!f(P7gDJ@S8p45pB8I8ngifMljfA&+T!O}%#d|seSMZcNlYY{69!E&= zJ&|p)Lt3*UKOdtT@i|k!ST}LmFHElsgD&Z9SMU%pqh7;xv`7Yj1o!n@eox{%AI{3P z4Z|gP6dM@mv_+ZL!9~QlMWanKI7b4&j??(aXBP#P#S#Gh0{uchZ}$0o#Q3{-QO*90 zVB(Jq#S2!4+mZ`STL^lI#t|44tOB=zW&r4`y#$dtCIah4d$37LV`O(1?klprJ}|z6 zSoW-=!Xl9($dF52bVLJ)qYUd07~EZAE$RjLggFRYd#0ioImR25Hc6~{r-VyxlAv|B z1gDxHB0&7|!C##@4%shQUol>@RYGt!3S2BkE)@8;WiSTO8!`&9qCq+TAX&l!@Sq-~ z*N6vbcgOPMtFch0!4>cP9ZvBN)k_F)iq~vTWLwU{wYk6zyI~s7R=AEP6NSL)ai`z! zXLcaX0cd<&ctEARV6jk4ei5G~^)Y|wLm#37u$}(@H2=jAz>tZQaqLaP0f@_fExE82 zlwrBRXGs+XFa{w(v04kMAvSk6Qb(PESs2JsJ`+~EP?PCU(+|7)>BdqycEdKT!&jBa zHnY%!nXa<~kS@${@)u$menBek84+tWSaqznoVCyu8@cV&;vpN6`DW95Woq;x@ebS| zfl+WISZ7g*B}^vTf|Y}UJ7wbFX3T_G69BC6yn<6vM0JMGiZq96Aq)6yR#a z>ys(_A-MncV_S03P-;djc8OKoC!dt~de~k|vs2I|zwdG%M0=xHP;=9fMp?VJLDod7 za!%JpTl-OHy$6u9KiaktU7lsCUZ|Z|^_XeN;0=eSdQP2?LQM7MVmzb!jqm_baP~W;c5fY4 zD5?hfBcLfmA@Vc(Q3qU_f4TXnSZYJ4FPAoFsBk4tg98o2pTT>&Kqg;nl+dm(NW2Pp z8p<6&{HPrAFP3XFzVLdTF&p#r0d18kLz z3$~VQA$1gW6XmjDsvf~O%$&3E490;^#n(CWh>R7sVBwLv1m}|kg4_;?ap1!z1|X|< ziN(K9?DgG9MLvlzT)5>f+?2Vmq4j}-ny#+=IC2%qgo&a+VTHsiTQS2UKN8{|k_&H- zBKW7+WtA4>5G;r>C28iNNH{P6YSQi&SA$#1koMbX=FnRu1>eK;VAMqgMye3%3wQO} zZ9snXSB}nF<5820125x`$d5fGybb!^7@U7-sz_j?KAYI{lQ|T>0W0DL`!PV8QwB3^Ukv;y8!3_d!#hVRG`umC1p=W06Tq^2? zX}kwI06)ZI2bQKc!p~xE0U1Qv^%$J4NN`OiBXRB|HgnzL>5q^{z$y=B(pHg38SwfuqHZ zV85`YS}NQYQQb=1s%AT=NZqf;km#Zkl#)q5bDO=!vEJ=D>xA^)`k%zzx?SQ>uq~-j z<3Ds3HvDI#wB=YgjQiwonlOEdBwK1Sc+4 zVAg@%ClLd{5i_?i1UMMOa^G|W%Ds(qD@p#PSW(FRP0&mOwS4CaK!DJ^l!+?&kt=;1 z4}w~|5cl7QeE&Y?{B!2~ z5Aq%!f@2rBHWk{+-p{2F0T{;~uSOk+UEnA|or*xiGEmx8EEPi~D(`+~${50f#SJxL3qz0&V5g0lT=|L&TOVG-DY+(Bi{C7J%OJh zpe9%Y#N!GxizDv3I*@6|`jE#X4UbB&^w+V374$T|%rN3C9fH%+_%ldY@l>_AOa7aL z*FOeAy9Z6kvG3R~2;7R_{0J6L-6GR(Fh3+xT+v|*X0qG;*U9zaR*VP^BMzzbg-f4x zmv%@X8WCr&%0QH{0%nZR0?-O~ql-F18;K(Q0|Bc`RydY_`812Q z5}9|{hH#(ltu8~IhQM?M0;MJI(4Vs=T?L3|2+b|7T4 zL-iJ(SZlG8o%mj~A=$5FYPrL|dPbE1aRwB1pSk0;*NsSpBMf-$JN8H~Ag@zdH3i$r?hAAVK7RM!-vC?kR z0wSLPl{wfGMt0$N1%u;Mkwf>Ay1w|YUZ71cbhf>F_d=BASM*^Kbe%Z^faX`#(z_HK zqhX_kdp+2sBrH(p_Q}#)uge)=OMxyL4%FKEAGF$rn8^S9G#}!7-?R(X(~O#P$6m*m ze+5WA^XCbHY`Mo`15MWdbO%9Ip0c9mA?yI=jHooKw0X9JmQhGbp(`pMpV5vXpl*xip2gmp(M)!p zQ$hmu>mgf7FZTTZvgWhZw&`N4)yFDP|Dh_(Qc`Ttw4Eu9+Di>sj=s`h!M-Vihz?@} zgwpUzXRh7{_anFL7;zaSlhA7JBchKFhce}R%n3qFZ^bYOch`~$xXqHcuT9BkvV6x% zPHTaj#U3Cx1(15b>IL>1*p0Bc@Tk)(Dl6^A^cOjpClm^`q~1u+$k-%D5!X3`p+hbV zm*er=mv9hD7Lqey6v5NvBuJ7KLz#Nj;_F$2|1?R^{f9vSO*7Rb`(6X7rS4k3F)68c z#7-7XTEDF4$|U^Lv#U@XRtbx{_MH|c<$7eI#A1CHEFOv?u*WPHufOT(J!l*-Vp)Gr zO73tqtcTlVz9Ct&!DjYXS#@WrZ5?Q_GK_yhIS5d7<2Z7Vet_~qV?D`J@q+8`x8j~* z)PNu?jqMe5i;}S<(G-OVtQ#Fes z5S_|`S7Fua_7Qv8|4joQnd|^B-zL^ngioc7YP4K1CXjiC|kwdr;Zl<)dxw{k@3S8+&(XRivaO=20^IM2A>G&+v`oRTi8swEIp}*;XR|)IjX! zBmGx1<@bNo-)Z6X82;3*Sv??J+y|Pt1X6J{1W-;A;>uPamDyIEmiHW5Tyy4Q)ju_E zwWt%7_m2Q$neUrBE90L-cG6B0a3r|~9|+8#6NLero&JoCo%o^^_H-54|}y6_6d zIF7SU47-Hb`uACK+fSw}_Jr)}$Tu64s1bc$PD;}^E@T#i(iaRT`*G7|9L`Cqx3Pvlx zHeJ3;ByPF7;w)*m&SN=<1Oy7&gmyj<$jhYUV)^L9TvHtuvO{nkK zXc;cD1-1!3yEY-|KZq%hB9qr4@06VjkPM;4#e7e!aWb^<~RS5r8UmU#7j#Q2uqyw|zxz)I0Ml zLIA85;S+V3ni6StCvognV{WU9*|dmB#i(e+;eG->9Dtl0uCbZm$IUkE1>w{qwMQm; z=CBoZ_1HrlW7dSaE59PuU&M|Q?&_QM=WVvBmC2d!v-!Q@hTSzYX@!Hm_V|e@+cilz zv}6%5v>383w@zWdx_uM&?5&MWbp7OY^DqM=ob!J@Waq4%ciPqhM;z>(whP(upf%b##Cz zxZ|u!Jqd(IZD2iukU%mZ1uWj+tz?DtF%aR_1K9ppe*ldNV29^VTTL?P3 zJ_Y>xMu%cyxko#ZM4J(-X|a*+@7v7y+g24gVj*PWxk8XRRq*NnvZ2cRaWTH|EZL@! zTRr%R)Cw*nfW{&=e!oqR^k7>4BP(boU}*-Ga&=HbcbM3QBqvD|js5TM^78aGi~n z?ZxA4KN8~@yc`ebi+9wqYy$ZB4DOkOWdyuHFoQk+Y&U9}-dil;$H%*T7b-e7QkR>^ zbrl3N9wvKrU%xeV^%7oNsW$TK9vT01dxmYGywE0F+CZyUH<_IFT+JVc+=0*0UfLZ2 zhbXLE6WrlT=k8a8AZ>Bh2*_z){{?GH)DrctBquHwk2{GX^dgaeqBUFTXIAC(C$!A# z9Be@n4fN~~8lSO%g)hDdV53Rba+G6=NqgWeOj_|qzfD~@WpNC(q9gBe)T2(wbPUSk zrJG2_c^Bh-1VQ5%YR9?QhH3RG24#R?sDUsJc~e+fPQnVPUHMu{W*HkzKc~+f2v2)q z=KD3d^ho-R?r-g#>M}o?I-4&7(A{pu?r#r<2ztRv>fm+}4a>Gm@3`{Pya|C($OixJ zt5!)aJbx8IFD0W%|AH*Fi?@$qtv37=HfZBbHaYttNc%gHEi_tkQwu8vjeJD#sA9%`l9vQ zlb%C1)%bIc@Gm3Mkr1;O9)9opEpn;B`oHs{1#0@tL&);wv;#^@7Hsla<=#_7B<{7o z7og(y{%k6rpJ@ITkUUn8gHK&T9&iA*?@cQv2BD(-x<&E-{X{{oeDJKzOjg*)i5JXv zV>@w`vH<7`rl}@s9+MTcEEqg^@ZjPH@_Ja`vO?f>K7YRQx;j?E)Y|G?SoRN3dOS>& z`5Kme;>vDN@{1}=Soi$8P0l=F_QR*G@?rS7<-FiDhcCr!{B@6w6@JFzRY;&4_N6A8 z0y`)e={!@I;UlKWb$@EVZJsE!oym28zQ~T{%M{?>OGcf)T^G0WtzaqynOAF8y8K(` z?%p+}$qEY%|*ZZJ)Sm}fWCjjm-fE}vG zE}XPL@>LcSDz@w7BV}>C>w~E$@%+i6UIM#AGPUv z=9h$j*@~zUSg#~ml49F_(Pjqzg1L3cinru3t$DOyE!|u+ZUu+FhF!#V{3AFab7y@U z!90=={BJhZwb3F6e_&NJ&s$+DxegkUHK;xO5ke@r6{DoHr)=u^&slWs`cwuWA*SVu z5aw84YPDDF1hPGOyqG(Cpap>u4NKN?`J#6Y2Hjhornv|C?DOcU?A7%5cj=;*^gN5( za(AESV=KK)D>KF!&cwKM1b0nx<4sIp?WRBqIV$5z;*&&mAyidt^DcY~HliL{2hitw zXs$j;2QMpNabJ&Bg&WAeizXmXOecHyapJ*uRu|b=8IvJH_~;z1zQRk4fyna+t2PmR zJ<|gu1UYTq$&;+yJ^X&tLX{u@A}$4j*lxte0Cd8=O{^m*g(Tmk@FEYMX9`E1seZY| zS-|r$LRVr8GOGdwq|Yw#SrnyqeR8X9m`&;avkCts0}t8kRuhs8GBPTy-a6~fI` zbRA=yWZhPakX^_Ji%`6Y2lBwZq7?kF10E6|cqG|%ZCHd@#Lw5YVb8G@Rd26FhEB48 zkb{E6v`T3%PQ} zC!Kod??}wSV6HdiytYj5W_)%Ydgn+FzJ$J`P4msl_*m+skCamR+?S(@{4Qx?tR;x1 z=VRnoZ?({yziTC%My+sNmQUuZMEZwE*AVCaPD`%6mw~|tKOf*%i&zcId%Ent!zXR) zXfw8d5_aYHr5$MhPx>b;cKbtUF}7Ww)n7RQ#s?wK_gnDvUs}NTww2v6ZlU{7s{s@N z+1^9udVC-xCVTlrFT8R;G5%h}rI_zR0v;suO%P(h2aXIrz>2SD0>vpdm}jIh8GRva ztc*}Q?g5AOl6d3QcV0@HPSZ2XCh7WI!=*{Gb zn2-ZVrC8AHC%7te=b5ittcgCYf^~6_c$T-v;WMF{Jm2{p@-ke+Ut+r@cfQ-a&1)^N zQAT6)AeNy5-U)l?aa0}_pMyd7zFZHw_bk|FfrbV57^%el&K1_7x7E5{ODLIHF@6O&a%1QODvzQ`2C^}MX z4c*n&MiTU;@(=)!$#R-}!Uue(>}$n`tf%oOZMLp41^lT=zWmpV;wvn-M9cjajSyDr z%-5}G6UNs7Xs!|^c7K?3X332YfZ-72E~Ym0?TW(0LXg<>h=oUpJ~a-z@!~54RJ~*c z^+Uu~WWqB|LQM%PsXJ)1K7_`-dmSgJoN^ouJnB(DuFmCmOrv$^vcUOPh>&}U{m3<0 zIcAu9N`&ge@WGR^J{0T;;;y*R^t{XB=IB^22hUR&ERO~vBV;*uU}y%9!+>jl-3t6z zGTBBjjCP9*4`aMD342ZFX8LkYdq7amCus(YPs{N=3%&saP)z+>5={{Qh50_^0Koac zsGTSrv1o3shUjSF*p4p1Na0Ca?{!!DK&1Un{`g=UF=H|B^6khGLMeW zz*3?m!hgWykI%_F;ub9Fuvq*YT93{-){#k;={xjkI*-P{R}!=G+s>Q4bjAV%j8)pa zW2Ku-h5t= zevjIC@i@Z0W9EP5zgq31{jB(5$XCco&4NsTlK%WkeydBcpYUDu+fNVNYrAGP&?7<| zn)#^`cBK7%_U*s{`{KKvvWZO-*1FAa-CzA5L?60n@s?YWuz?VrMa6w8$6hO9`wolt z6xiT5AF@!}Ar{dI3s!Re@@rESsC{?GZr7Qs&@sf;KH;G zJ$0Bgf@`6oOO`%I`)BUE2l!EY-O-h>JNx}snJCVa{1@*OC*psPjn+3>WGxfRG09y#Td%UCoQS|k`Fl=S zsP75$$4*+w{XJH+9${7mewo1x0CJVD)C7p&YU@2q5TPh6QBqRz)OXE5Fv{U+zxTME zt?9PscD`;i_rR7l62qa!XQj6c+DzoEO`JXmAUyy=%nS$_n<%~;m+-{q_aMkUfpBlc z0y}~!1ef-JA`{JaVBA$k9KQfYT#nII9-yEJBGXdtPkP#6J75X?eB0EpdDcD58;E+u zIYnRcJoWpGC(c#1ZP<%!PGts?y-135rykx1l9OXkxc9IHs(cnCje2zjmLq=V+hU|K z*M0@n5&u62V}d)jR`^jh%z1ynwLkY5q}ziG9;g0a;c^^@DZWGgb7ldqBVf&iz@Tfhp1SqH?? zmqYUH9SYjsQOrY8b7hlsFZ@cy{EylxZ?{dzBaOhHOL)+Q53Kx1^rHCv(N6PWKOYJ| zfqTJ4tl$dggk<{YRW7{J;s419R{Zgl`TFul{!dCs%W|vPuQF?S7j%_E*4TA1n?-r}0hU zALktj+<#}@Mnh3Wq@!Ylz0UZqpfB9_=v@MEG(gEHE58!2gs1S(?=pMg3m_h}PFr>p zQ1u~54%ic=bQ7`>aH~-*Xc(r@eVm6%KrrZ?^;tzli3I{IOx)u*Xf66);h>}z+7yCF zM*srB6_NXkYguavYj&x zwgcXOsi4cLcF7;D{)660`|HxfcA@^KQbHq9Dyvl_?3<-+&;CyfB#v1{?cZD3Js`a5 zIpB8zVzu7q*2CZ@Mw7PYWSwnzq21b}^>DL=togHcz|PncwJ+K;t*=}B!-OiY!)$tu zSP%gO6)?FA)&UIu4vTgFsf`^Zcud`$B!ayMz-DF52MGw6S#hV1d=NII*-E+zc+xBZ zX6l3G4H)h#u%Z3ih~H1$unl>$8SXbO-V2yTeQ47>BYjtJtH+942CV8mFA!Aqd7J6n zYm;3cGrQ-*j?Uk?uk}`f#*jwrZ?;>>#^YrDB@dJroroiQTKp3C7(;45nilvr!5(Mz zVVS@!(>b@2`Tdp5I92R!Bm#CVfiry_tN`)0`BnQG>(X9YJA-xIgbs~7tp5J|h$iAHx zSx01_^{9i3l_CK5CGI{kG&I!LghPyg-q8YRV1xj)0=bzcDl1QP8?TKRCPwG;F2VsMbq=BI6c`J1+X&l~33MzD>w&`E{N z5&kbJw9kieO(ETF-Z#yUQ&pnlRg18=Br7mN0*5;)J4NAfoNqEzqA`LBi1#5+c(ce# zZ^J|z%3I(O=_RH>A3Xd_ zQHkoSxg`097M0uIW08wZ_^pgs+xiI$Nehy(B$<91KrJ&K8y}Y`A?_xZ7i1SMGd`W^ zq^3l^MLn%e&j@j_+*{Ejk32H6apT5+#c!Iy2TwqiunZ*PP8wt9^!y*S9pFDa(PCrK zVqzI(7`*wLui+1Mq9%_ffC7kA?Xk%-brwGKDxQDnW?=&Yl~}S>Fj?2k*zC)F7C%d0 zZ@Vuwz3RN_rhof$q%F(Pq0 zj&>0}sOW+vXGbkM>9Nt%_t@mbdxb+Lf z248>fIrH`tenQ}dd@{@LW4(;Aif#5(J>0(y(bN={e2V0?7aI4}S22zs_$8{MA$+ zu%QH@2y-$NnE<>#wZ;a?4%{oFn;TU$Na87_>I+IZLj+#T+G24syIw+3IXPg7NnDB1 z0wyPsTacqKGQu(<6VpgW1^cx5u_sm z=Qr=8J3PJnEq1Yo)gR$s=)D$ee1r(n8&c0*i$2l2MG3?Z4o={W>N&@{M~38T`1fM$ z1u6k>grSLxmn_+L5zRrpl@yiOhN6i5RQUziWMUJl;R}jZe^GIT$T>GS)b?jT``O=n zA9fL5-!xGmF565svqcQxyA8#4@`1shmav1KZngML1&5>;Ro z7G*@E%yirJJtw(^$S_EA`t+cy`>~?!|2DnWBAep_6d#3Cxaqdqxk_4g@;CIx2>33blZ&3hKqpTpXC#<&D zW94^StE3-MV(vu&)SfK^Hg(T1Qh3yG7#KN#@7}nQy$}IH!a%LhF|!Y?!9V}(5u3gA zmd&0zYq46a2GK4g9aSDvaUKcqAS8COd7Fh#RY7_KCrH<0d)6a;-*)YQ-~Bed8()(6 zn#XLq^B}88FYS*Lyd+@3nJMHw$N)-U<6fKSeat+A=WOh&-?FN^-mt>v zQEO`WmJPr30@0}22vqR_yZ_bGc2_qsB*1<7dj28j#p$=x`qyo;ne9Xn5(&7PMSVWl ziD~Yj1x5PH&fz+hV4WO*yjF5s5LpU~K^a0v@M~(mu0kV35l~;zMjtjDF)P~8VFS;8 z2C4o|izI#|r>ulU~ za}|+o+7wj8vxil_oqdH(T=<_B={s!|d-|+mH&OdXCTxlX7uzS>Y-dCPE`^nsFX}vb z{=MuuZhh56}Vq~HpK6?G4*KxCCJ?pUaYq}NvIS*BWtxwjrDU5o04)#Ry zFNRAU=T%mM092t{vGxw;IehrA5Wui5s(2y)y`X8je*R|Xg8PRH#gI8Ar~_}>A~H+S zUEs}=#G#vh^037*@F?3kV#V;Y!ND<$9XViYrkNi4j<8HuC#=0l(W0$(aaWCe>h~qRl2>VvWIdx&WVn!gd(KxITms5dN@Ldw~gc zVTR)LEU@L##&zb>$Q!74>hR5Eekdo%u_2 zwi5MMRRAgI&0b{3jVD<0kxyE9@T_%y`>(CM<@;FFjagl1rEQ9=v2}#F&bJI9{ySFy z>vPw38(GVwT&z~ix1wzKIbF`M^q)3Qd6(nWmw6PjRq)O`AC=r;l5tYNP>olnlI?t^ zd#}|w>HP6bwRit>{1Aq1dgzzQkpZO)LQ1w*SpAle)m2UdH664-;I+7jx`w?DP!D%O zV+rQ;!Gb}-q8`fhAg8mJl_CK5CE7a_0Q=avbLWn%Teps%Y9zVMvIqfF%}8PmIAbOL z87o8}ILk9+TDp0QRt(fMNvML@num$oj!u1|&$eLgRvj(RJK?83a7e~KB>k9bUT1MU z%kr{pTS?D2{m62HaY-W74|zG_nEX0&qm|V24!Sosj7>jYht`5NK-!s`wTKcCOCVt- zLSKyHS^Y7ZU~oJL3`>i;tR#rLbq6Tw;SDft$b3 z>%!nfaw#Lh#T~Y3&h2;kzLo%uKyttCKaBK$f6;k+x^fsjG}KbDkoPqxLIAfv0`M1G z;F^RSyDNDQ?%pL@xf}1dnuVrB<_l;-4(J9JW zJ^;QH3vl{d-};tF0cQbL56x{(_wYOKvQh-#zCe3zP6L8LS<={#*is09)!&b_G8Tr+ z$$$Vf6d^vkJve2d2pG+=D`Iyu7fmR_Xf<8xvb9~qB>ZTfTm6@Bv;toYV)uBlzS1tP zElqiaVaat(iYC0W+|-cackO#^dNzi`$tCRK-z2CdCfH~O<}={BK$oo{i?0hHHR5xl z@7Sx)11aal%jv()=^l=qz##7Q)ZV>L1`H+Yl*Tv)q38g*^NgNj6AW|B$L~OlKqRpO z^OHF@5Dhr}?n~f48^L?-Vx4ol_l1{vNQ!819Q9n5reFTWB})<(JjxBDftdB)y4z+5 zZ0nfi&Laxlb^VIi;LU+qEAwFJlu`fBw*XHbUlAMo6hHUu9L$NtP8$)Y-Ri}>%atGi zy};cxR57fPU~KUCa0`v}h9H@zGFPvML*BTp4-$sTiy@3Y;bt!i;)vh(meU<}+qr3U z|D_QBnZIxGr^HzOFWP`zYH79JE%5%R8Luh%DYIgw6|ZfviDQ-K88~dgL+7pX?g(bV zIL7#43#1`{_H^dc+>~*EcJ8+WsP6AMz;z%^a;q2*GG;igr4RyLgP|KUfsOOdJZA3z zKXLa2$Vu2;T^G>H7c4$5;8#pO@+l$@cDO}78wZ5-KHZNjIT!_DMFLhbQ)z|Kkd@6A zTY0?5k-aFrcnRUL{50Hq_Gy+80EB-mKbO1L`3BKoyn~H6J~rbC+i9W)@Bdjc5N+RW zak=&0AOuiMXY7I!F2OL)iI`0rmlUWJUkDHrTb(Lhz?}4fV{Go|xS!~J@!WmO?(&<# z3#)Noq!%+}&anGtXJ>y@P@q}G#DK&KV6-5ig`7h&m5?`T>xz3VG~Uc*Q2{r3QG}Os zN9=*wjdnLp74R=!AhUhJG*XTi?YIs2*V8#z9S%XND&L(v(N@z6Fueg%KLwd1+aDnv z_T3h~?Q!exc*VRg<6!gGU$FA~lc>-X&=Qy1X@(LYjRTCb=1YW8GEE>|A5n4?>`Vs% zAb>G|zxtY~N^6*@v5IJk)yJ!?B&jst>J5x@_^W*p<5_@Vw2rk>`;xd@b3T*|I`;-K z0S}NRT2t3UfQumKeeC_PfQadZk_!f(!VthyW-IOlYyR|q4mq-X$69XYXZ_J0JPmJUTtrb{|55}T++H+bMX<%$ikG$p2{ht3+i{a%jh(Q;9LimQ z1UQ|4xmpC^B7x}d{oe0&{ri9a@0~Y`Oz|?gJw%t(@3~B-3tAqKo@a%OzV1@C_VsLW)h&6``t(lc)exfbYmYKEetKPDSvLP!9V!qndL0)=- zSSHE{3$-C75R_0zQD|ius1@8Bby<*93+Vf`A z+QYS0if=~oENZ41z>fr;fm!(EDahwA*^bHQ=hwLy(QlF2R7O~P;{{eh*eU_KfLr0X zojpJq@&q{xxz4{7Ij(D|>p~U!tyNk@;H;Hf2*BAp;LZGDPbWC{r2n~mCiUy`ar#}k ze~Tqk-Oc@PT3x}AbrB~qA^DEvC)c?Ip@i#$qmchvOS2T@7O5BjsrG&T^Pj)Somx5d zkUmD6z-PrEv{D4%zQBE%UMwsW{rcCxUH}4kjo-UOs;I#-3c~)9X0g01Dhdx?85p;< zSOpIIqBa)8E`HHHH_ahJB`@~%Whe3bpLqn$KiD|W#>w)pm!O}|wjDKpL&D0-NHKO1 z_2=6Kq#Glo)VfC*%55lgYDg;43ja=`iz285B{$K86xo;W%d)jelUtdF72YgD+N=7_ zmU!a-!rl3lRSb^Xo$(#knyk0xWGyRtfdkZKc+v$}skO=m6G7H=xjF&70IG}pF7J6U z=iTD2+>0B2`40C^-I3|+^ed$YI5~(fPS`RG-eiuf$w0v190#J=E@N2J^J8S?p$&v#+ z!?uf!$qPvb-=dgjk?9`iRQewcyTmhl3&x396R=b9T8pPmqV#)j=x<4$CTt z3E5hBP(`@OXX1+U?8Zp4qoBvi?t+)yDR)>8{^@kw3<0sjqyZ0q%c4`?!_v@ev**Zh zH&|zp(RL!kJ`Q5o;<$;fj-(nYhE!iZJOzt>^d*aLP)xRt~ml>mJK2uTS17TLy8Wh z;!Gp#0puK%S_$;X($c`kH=x=`F#y+pHCWoBMQ1cIQ2iB*joKE-_EIK|NY(sG662pS z>-OWA(*TK!tjUQyO!Q$*xCAleeB|BpiPx4#_qZqxGW1MiYCPSDpbSJIc0f)_`GmvD z)+kBmW3v|O$9oYQhOHMSZTD28ZH-jh*5q1e#TS78V=8jWn!-zQssN)LISpNBA)q2- zH)H!(_kN=k^CXlP>vwbIlJUfZD7ROL<QOjwyk54z-`>vh86 z{l~23$cwi5^;c{|vdLL3^Lf1lOO(*ySd{G_>pr~k)T6pXc>@D*Q4 z{=m-OcAL%K_0y1L^u=|i07UYyE$p|Jg8rPt5G<;}s16w7ALaEq7;_d}j$IbOMFKhN z%5?Ec5P*PRB^?Qf6p8fp^+Dv?_jOUli?NGTfgW6h=L{H97t;R9DzFsq!1crkC_y56 zQxz;!ypyB0b|hx&$9%~C@pR0SR2Bm0W1@}KOj@`_Iy44w8Tfa;UH3rk$(1))L+*mw z9)e@ON~r0J;Cw0DS5PFs80oQ65|-Y2Vcc#Tudt1gS_g^EO{f)A_RhXl@|a1Su{+4a za5O+DwzfhWTCmf_&B2(Y z>Vi3U5l)B66*crqSOC31FI%S%A?6!e zfP0FE?6qj2U6Nh*%~A;7=lo)SSn^1?Y6xA{( zLu=?iQf!a@(U&ZWBsfvol8S?uuRH(*=6`Fytvfqp|LoivViz=8brQDhrZ31xoHn}i zIyKoYH#=q6bNN`mbZ^S)FZGoBH?`MzyzT3^r#-LQD^=t6^anm{v)hybxuvU;eUUlsU|@2OVapsL^7$K*lp70N7hPVQcY4E1RsM1~JOl7bEk+ zrNt5c;ZuM7dD}$0wqW_6AMmRquxlXZ|KC-VHcKUY?+6anZhdZ|l-%p-u~$BzTW_P^MEh0P)Tg~hxe0>o*YSvm>)kVF-} zDQkiaSOaO)g-yWHyHwkCERfqlY*g#J`>i%yN5ubh310SgXkuy_j^pvzRXTP#jb&pa8Gnni;Po%E8&q*m*42~y}m17@}xkvO2cJ~CWog_w~ zsE?F2fh5|Qi|QXFU)}-#Nt;E093cp6w6ey+P?K>0AqMXpWyN;djUX)!H56z5%+Lzr zIa>sq;%VMOL`1-!exr>sjLjlJRLz^3EwN#}6A<)9*#B$xmt#L&!yK;{*Be9610s%0d7?WJ@6c1};!o4LO5h zkaryGx20H5A&|?^iM|K2s4-D!pP#I?@Qt(yaCHCuR^8KMkG?qo-yFpB2j7M~iY9y) zy8m+_GT!eSwm=J^#dBocUA9VK#mQmlIg1NHhxPpfi8Bk`ch#EIQXCWajLi8f< zLdR%G(~NDr-wB?%E7@-AG5jA+PI8vm3jmE)##x+CgbuX2YE{+06rk&u(v}h77n^yl zyGrh%y#OkP(Z6P#%zt+$Hy}`417K(Gn^~TD#ru}M%J$Ro`!F`DftJc{NvSpab^mGm zw?%(u;}PsAH#}g;2YwYpDJ1psO9e@k^!)& zemjzW_0Nqd3eUKUs6RW139$y@Ul7EUt%&ar7T58)^C0>|V2iaw1nuRZG>xi7dcRzn;Fpgm^6`~UU7{?|Izh&fm+SX7U!1!I?q4o)vcSkjAbF6t*= zI!P<1szCq@*o`XkDZg;cs=E5^p~P)g4e;kXZ3H~W5j7nRoU;N#a(gP5e(RNdmg4FA zFtrLcl3`}{yhX-eA*rO_qC@m)7twCLI|#JUjDl!$%5I?Nl!f2?zWw*wu!WjRt)Pm~ zE0`J!Xp#VpfJHdg3Em=LasUJ%5@0OAr`=V`Qu6FVFV zAk+7#A7lmjP2Ya|4jF)t`p?P+{7K#59&4|A<^{LzJ)F7$1u2d_Qr>IZFhADnpRF~4P&Ii)s~rA+ zPI&IX6iserOBVpT@OQ;ub2SLSeYt>Nqv|4n@SpwJ7b-viU*+7#Q!SHKAYqafEK~y` z{(5oYbcKJ)>Tw=v0SR1UjhRZ!4fNuBujw&u!}BlDbH+*rrmTe(OEz-(6s`VB_<6Rd z$4-=8MD^z^K>0kn>^&Y-h>pDqLdAr_N|Qy#hnkXr*oFqxqH#d3u#1rFL-aE&Lh=$+ z*E#DBVOv0?URy^15(Ob~bJ#h+0}>G6i;d8#DRr1uNf3auy3XC>01$xd=_3*^ehph= zb(lj7EfxW;OA)pDfw)K3Ua*P5AWb<5gHJJ&9G|90FiY6;$FLjyWn5#+C7=H&z`|fpd@tVb7zX z340pT*prF;0583stNzXE@0lfL;nA0@ffcqb@wlTl%cowE)FYlrd#Ulbz0i8h>g&i9 zO#Zu7D^%s9K3@T@G)#xWbqpW#Ncc29)q!bo2aY=jEH(-@hSv;3Von}r)h7c|?3M@N zeK)3Dku$A5PBRy`)jek1CP}qDDamz>eI)vz-Iv&o39-VVFGT=iA5Qr$*>lBj*moXz z!A8l0P&y3R-%Wj5CUO+1S!JV8Ni=5PhPzU3&DU8?m!o-Ce5n%P--^0>Lvgp&vCu6| z{4rNGKrgMC*k-o~mIPBA%W5bS|DO$;xK(7`&!d>EcjUgH7i$ynr&9s3&wS=HuW(M< z0H^pd3l0SFp@$Wad1Iy`Bv6Q5z=LHMm}nE3Zn^g7rV-BccGw5HYwXcM(tYCYns3-| zx&5Bo;U zXRLD11@pZAZInmMA7{nqK?x4iH}RUfwqVmsSd+tu*N%SQnx6lT{oC+|?V;p$oQGy&Bw(3@X9`%_Q+yAzi5?d23Ws<9lmT!e7 zzeHud$h>0}O!^w0x!T^%xAnZrMFM1 zY#Cs+vI(@X#+4m;M*1vp;$_D4|I!M? z_aF70wNphG?GGRNx<&TPTKOI3zXx@t&tFOy2v}r?cXXP5{Qmpz7vR^k38u8Tx(L99 zySd)w$`zD6X2Y_zx(yKmaFKu-JA35FktX(k>eis#<_d4*NI1cEnTp0)TODk`y225w zWAzGMjxdqwk<~dTau+w;^3gHd)H`hz@gVEJFmd*oC#y3FxK0Lp?S+aVJ5V=leJ!IF zDJ8yJzPA6X)B2^gFcQi;G22CS;K@1^NVg(2gr{DP5f|_Sbe`cZt9$#5Z8&w#eqx{k zSLjOQAyS7f><=M88TlM9=&&Pgr|tOWv*v9_Gf~BTnqBOi89Fyj7e2kT**c?lC>V(c zcWINa{yVgg)6_Bi*~UC>Me;9$w`|`py}y!vDC%#T@z0;m!4O!`K>#lB3(j1)yQG{~}8}pvry}IAxz|{HA^Nu^qPm{s+nUg3g>kn5kKR&0C%I1@S2? z5<3wapLoc|`rk$NnY}3lkoAew1z8Y!ddMg6^#8D5duhZz`$nDJ7u{mDNc=MuB|AAD zykNiG{@2#?u3oG7DONJP8I{r3EyArbt;n}{q4+|?UGT)=mr-@TQ%gPU>;uHRxV;3S zc7Yc1?4_Wzg=EGJ;Ab%nPTxi5U`Gco0$5c6pjvaaEP(1z5jN5gYjcr+pmz3mfA@E5 ze(l$O?a%rBDK-jfEVKbC{=ypKRG_nRLc%(y=Ktuc6)^Fk$}@J19DIGzT67>%Azq`x zYU4fmf>m9J+7<*|igcH$=mRHEZXEHPw?A+1w_|Gx?d-mPYcq`-Eiv6^)32Sg*`XKB zi&0aEl-Acx5a>3R4w~)3dhbloCXQBH{PvGxe2)50G4OKWs#T;)t~_MN{x~>HOxf-VgqJK8&*LGqd(*KeDPwoDM5z<9i;I)^Vi)U0d%Kp zg2T3!RN~D6vZ%TjR(r3>A0Zw=A9nvEQ<%8myRhVKDf{_R!2gnO)LyL^w*xI9JG!pc zrZ()hL|rSE9=Mkl-bO%=Qi}~^m~)-yuJCA#aNFU&GD3?r+3eJ2;{RMvSb_Jk zIYk_BockJq{o^uZ26DFcyV2e=)t)C`ufrRznvuISAo^Q z>&hS{y~wmxdj2Q9uiC-tuzm4?H8ykCPm4fg?y=-gJ)BBNDc%0%m1SXT05H$gh=saNTjMuAXaC2U?Y3j8 z)wac3Sc5Y+Uj5JuJ@&^1-?pPaal(e~9Ku9dYTkuayGMdyDIXRi68HMzy;v_f8F^$m znk}yU;)iacV`cmKnZjYa1L0pQ8m+8GKeSmP^9rHRl=dsl^6%S%87>R>1w-k=Kb_Zz zYrE>QS_nW5aT}!uiVB!V0B6shZNQiL|0PbqJOWUx0DlPbvJi6tCTDDBaIOk=3rf=3 ziJTIEjJkKS-i{Hzx({>VRV`EF=Dl#-cFs212AQCytx{U;_q}mUS+01+lRwG3V^TR!fXsz-E8Q{C>J+Aud_frb~38pv#j-XKi+P4L(2* zTI{x;C&KVLD3S&cP>vx+z~-45v$9v7u(orZ_N!;N*uJSY%(0d9M18z;wU*=1E1nZ} ztmLd6dHlFd?MAq@2GGuYyYsEi#BipoP{7hUmv)HmqSK;GAqfKCL4|~4)&%Riul&4i zAktMX;Fr!{8nIw8ynos_304F%e6}qA79#)`&Q_&YR)4RaBIkbuJm=p*jC@4im< z`!BbeL3UgoD=s%rcM@|i-H-?PjwAjk{vTXgA+WB5}8$?F!E z)a~*P+gqUld#-NE-q_r1=eKUMBs{+pr%$V^TlBl26so4yq7$SQk3jgTH?BpYx07Vn ziBHhEJsz9xuCxVm)bWe_ob5(JJ zu9d;IZosX*9oDrbmo+PkhO}Xdo9QLs$6Uy7wR-;?tT@y&$ATfjk~Ynz^v>b%>Pn8~ z;fg9&loN-9nk`4qikH&{A2n3K;K=`bh&}$7+sPk5zntt%ikrZx|vRdeQ)_~?3Gdr-|`tt zHg7juf0xsStR(+j)e`vmyG~m5lYeag>a7iS=R~`0O|&kce$rc^fgOVu`iAc%`}Y0M z*_j;|tav+Q`f_m&dCr*>NcK}GUVWPzsCB;+i$F<&Un)@HCT;zFXyj@Zi&yxaQQHsYJU6Oz9;3-Hg?k0+sL z@SJ)3PlDO0KaD`h(1MknqG#jN2;c_My&sin|GO<#aH~ZhzSEKoyPSSp7GSjUWAGGw z{!6y$Y%jpS(H@>yN2+sHqAY+ZO6Zig6V1ol_6PBA+HBjn1-EiHeh66}S@2z=07MB% zt|H1JH~2H_aR?j6sVW|5r2q7io4?3b<-Gv^y~TZYOYw!AzW(C-Lq!c(X{KC$)4uMI zV1#3l|1SUUA^35Ub~Wx-QOr^N~cP=WX` zhDZ~HEWC~H4uMhIU;}QUqpNYK2+-+QRWviPb1x>{_j)qpD9x3CUp)WYxZ55t9k(M* ze(P;tXOpd)=2re35Uu*)Sv`p{Ci$@AtOFBxRZX0KnBG(Z&PX3oZ~BUDcBI*6qqkY4 zU?(I$_*DFUQA)i!|IFeaLU?F9Y`D{!2y?!%Ys_{{)R5z^WX|Ym@dKJ|DZl=UtZ2uJ zM(yol!fln1Wf*^hm6m*fUvXM>;K3 ze*v5BE}US9h`bsomJf`MqTcKATL0fSS*-9Di|zRpOSWj$N53!I@#S6wa+1K$+k4JJ z-}yuPH*c=9J6QQ|i?`01_b&Z7^{X75UL~%;U$hO{_Z!GuwGtz*e)JC($%vf@3Kyn&f}-8L<^ufpKxE?j)yOa4d6sjm%oIy z0ZbUe7((ihsX=nJWe6Rn`~B!t%L%IZ6BTFe!Z2~-5|!4OP`tqvmT1_?%5(eaZrk1! zusQ-&y-mpIgJq-kcWXxN%tMdabS+3p`hCUT%gFODdZ(=DdQV#c!oouQ_8q6kl`oVF zE9Ju?Ly-I@YHadcvxT?(tR>6WvFh(g1Wn#%&@dTJEX|8((` zJ=F{qP>n000(aiTMJm6x;FSGTd506{PXTVT4mm>NP-#0Z@zroP68v4hQ!pXe;8RD~ z1S{$MzYF}UjsR9;eabXEE&@=)7gGV@TW+~UI=^o&c#suLYC$DJkX>||RCM8O9EHHR z+lu;Z6XaGKZo^^)E_daE+p{0UBDnpI*yi3DYa5O^tJ5hYxBDx{?YrweHhRll7FoZ0 zPST%8H;Md5plAcong8{WEESwsNZ~j~L_4SW)JU@dytp4JO3Na9x9lwBWzyOz*77qf!Vo0u^ zu6Wz_;5B%me~0zP0#rU<)zXI+pCQ7Huj8ma5Z%P;KWk6;4%u(t<+V%OZn5~TcRSg7 zQ>%WSbpm8Ie963rzh=QLJr-=CYxBSxi<^~x92*A^yZzSl#14yX{;(zA{}_fnt<;-C z4v}5~L*OCvtq&iEitm5X{@u}fyL0?D+mUF`O7>3^2y~SAy2rg2?2GkB?KsIyJAe8! z7OQO|ULXS7`t=qaFG7@%NEtfi`;E*730M~!Sh>xWQ<1`meZ~7jJJi@>iHH9wj5QQM zHtQny!5g?Q0r)>tan3d{2b=I)@#K(6DKfU=Vk*$5lQsMDTullV1QUFUcwfQDby@w@ zb=L|3sBRYlq$2?r!%gqmv#0RVrAxoheV^9NDk*P4pVLusqR=EsXc>=Aaz#~LE-pyc zD!>9p7mt_p+JV^$wmiv28NduJUJms*5`H=joSdKJd z%zIyd%GPxD+fSY;wL9?&Y$xERV(dqlXNth9I0o|ObBvu5Lw2xo+6K#lWX);DyYCSj zs=}Mx7&#K#YJO z3K|k~5P&An(o*c3LERF;RJfa|Z1z^9$i{Ia6*Zo{a8au@5pI*`4qAtAvklhN+V^g+ zC33@_)XIM)swdKJ`(`?zl@UfJWCVO#wz5PGqjW&_XR2YGnb-iVt z!%v$1?SHY*-5-aq-fNM4AEITb(Iib@X|Jfxum7J`;5lSXk3WwV0P8}1$mB6xZ z_L4mLd^U9CT^8T)m?duk_$#3f^IiGp-swGazyi9D7EW5T>{tHriIXyG+m zQt!VK1nRc&8t#?X??Z*-_TGw9wzu@6liM%Tr@Kv%aJ#he9u~Dqkif!t3aI@)-q6s{ zH8_Y5dP?{=&R$4B$6C|GKEGor0NU=5E=+?3RDeEAA34Q`7i`dbrAAT@!3wGD{0>7ss1$HD-YNyFAl(7hrbe^;%mT0ex_Y}FzELq&(Jpx~GVDhT?p67e|o$%8LGK`8Cl5%@*7VF+`F#do|L zGI)yvs5$NV7q@5bI9avEV!Ix*Nlcc*c;Za@OKh|li^~xGBGsX&3Dk#PR`;ZUT^5W5 zkoiF{mxBa_w=)zWgr-fFC=S{9Nrvpy5sQuWTR|JKf)x8tsGboQB_mD2gE_2d~AX-hU4Uiv(MoxcP8lKL;ilFw-F0|Q`pII$E=2sT7cqyxU-=bDvk$pW~I)(2=4 zCez1hiU`Ar-RiBPbxC~EgX z2}~18tcxV0)0sR6wOV8U?gYqOj{(hk$o}&B6wgmRD=ugg6mTJ-P}7`5@~P6jCs|QviK2ZryZK%R+m8DH zXoZ>*aQoH3)Vd`vz0}XtvHN_^J^iJ;0W z^AIIFtbha`Vg;(!uU{{B;k)?#-`Exv3}7aDEHXW4)5CAlEkcf&i&QN$gz|bB1D79+ zthcWs7@WZdeZI(02kF24<*(z$+hX?Er+9laEt|(X^S9>x17V_l@6WC2?*D0p4Lw%S z%qQkKj}xfU#t%nq_}G1{lAA5D@1M{f+EohwdnIy+yc@j=H;NU&q}VRLj_tz<^S=J~ zAi%>=0eHX>4lO!TP4=QTi#ZX}OA-zoK?&SZXSl|)oL&fVjZjcoQlqm2 zxY&+ZLNbAjg}C^TWt*jvsZ3bU@D@8s%JGX(1A4gw=n`l>0HDciR)CiGa-HFYNZCD8 zUFIKu65an8(tkcH`>eQJ0gZ`tlY6hfz{a}ow@B;btk$q0wHqPNA;WKW;MbQ3fYsIp zc=i&g4JLaed7jhCdczEEEhn8AD}L*p^m7eVhp3NyI_GjX-RNIxZ4CmyHat+@Ph_gw z(e;-X;G9BQCt~^V*i{IU;(O z0AEN)o0xQo%78?ZKXCcLz`ziK!B_ab1TiJzq5p`%x=pmwzBQKm6emc~ZblTsbZO!*yHGz@a^*@B_jZVb-; zdBY*H`c7H_$JvWqe2ZDIa4K)ujr4zsZ%YiG|E}8F+G^?;W23_`x4bO))8eSjMFRZ1 zwq*&RUBlP8SWV=O`d1$+tS1a81}Svsop%FA=dJu6A_#)U@&bOo zILzulc6ygh4&cc1$j4GDKIPGXhpuB#r-&8 zI2Qqk{F!E(z#6Jx=gytq+X^+ z+f8V(26W%6Ry5J^B=k&>NTimPUtz$PDM=)5Qj1NURF3-%mT1@u(6AW113ccA`Lxt! zQB*>%+OCSa%Ij^{?4~N_&Q|8meb|@WN^sX&0(-~@C7Y9vqyZxRgC#9age!&i&hY&| zy#4muzo$7)!?o&b&fhT7-|f8XNdf4c=?FmBPDntVAV^k+1dbj(+Kx-)C-?5%`y$6M z>1l;YB~waCS7T%sip>yo19^Zd%>;fLv<-w4YrtY~CPvDo={g$;<4&ug)I(QQr~m<= zC*0|z;96FW$n6T<6+_%J{#w8y+jp9+dl0%u3qq#WUsdCN{O}d@fQS~%$gB-%|NWs+ z`(WiMtHRDd8`*#iV)-Iqpzx`aa*?U{E>yC`)%!qpClKbEWUDdCoh|L zEld=javPfYO-pWhFM56ie>bVY%c4&I|NWsxt_*?SWAOX?Fz~q_vcD3ZU(P+*R(^Gg zqpB_>&qehuto{hAK?dnwe!7Pk81G%Xc5M`!e*wMJexd+G{<}y(2tb>r|fvV+KEz`t|?uK_G3 zEmIpRs@=t1wvYW5TsU)p>!NpNIh1pZf>sEJ=NdM?Ql$TEZ;eg&wOgVQ^WG99<39%e zEFF7&Pir2uv+C~w`0pw1w9T-M6+Ubm;Q6xyzsP>ssWdYW>#?IElzax@*BsVd)|}=w zF6pni?(+UF9Jp|CT|fRtAOL-!`?30XVLo++HVH?B1jgTf`()`O4?prXe*b`NQBmjP zHCTqgrE-(wUb)D_YQg;)V8s<|B|FPLthhc=-f8c_j=KbzfKrWI5h4)1Sd2=su-ue| zCx>~0^R?3X&vdugRM&R1wYyTh|AJQj_~1tLfX2RvK%V3dH{ zM@Qq19Xr0XWefB&j**n^qleHI@cwfLryuSyph6{nbCdvKl>* zv|0fDH!CjK`>IaauF?x213WodEV33ZNf=#NLGEZ4pCJDIVgoV&|Cw)m;~PKsJHPWg z>#0jBKX>&P-=B&1&-%)1dEsV204~t$JKf*z-utz$eXZeN{>y*)<)WgZk8xe{g3Co1 zSL}cQ2?1degb;Vqjzd^vu@g|mQs)Fg1jRlfU=Il#V>XM70FKWgM=rl$nO}N`tP4-Q zVg;=c1VE6Ck^{J{Pk$Wz66ud%922x?*`ruMl=C$pfghLa-UFKSb@2OlkhJseqCtBP zUWoD~DM9j|%coyx!Gm2xsHDwFyF=FOW+ySlo52BF}S94{)c15g1$+=mrrNgjl; z*7*!EfQJf;K*<5C@swGq3=Sun_3Ye_XC>4@mS|f;Z9@Z23P1;BUvN zr?s#*t6jeu=Kwx?Ww!PQ$}sO;56`c3UYU)Y@bdc^%~>ANJa$+9n~LX2-;NbJgYMp!buYnV5No$Jn=P{cutm;~S;1P+M@UF%=~MCt@e({^><2i` z)S&^8KY|+Z<8obkKzR9{;Eerb;gEf*;Z?h>xZ7$_5oZhIfFr{8(`w@5xOD}sVL$d;$r7san1fgPsA zWT_K+#$wGo8av>~2XKWAlaM1;vDXp>>tG4cB>b2P z$TXB!eNN*lWL`%Iv=-ESzg&LF_LX%wQvMJQKDmT_nskm@k7z#rP^FdBZk=2CvjYF$ z-hco7pL^@Ax8UvOfq#nM2#Fl2zYF}T+THkhW6RBk0MdJ79`NT*>ewz`yx4%hz~6l6 zLmv_X0D_j5lxe1)0VDGY&Kbhu@d#dOSpxtHUxuh}x5Z*jsc1hpX#k8= zgWtJ-Yf$e!LfpPj)SR}*G3?n{a>**O>{Hr#cQ~?roit1#x${=6L)yQAc~rtY(j3V6 z;xIfFc}2MN@US;8(Dkqw5h{nIqF0APXJQI&GRUS6t50A){tzxe)ip8uu-e%f|ZQUGdKuHqsA&y!C+ z*-S!(KV!Rx2cV}j7e_9DrIrFTC`6NlgEH|EWq-^ zkmC-GfP!^?1d8he2>Cuy^M-9l#aB;$#~_rP%HmOSPNw~lEr}n8o}${FPTDRB{8D-Q zvOf9h-~7$rd<@cGz%Rhh1pF@FuNB9gw`p&^@ju^b6oA`f>P&U2mqBRSx^?TH-g@h; zcXGVOya%y&eCiB$loJiIiYo_&5%0-H@+@D(ik*D%Dlf+@V^#DgdT{Ca=N10}sT zNr?r;vs}+#Ts{v2E@8ag82^Ar?!-au_t&pqFYrsGRPS$MzxDj%9{k+%gpdIIw_rF^ zsqC1*TW`HpUshK3>e{tyzeL+Ya>gVhju=1@%Q6?TI;(;=rh5oB>ZCL~b;d*8N2C}7 zH5io^Vj%ntCXCD{(B>>`1ACDMbhK{tvY7?y*|oaO%tb+}cy-Xd`$UlV-_wi^5EQ$; zfvCBt3k$C0Ey%JQr)()8b}Ma4-kiUSq4xH&mf)MS_65IIek5opIpcc$!94ohb$Iu1 zWDI*u=qZ^UOs`o<&%Y3TpGiHJ2k^Y?wvZeD{rRoW|H0~#n(!+M`ht2~i#voYvo1xtxWeugjZd*1e;Ixcp^jg3Yt`2J2WJZWRta zGnu+8abI?TY?4NXN-LM(k-Z4;Uj-A;_&z=vgUSoRKRmeQ!EZnF%rgSNdVTBpqu@8a z-hscCvI zL!~^HY}Vqlg^DaSeXi>OreP!=WQfmB`IFmk|JoC8zPa73{SzMida!J0W&{}PGQ^#* z7pg9DwG_)n!FIt!1bSrZpbDd4Q)6S}oz#Co9y&2LmnOb{XWPLb*?Ec(vkFsX!6z3Qf}`Ctg1kC3|()0zRZGk?z@oK8709IS%JbPOzB${%Yr5Eni#6#fwxH&Dw^I znOVHb+fy1!+w~d_msTj}ep&JiM9LQ754dq!r)Sd|19$ts0Jq4lgE=7imgK3`3?w<^ zRJP{EYTD5?YK&-2lgV^4xj)}}{N*K1+AV$VIHpf9+4C8#mf8N(CRJ}ZA?CDyArmovXgk5Nbmc8K2GgKrtA4V>m-7X(;$h<-u^)^EGgGH zhB{N|_Kn@IW(5dc!aXRjlG?8X(&V&3O-U(^JwXu>oQ!MFU)2&X_mMEx9fjcJukY(f z^yC&$q65f;3@eY@ZRtw--mhez(%kcz0ORJY*xBr+Ut1h_iIaPa`@doc=L{G#*7g68 z5_w?1>a6BR=ux3M+mRiqD+S#ieD+muu680fy*^XH#K+_yJ3_HOb=?s1cbP22=g}nb z_0z&sHQ1MSe3DUX4ULS?wcA&OK~8=i$25n0_b!`ovyNp1zqIV6k2+ecB6^R7P*t<~{FqMSABjhxI8CAv2pR`iKPEckx&jrhc@ zg;8{*eoy`O_w(G;>;-j~W#7FG&Fr5m(P@3{bnh;cB~T7Qk000p34|#2dYd`gTk{5L zcUIyRvA>$V8wM4<%bqeIP;k0{z(eiTiwHDt?9?CvuJd=~Y#F%nDL)_{4-EWU7|IK6 zQTkgDuYm6L9F)J1-(G+^q-B~T)jDgJ=d<-v`Q>O&z3zQurF}>9+&4)(K;SsRBR{^V zv5jpVtPL?9^IG4Txn9gxrV`LZ5EX61 zsH2>ON)Io3+(y#y5~2fNP0@pSX`UXoNR`U6Z6uhb`UsEG?o|o9cEguJKfG_Bp7L2u z2?>=8mD~YZTLx&BWTDu5tkRzp0-M86qqolN7mY%#n}Quk1GCx^A=VjYh4ss`O`hl% z;J_`+*JHu*$%bq=9))~skNmT5gKZAoEOjf=`sek!JPF)3BS`B{%*3wAxu-|n9Jtle zl58|phkQbRjTTG7ZK&>NpccrMNIr{?S;kTMK9r2+3vqakji{0ebW&5rx4GvGyT|e< z`5WZNvjBIQBXTh)?f2aW=Wof!EP91RBaGO5A(JbQC0MXl6hY77)eylz%2c#}AG7)# zctq!`;|tg)Zl$tfBU9kHvyuYcYwMaj+J`CpFA^F4lqNWI*+?7{b@*HgR$4M$L|!3@ z7w-87=$?-3%1^GW?3LPx{^fn%!V!!MSXe-xj_PZ#GEV*J%h6g$8#uT?)3IFVCn6=D z8YYu|DnI>z{7d*UIX6EqFE1?bySXi8`>%FSPoB_+6eD25y{!i**F~_7@{e#$uqNrg z+;Aqr4!ftk-}B(VRED1jT{Q_wnZC1MPwE*v{}voz=-7I(H6F9;8{fN%AU-$qW9eyoQ~TbXn!4_tcCHVE@btE5B)f5x zn=NzUW4>B*55`!SvcP@ScCx(fJldEhf`+am$l|~_^P%$`n0bW^;AdbRPvFgC+vb0m zP&YN#DV^JRL}SNNaJ5TFv9U(CR?0Lte})FkR}hLlAi_x4>L_3<+z|mkOO5!z&cFo< z1n)5h-Hw8@jT}2F%%^Ad&;L!I>%7%iE&slh;0_Pz^CY4|TIq*K>||{)4(lgPb;IL& z(%Zz-4Svqm`GMp~F17EnsLJaMi*C^m(oxa5?vEB`QnV(5warQ7sZsgcRMVDEJ2yr` zDrP37?#KdWs+O}qzTzqdcoG~gC1g_g>7_Q3oC}_Ci_-aHV5zfr0H=f>f9Z~Gh$?U} zAi_^FpX4AsbTnS?{#EIkUztK}%S<3eT!M?O7Z|Vheuh0CIQqWg?Mu-ArmZ7!HZ5Bh z?-yX;)M*UT0>5DG3D_!1J6Aj%Ql%a_7xkO!{c}&p2iz;nAZE`w%1!>^eA#}JEgJp! zwhet=%TXaZJ6uB~O8o1pi#S!y$!ez&^mZ`%rId@&fE?L2E!7(30WI6vNWVzOH6wl} zefVTd-3zsVbYJB7G)djWPOMXZ?*lV(J|%mQ38@7(a8e>tk)VCV!p}D{^wh*dSKP2V zWiO-mhmIkomt#lt5Mur>X|n;Hp;gIax~bIRAs})t(#-2;%fvH<-c61dIoTBcIzz9& zNjWSx{s;`r^dXB8v}*Z$WoW8Wj;-EbPBXjYXxneziGIhSsPJAwbIeqdE64AQ^m_ZK zpsjsAHy|eYz3^X)bT8_4`2;aw4vkt7kX1m`Nhvn>`QNWka@ZdWq5w>$PIjmToN6hdl;3BB!=C!15dJaL^xyHUaZ`rcX^U!TdZU(E4C0e zJt3{&37hrW!;WV^Jmij$IsdZOU-ir~_`q-*)Qog*Yo`t*=-5I}tmr!*s>YO#E}Sa5 zB$Gzc^hi5Cbw(B9+XRk`Beo7a`dKxM1wYkO=h8EznSBMLfC}^ihDw@Ad80o<7eF

x7$WS zTYrTz?%C*cO3|ZZmD-{UL&TYsXUIibhyGa;-JWAOk3W4P%5*?>`I6dc#?UzSiI=@) zb=xIIL^pzLslYO7j}|Q)IAZ+Sf`(=1$4Kg)2c7LRUeIwTlDPYFK?$}KfT6YsPWhIJ z9!~=w8vt3cz>C~xvMe&^%fmjY!*_YMaewjd^cbo52gjQ7os)qGg7(kokt0HXdxAD5 zpZTPm5?ETP>(CyG5(#xV4}ri9wpBY5pK zMZ&`!2tt3~g8^X^#iH|#-xC-N2lh~(XS?6V#WqN|Q|fT1>mmPmiE-Z{sZQxeL&UAy z*DrOTbXIvN+!5#qS1(a{rh1>Rb9(TUPeTl~f+po^5cnfDJY1%L1l+&NRHSFDlo z9!+oi^ZL;-KiwfSYLMc0g>)IaraFID`QcQ+LEB{5$7$?A_9lZjM=yJU`H&DFO0Bp&j4Uvf#6LNt)Paf3^vr!5($B zy+nB`8D51z;2%)DQtp=9kW^eMxWBVh(5rCn7|?nf1oslfKSm5>2WtN|#DwA|up=td z=Q4cVKj*uESjL}Gy%s;A42r3*djC^tnLc{geYpfDGPKb#@3)a93p*SL7X>xMz5%t0 zEMsz|IxUz9IBe}RY>7ng6~#XM1;DS~%qTH}6y95APQR6kJb;|V784Z~lgGO?gVr%^ zi-NTke1n|&MP5k}H!}V=9rEW>c5!!i#WNo7gW3Rhhgc7vuq;-@o}W&eq`o z-ySLY_-lMX?!wBsHod4hGgq~^GoR=SXs?n^=hs34KFZUyGRE%|=FdQUPv>7wFaL~j zFW4jc+DgTvtW(Sl#f4lC=cz`_w_MBzdvQcx7I1ayj zqWzm;pV*jt$cR6JzhQ|D=TX*oUBy(TqW&yTv%D)Kp#mt7Ubkj(40c# zB}nMTaX5Vr6scxitSA)FYclLqn753Nxfs*|7Lvd&}i0 zy*I0Qp(`~U-!g-j1c5KUwzn(b2Scj(NV})Jyu3e0KENjkpR`orNAlI@p!W&^=P%&_ z0RbF8T-)xV#(nVzQQN5%E}=R82C6@n^QWhof2#Eh&DXi4?J^`ud&v`&R&EjaRX6Xs zEV6%!1iyOCv2wQfDrJ}H ze)2ITfF9ZrKs$GBlI7V@ocwJ&UDUi*dd=f-pD*{K3^&K3A8vP*w6Z2Gv# zMPv_6UzgNL0*Cam_0)Rh8rlR6bs7y7bC0b0t7hthsbAla=OPgRcxTbFHia?}XJuwp zWPjVuyW{uRe#29%qNI1X?~Ch8CkzVQTw4!$JHnE5oXRkX2(tkwG_l;7dT^tJ|6a6cc(UH z{C2(YmD7g48hftfoi&LQ%Gl|`#BvgP-0=T8G+EJhP)1oUl4qs*stpvzZVo{JqZATO9C8Hv|B99DxHEAOS#nOau;$p$7nxqi_VN0MI7B z*aVSWf16{Z@ljqe=ex+8oE0BjQ85tMEvP~;f9 zBM8|50LB5V(DzC}Vs*p2Y=A)kU;zXq+y>C|YcNp&h-U$Si`#&^MG&dpnLo_{mUDc4 z34k%~yEHjIssKO~8UUC^%L4d`=ty}90g_kKNC3ep+M5{#ARv8xg-+BJ@8{N1F=^nBcxK<~`j(CVe*W{P zYFUqxY^P`KCB=9U%jKVvNh^wf#Z_gMB}@YVd)4IuQUyLxmRqb(}Mw-S|$LKK$~fKI>iP+v4)N{r^Di|Hwv_6MX)*_a7+C+VHo|;Wf_D z>dDt-9RR@JbKInNY)^dd$1>c-Bmi(ejLVlGO{meHy1|W};X%!<`!oN6 znx3{m;puc{@;^|QJ%ckdL%%Nn7pUv&{|(B?PV6246cZEmSWknJjD-x(F_c=GYK8y+ z2!9CzkPzXE(>G&ydH?`D@w@}59AMkR->BJ}X}!?Z1>C`3lK_AbP5|(~pWt6C_!pkj za)AH>dzaNrc)`bB8N`QYR)i=Q1HqvB!Ex&YT_g?v$^UCca ze|z^>dkTpmN)VV<^Vs8s*dBuFcVz-D4RI=|NZ~p=>az;5@WY?sXrngITJYXgF6{O)zI8#T-gulflS>%8s}rW_ahz$ z{h&a(P@~G_MJBg#&Ri$ubGSNO(J`F_*v*FIa~)*1Gbb4?uWB=?Y9n~!CU{|~uk@1e zulri|&Q;viUuKZhJ+ND?`dT=VPtcV-A?nZXin#hY#}+*$_p|m2*lOH-!>~`#;EQRW zpkQGKlIJ8|s7@2caAB*pG76MDIV$dVfneR=eQ#87k%G@Q@id8eyJ5zj^@T;{ShpU+ zeV((c)VC^n1uuPv+C|KYC*&3Wm+Y9M5X@q+%?MFv+P4ZwHR7m`S+FFlW(?Y zsu`%C+x}dIE}@@rHg)#Ug0re8t@*6?uX!xYZMW1NyiDs8s2i+1-tt@9*%^0THFthL zipLB@#oeV3070&}F7ARSG6?1>y(d!ov#tg_Kwr<+Tqe@`*LGaSeRs-d>jT>?6vn-^ z`!(w_^<9m!ochwLQg#g6Yh24ZMiAEUgL$``LItDgzr5oamA)0T!W;NOlO^%85Or&g z|ILxi`8cH0->!Y8&cmu9uxv*MQRrQ&kfKW&<)S~??`jlO;WD2yoi3F;liGh|yQS}J zTGq_n!l0samQ^ZcG5K`i>10Lb{(V<;$!$Y8L;pq5vA@%mxx@U|yxCxb8nkblOL>Kd zu<9Z&vNMI@ZN?(q3Ey*)&(LnY$6lB1l*b2qyz&NHKA zlLeVNUDuJbOqCRezf+#i-c?(VUGRNmeS5)5yXrk!-lM zYA!i=f@Lu4Y|W!DBlW}wE}V8^Ey(rL%l%RR<9qZNJnQ^dw$HB6n))$jO#Oq5pPmPN4ngIWiP^FJMUV4WKkDewb) zSf7~`yAQdGBYkzr2RdyHmXjY2Ox{Ty^37%R$^3yda&jgxAX$&sPP83J0I0fOubSE| z=9`TdgoGwPFbc5tY08b4)XvlyJD3jy=&Mv~Lyc(mmfI1SRJ=y8{SvS9jM}C9&b~Aa zTzia-Qn1$gQ)u7lY7S?+<^xqWo_BO5k>n7#&@|xI&`nu zk9d}u3{>*Zdi8_8UKFKSZ{v>BI>s-i>~c(HIiK0w;|_)EskhEWhI&{zzeiVRLVWtt z@cER_1l*l9_x{h8@_;Ro|5{3eZ>ib;YH7>bXq{Wntc(5g`HH(~ZmdR$@g%N5D&K(z zTcFI=$+czm;|sb4mFrQprb{-mt#3GDX#1nUB>vZ;VXL{M*W5&CEn-c(Y~wd&#gO@8 znDvQ36{_~q>VmOXB!RP<2;3YuJkV?` zT$1J2pXCipGIm!`-%;BvE)^~!T?){Bu82E|4-WJR3JRj)t|R%%s5PfTKirXZ$ryD( z>pArRoV}8|z>8%!_`di+4b}C;JvbQG8KHQ+q`aM+%cR~I1=S2ydem0Wke9G8ai7Id zp$I=Gh?J~TZejC{ulGz$+p|xYL6ejqVOyE!B)gJ$78dS56M*ZRR<|1YJf1zd5%$@Spsxp>Rwi6Sxyki<3U$iwq8X6Pf;F{B5UtGgdJ&hX>1f z#P;RrOFZJ`Vxk5+Ga5f+cMWoDI~SVn@@RH-nwNG|O&UHr7gvFDdX9Q1)ZM>d=%Vg) zc3^&1F7$6UV^QhUN>UB)bVDgM9GO+_{I<~Z#y9Gw(yeD+lC+7hE2ppcA>&SyZ|ll! z3H))C9S4P@DE;5x=K7uHRRj5sN+P$nJsYu*OWvwO)~*E}h4^F}tSSe3sI#H{tRhbY zAEJ8NAel6zE;6K!8%#?`)UE2U`?=vIKNs4gz0rT`%s34{x42LN8NcIawn{$yyz+Jp zoh+q0?5lS*urrqsq;guE)uWKIAvTr~bkV|*>E?MEeF9g$7Q?3-aQ4pmu^-V%{pM%z z!|U72qg{kNV7vpU-47-vDx=f{x-T)OMmqMRZU$;@2pFiRa+NMgf3nYhhS|`{!2G7g z=W{v2Lw zYjl7(2oMNg`7;!#f8SV96I*Ap`s#P`qn zVyXH0GFL~I%YNo{v?wsk1+&>EWay|EdbuTr213}fYEh)(`?cAWTP2kzQ?|El6^&$&#CI?ws>ha5<=*TIXGJ+kQf z8+@#f?Op7^UEqSi-YBp#wSfv$i-?vcVMH&a6Wf;r>=#I~>a}ptbaGIz-fhg@_V~#8 z>IpP~v85a|G3&&Lf4<9_>`CeD2gYI6&r%DNM|}GVoS5Y3Q%14bjPFQy&~Q8Ze(i|q zXWX-84zBfTU(Q2~Ky-Ih8TmlLoy{K!uM~;GXbI4qo7_aSoCzapkjSZizi7cw)RmhW z>MUH`;PIGOmG&h5vDIAoj^BUhl`7W@*#w~m#7u-sTJg;qFRG>6;sfW9gcvg{Y3Okv zuwAV4hh1!JA9_ypOZ{VdbK5wbkJT067qBxoyLYDIKPuUFzUJdhhy;?N#A)ya zDlszjRQsu(-za@=<(Th!OG-sQr>czwWU8*l-2$HC-kuHFWHb72SuQxpfFQ~mGHv<3 zH)JNXyB3RXvZ&(SwVuvxW1lXIKzIN?zK-{m2Pk1xy=kUBYP*n~Z?{}wP+9_&@FC}D zIECx%u$$4C6p@;rYUAc5m~mkEQD3s~8ex zE_|Tg0j0)Qy`M$cCxSS){Y;9sPo_Bm*c0b36^d4MB{_jY?OzdB15c_Z{iDt;NXIoP-pK7$RH0994NA_fEy=Ym3_^m_ z=D__qmtDAe+)=k8-|$xIu$~H(1{lSE81d-KjhzO>w}14WwZwh;x4AvOf>qYNO%y0f z6`RSyddeUTH=i3kC5Hc_L@SZ##WuG)z{d|S*Xc$Y{(xsE)f*9K=qf1o?oky@l}lt# zQ=1wl=|xPf=bT>E)3F96Y@8$zIzcbiO%KZbYi71~u0Hieb;QiQg$RaL|2Q)#JE$C+ zLlVV%Gc8FASd9r#?t=hAte@vVn!!NEPkh`1bH0t-kweP6NBF?v<5R|*rW}cilur6F zk1H-To*!hWfsoUecS(@W8KQ^TZ&Wev==?F$z|%)Oakh=SVIyHKiC7})E1u<1O~MCD zk3|y7NCNxo@Z<|11j*rA?R9y+CRjpPTaE4z!(si?ZGv}QhE9UqnX2YnF{aHu^ zmbxpLm{SzfG>F*8C#+T!7EAD<(e##q$QCHN$uKCkcQ!pRytSiCnWgx~p~*1?_k!dz z0ZLkTvMF1{9zVV1dj3xC7jSPj`PU=r$CaxOPXzS7KZy%DJ!=tZz=+jbv>g*{}a)F=%4Esvga zK4bpoSgP&eeO&lPVCW}f8{|K$)Q|oe9-k2t zxc6IoYOEWY0%!tioSw_aM+Rlrdz_O)h@ogr3aFcVwHT^3RHY`58s_J2iiOoJw9$jh zA9OfzGn7G3B!Q3jm}7gawv;L)A*9IkssiWuOvNrx4}2LqPe%%Hr3tlR30gPG9l)u- z^|61M$+GKJwzQ~Er-;E`bSMVmFbj&msX&y(lrU_ZCL#Eb`EXF{3r#13J6NA`LHHn^ z-ldJinZ&^pZxcjoy^%vb%{i{w>ha?Q)ZsUE`Qc=36d$kpu_RygTLP=aV-?- zzN^9h^I+9f4db!>xik?YY?vsYVh~ZqnWL#_9pCIdEeMQU_CKz5<)nnnNjaH1)p=id z)lHHjQ=X8V0VhDQFd6^C4FlL?CWuKnG$_HhPM2GgLXF_NqvDVxug*o8Eo8VMiu4I( zs^G102$fvbQ_0}*x3f13Tv%CJlvXCi?ZDMUjbt+EN;*!PGH~ZTE#i6@&1U#%%lJ_` zUSwO=>9Og7n9+e?ryl%if2tU*tm1^dvc#e;)v+84rJuXBl$9$)lg~~< zJ|l!uK7IA6BIJa9(zyvBRbg;y$jkqj8zw^Vb{XrKVe=(!vEm6K#Fgw*`2=xe=<7Ui z=&y*>t%7i4<$TV0;>5>H91Lyf3zks*BMM(g=4ChTlH&k#7@-(Q?zaa{CW^f72P?tA zI=7`CD%V-BdQcE*8kIIW)Fpc|gIq~=e|q!bE=|LgHX8ZURz|cLU5ZGL_*O-}>VuV- zj|Ojc2eG?^4Bwq97xaziaSY4jq#g%E^X7UA=BeGy`R!q5?L*^&`4OJ*kMGugEx#O_ z)L7+EM@x9+>MgkXqgl2sT~>^ab6m)PJOo2YiKE>wavh}iW$}@$&MCS)xB>nVT+ec8 zZ13HTbtWJV713tFo$!UF3#Ay{oR4;Is*q0l2JLSIxm~6OZKb_Sxae7S3sr)V;YB`D zARy((fYM@F?0%MC-E6-%5-;T^Z0i`Ej;kG(zMRGn5}NdiuS=vs;-bIfy5B)2QbVv& z>W3JP_j*RK=OECL>jw12MY>z@=efs;0pr5_TWZfI5CEYA$4?v-6Vflzb*auVzcU|* zQIX2&z_Z;El3n*v8BH~BnOy5)dpFL+P zqItx$n|M@q6d5g1R+M*~8c3uv=Mnoc|OatVZoRfXH2;lG@nITPHD>4$9~aB`gfvK#RM7 zBz?3^NCIfOX*9JiJQ57*Qo7y!uv|4es8a7ulpBurNDu-ffDqW@1#v<(EG-CzRwGGAU;PqSR(f4D z?-HKOP}JXFs!$R@0y1?~JK$uR-^`hoA?mX~aZ#rUV&3xgxF$Use0w=qOM?%drqLBF z_c}t=2@&%YtM;<9jM@A06$S#-^}^_q0NOUSNbsnB1(IuHAKJZ(7dor?;hx?yBLqPf zOr}@6Qa?Um1|Crxm{QlxBM6m|#!3Mw7D=!rzil95|Gw1+9>EV;m(spenj{aVdBJWx zB7`9O=6rVi-u43tXUF@J{#uaQ>;@o<}n=w7Q_cm%4N31*U6YK`{ltc>iOJ zg{aFlY{4@+^o_*km3;#Tw=f*KLOtSFEO-LsuY&>!09uJ_V;=-dP?X{)utx zh>^XqZ@l_$Q?+=iyiZOC^^Zm8x6I!33|3%Iw$;#FyeBc zRH-;n`c&IMGx3;tEI2wz$6&b_v6AZ|N!F2zdaI@rdo52rN7Kx?iB#nOUf$wRDAx6P?T( zy3l>!?m!NI3Qw!+M#QFdwQhmCx#&Rpb;dLA+mHAb{L*#5aKLv08+QKO(p_Tguf)I3aQ7^j&Cad=I&B9wO&2ujBvQ9lZ3IcYS%!;I=$ICyqx=)hn)fee zJgUG)zRSDh4k|jNBz@8bFz75*nQ3=@vy=MmCrXkxRD`#yg?ePt6f^_>=--U#BhdKc z%6p~5!^89V;NEWOvK#h+Jcb-e`QG8Di^e(IhKM^E#gE%lw>|vnRG_#asipYowfC~Y z8^)4*u})%Q_fw+)GQkCr*7CUD#0rO~(GGNZ$0NzW^h*N?xm)xLEsN3DX^bzFHlf~) z7~V`Q?J}b3erk-rH=4BVXIR?TGGrr?@s`|~`D7bD+a1|fL@iqptS~?41^I@|MAWs@ z*r`6nPnr(w?jL@dFY{ahF}03QPTil3FCfRzcZf*~Tgr$38VnZ%#0u_Q@YoLC;)g<3WFwsA>ASgCSruh8bDI?*E|04MM zEyuOZ0!2AiF{cJwNww`+4E`>CW^lsWGOnfgNGH>$k8 zewjP4AoXvm*2ZsUggI}LeWEdIXjXUs(F{Gsqb@p@%bT>W1=u6Vt`dKRjH|xC$5U;k>H<)@qhIJ~_)Ltmv<`bIEdlj3|- zzRjb*BGp#Um|JK$L2f;5$9HK4aCzfBbNhjDNi7VaK& zk`d8yURR|>qM33RGHFDfObR#&w{@%y?(>nccEmls^6pQO30_gPnJGB@Mf^<{Lzva! zdM6{*j_;UpDJ?O0`Em`tgV*u32nQ~a!=*K__q+7z;16dX0-TyQvhVY=>^e13e~*9X z`@5U&bn0sZINzQ1TD>s7M1jSiB*Xec&Kyg0UCrgp!|%|Iq8Iv>-mFOfr*85vyA#4_ z*T<3v-~5i}U|vmcIPY`JM6L=xE4AVyd(xUSEn)~C8y2<}G`UbA%vI|Qin(|#+EtPy zK%|OFsHp0;j^6Q3X!jtb@tbQAnE53#Y*d9f)qtS_U-oBodkDU%8s?iQ(|oZkKXHGv z=JF=sPXCuS_ie<_nIq&S{pcLyJ#efwiC?!fg5Qmgn~sOT`vLW@)^||}WN)aHleyJO zm6D*+74^5Wm-ZF4ulM7zoAK-jyo~uSAq^ukL(J`jL`uQ|4=AHx-jT(clIyxghvrmL z%;3xpnORH7=C!WT-+SsE(wx}jW>|_H^O44D+z)ES!0omJMAcQW-gQiuEAh{Aw@D)n z5j?lA7F2!-HGtQyUVNOuh9TZ}0mCj|juWUWAlB>QPQ-Hjkiy%|{=Ai~!0$OO6xC#= zKR}_KY{ShDjlSoKObkl7JZokizUy6AJ+v7GMv>rP_6D1vtEVT0u&W{yd0Im2QLQhU z^JtLs&$14+tOP+(6n_g7Jyi&dAyPI)UH>%_Fb_2E28P_pjo=r{HMW6p&uc%mU3wh% zz$vRB9HYEhT+jMhD6G9~RZsAAoWT@=Q*uS2dC++XZ}u+zj48%YAc8fzqvhn{jFIT< zcayJV^oH&34?4a+__H|Z8TR81R@NcEHbE88Sv6|cxD6#WndO?rTPfxrMw9C z=B&V{LQt_qQO!`KUqP;Jmy%dswCoOfbyczP&xCCwnGz{cu+Q_=xz2^)nl}H9gAaH) zi)r%I$4Uh~5p`@T{b9v@Bb5`4JR@flqBX- z7NtJUaXr^q6``rFp6#AASvuwc(2hhrHrtPz#ljG9q^KDz%bgBDQ)*sj_4dZUvT7@+r)+-veB-~+OJ7Qj}_^$r3<9tD`8cFESqZ#~{%mQ_tg z{{%;@^ z`foemvioMb#+Tq#bV)%&`3LcmU2%n18PZAFZgVA{*Q%* zALoQ=i0x$&QKr22`i7D_%#8(?Tp+aKxi`BrQZMq9oeT_>JF%Y7tVRSRJ6>9cghMNelx0I znBzLFp?LiFNT!{Yq+_CeP$6JCiQr>HM<0CMpU651r&6`Qq~^~O%hur>f=_CD4-ka{ zqYU3}nngA@&LCOI1ypuz1UZiGN!>_~AQ}J5J}|LxGq)hG`BeUc7!9D9>JL3(x++)E zbGvyD(2GZ-_ea_AX8)Idp?J~{{73rk|F#(E6R&rE zWqq|nV{pMaau5%@^n;vT9s_Ix)X&9n6>u%68bJJ0SS4o6y68Gm{ap5zx-wezm^$7q3VlZNF>|>kVhW}TzLn|4YyK? z#}X!hyKWOSbH1wweIk0L%qCCmc0e8!HG|WbCA+9rzmWC|F8i8j10!N1Tc-m)rl_)Q z{Ggxs@;6>CVmB-mE|DSuv!%$)HbP$g5sEO@+o@k`WPe}W8lx1A#R@#EN1|?!?ZL!5cmpoLAM@Uh@A$!6N^N ztW&?!1CoKVrXXc~%xHUeoU})?u~7M$vJSWH&&kBj$kMC+L(^8TCpa~^TSZo(%eudh z@^+z-bhkj9>;|zjODRY3-2D3swR2>Vrs6);iO?mi6m)gr{(}eC#7rdYKca@7ZG#)S z+Tx|q9zOe`qGTpJ2rIngpCM&+6WiZ!Ik5B))mf}D7I*wCU{Sum!>TXCC&nq?SM@q- z2aes;Q1qwmIshGNEiX*np%~v|bO}Wx7+&;+aRlj%<|_t0I4j-Z8-d;(u!2UtaGBkp zwX%lSqZu+<^xdWjr98$9x3|DTSc46K%M+zWIe-c-mHxj!A_za-id4F1xgiE~7V zO*5Rny0JkBQy{NzT~X(XGriOXoO3b{r9ZCe<=i)N&85lP1|Pgn_&i!tMyz3$Ot1O4 z_U-%iX`({lC%|?aM!8NCP)p}HLqtDM81o}4@aPRMYK86z>V!*%Z+aDjC7%vnwBx{- z#rXwgw&w2hQu5OQL5|+y@Q)iKJalK%`sNGJ2v_CB>3EE5n_D|Gi5K=o=}Yr>Kb^lk zTElB}zITM~1ovCad(af*NkDN@9(&|!^zSXm-PU6A10Vr(l@71hbpmi$7)kI0n7<4x z>ooG(N;MywgCTRcXA!XPv+uEHKDMa$Rj5LJt;o7Y8qtqJHigN7@81+_rZ`@3 zlJG{AG-|vKR1<&@dbqEzm?+5J7df)Q1(h;f6ZLkA9&hXqbf zYC{y)7>F-2R~OkCk-?9yce-2&ssB0&Gg{!i_Zvk0zKU+EcEcmlF{2mtX9>64|K94~ zdy`0ljLA`s2!6H&@V}O|y?*9}zIjHbhvgwb9tcxC1lh241trOv_On%rfY}zOsVS65 zn1Vm~O3udREh$7IRiQYGfZ{~%d*2h=k3@}gH2kYW>46xa?Nj+zhz^*1+nyC90C1OB z>^2hx0cQVQ3sISOJRds}pUBN!@LGExYr!Tu)(=$e?rm}Nq6N_cX~8foeb${Q2$c1t zI7_pm=4A$(4=0!w^f#<36<$h!N1d|fhF?UYRvKn|&s;X8hUX`7kB;HIWvsKt{4wYZ zZRyph*^b#Zb__RYYC_7hGV21#9*fQYgqyCU9v-KdZD4ECM9_5IKEvy4PKMOn23ZN4 z;yra~u%PCf-nC~_xz1`>iO7qMp{sZm?$$^%cmbY1ktem@DZiJ{cssr5@2Z`1)fL1i z!gu*pOkKP-OlRMK3GHRbn=|GFg?jMV0iV2@obN4)$LvGzkgd+4?0t`zYlTEv0>cX? zPMssjGJ}^mlp<7a@_aYVk^%h8L-9%;+LjhFp_<+*AJ18X{{aSeMWGI*joCKX&Fo9d&GR)QUbB8QDQJ ziKDgbSndoSddHnX8D`CKm*Wf*Qzd7u$?MVIh#E~Yn z@(p}dF>F4FVs*d1`Q+8PgV@w)?twt;SvGKZP=#J?PO)_2BKq=gVK_gBPh_jf^=tLj zk7Q$PKEz{5qS^e-Uz&S_nf${<&_|>!OTw`f2Vv5i8`FE5r0w;(Ra zQmUnyIz2d|Zd&1hQ8FpBydw5XY*UphCD3`#-RTkq&~*AhvgpB0rbGFGgnzNx1t%-w zG1Z3OryvZUuDVsfR47`HtBjxpk{)T02lvIiy5XCetg`R0#0f@bkPRz|=(%{`xTdvj zo-h{ctLIz`LE5{Jv)H;!+|Ne@Og-r$wOyZ0pw4lp^aq0LIe;s;*%URbDndeAb%`5> zeM)hKwJB8$OcM&&zVK{p;#{2go`#x*lLB)Yf3#p;e7_9=$_mR)OEFWGi7V0OMl0Fo zPMJ4~f1h@K8<}0jnY(z*3GmO)gC+rHsV)v$=tz~942DjKxfv|UmSJDMB3`IgUEZrm zCW_^xY>a8$QGd#lTdcjBLjp_;h5-y8J^3slgtV_D$yzhc8Qq~kxeC6oJi#pdj*mZS zJVm8WMh^ti1TA0FElb7qEbJlv>7tnXaJP<(x(2YN=89@Giaqo6GQsp`jA{UHXplTw zJ*{oH(fy{~XWLor9O{?0VlV9%cj?8s21g zUU6?7=Fs7kusi0k8dS*%W|Q!YrMZ3QPfbcS^_f1oN-kq%fd6ZmT~(gKJ2v1%OrmTm zT9ZDR-ccjhS!po5j5Obn)HYxAq;;C3(?Y{3LpuHFU2<;k6_Ze)_9yX3=}FayH>|G2 z%bM0Vo<(WzX{0Ib4k5IWxRZY>u8O_AkV-*X(D~|HN?2eN@U7oWmy=oF`?gS$|Bt4# zaBK2?+xRwOG@~0vcdK-_C?O&$Ehs1`1Ega#BP2utr8`7INrBNJEhr76yBjvPci-P} zy#K*-9QXZP_Z8>)xsHP8)~W}gkm!DifD(*i8m|+)#hGXuP4bAzVvi#ek8Bf@aGwsv#)H(E(HC^pa!@+Yxj^nM*qvF0E zmu9AgD7q1cR@};pYQ?3?G8^-O3N=mcqAD#}t=HXgP1M^!WSM`^gU%BXFY(~oT?~cb zqh(lW`r~pE?GyJjV1b4uz=v)gNOSa@k6@N|eol!YA(^Ya8U_ziJP$W~anBm_X4IH%%+OD1e$d233v zikYD#O5vNFkEca^DQ=#(fjB+x#KXfF8>_jfGFIcRO0;v6RAX@L))sOhPC=XX5#Kv9 zJ%wQ!&Jxr;kAJIk=dD`%<*miI(;f1MAMr|2xM4Qr+OBWqkjEb`O*UFqr&aJDqkaD) zV0Sem`98(_D8ko=hSwwangThXuK7CQ#@J>&KH3xA64{%)<{^{V0@~pB?VM zZfBe?R#68#N>j8W$DYqk8~4CUe`$>^4#CQx7Iqfbiixbri3sUODR4AVcIR2}PP?p~ zT{|{;2W^h>)_d9BKGnYX#IXI7B%vm96r+9TXt&^dzD?Q=;mEh+sHV{jN)Ue8Sno(2 zVj8XR#NFOrDs#muI=B&gYuLIB!9w5b*K#>@@-ma{R69dwDa9Cr$)T)ga)KR#^(dHgwm;AacE$xifJzCx^!A3aBPK@;}ryL~qTou-e8IAMRIHI_}@ z3eXZLsmUq^^EC!%5$kw`=uu5giy+){=ZMjI2`Ps?&L&+Q9nN>A-7i1Kwi$%Cbx4FR z*N*~vaKH8+l;c$p$t~LWF=OVNUTu=XT4ka^zpooG6(|(^rRzL0#N}b=ZtSK0dc@h_ zYnJP{BZg}>hRZmNC|*t%osHf{Vc!noC5R;MUEChnAxqPDgW^HSKh+P_`fRYyusd9& zA%K;Vuwb2G9sTVnuF0b1f!N%=kJ{OeO z>m1!7IBOjI@>KN3$1tZiXex|)_e7y-hd4T<@OwQs=l2Tn-+ZgDKi1rhK6ZY5S97DT_|zQUxm0@YN(;J<%Xs6?yAoVWJOq7iExdB5#xni3qkiU`Dq74T;Glz zqKIdf`Y3Au^7+2Q@O;kFfNc;8y?7}pC@46pg75wwKs|;Ha+1b9z-5)P`>rXKX}g|S zR(uN`Fa?>m=KMzrA6&>ssByz5BCb-9_;djbf@hzdclX86lCY7yt&J11rLyH|k9714 z4Z=Wgh$Gs^?<``Jf28RY|6#mqLuuXS_A&k@w!p(htUXfl))R42w`PG+BO6zvrjZ)V z$EYOX3|*H!(Th4OjaE2fq@vt!$TS&YW@b3_Nx>ZHp*HB~jWYEcA$<3{5bV?CD$TAz zmJ8P82bYuGa1*c4^p+CyQ9Ka`Kat*kvbgypK>dhQmZF~eZWak8ms>ME=h7ax5!>TO zArrZZk3z$km*Vcd;uGq_L60xLpf8i&Fy->8uf9;gIr60!0*iG^yc+b+?>kFsimqoi z=|W)2o3J407-_)Zx=_9`K4|Fd@Z4$x`nNBa``~A%c**1I6L{Q}!Afsf|6OB(M%Q^Gid^}|b=EP~VczeTh^AmbKK@OIG zU&4unxf61@O0ERT2Mo{>48mUFl{~Tg!4>L((HGNxcejbxts2ZAFwi6m*66+p303%# zm*QW&S+GX~UceJFbw0A>4pW$)QKEU**I`mi({5vz9*(~t)7ML`lR~ibz|c2mj3lOG zvh>t!ABBzrfvx2JTS@(>)mS;{9JTfU+=NdXdZEERyWReT7SO8=(5JX^U-%0&8uln` zq&=y%#w&LQU6Tx3yd`V(vj4`Yh^IMdVv9+y`@Et(SgtQ$z6(W2vducf4ijdCX!UI+cj0$MbTA>|L=qdcqLF z9TogG(T0=X+k)f=Eid-gs*=#NLWJF}{!w?fv{raNmh$K)7Q|`END%|2;um6@!D7_h z+|IBgW1Sd)!*qC6rj7wE#BKf}Cx7%wck9p_e($()kgqMmKj&Wrp!9CCErs0#(LRt{NbPNxP;MlE9_=1vMy7+pA8d{wOu*qT4H84PLd)uc^1D zdsSv!4d*%*$Vh5<18Wb{Zs6Pp5!LP$8nS9R2mEI$PO>+lU-^c)oa%)dEF>-t-};_WS^Coxe#J1R z{7)8qrUt8fU|wJqZzf;2@JBVb=}sSQyK85N)L%d0aUml0$lSSQQ9_mvQ#BVYEUWFC zQdBL`9##^wWgPUMz+b%kwbjGACGJ;so*?6p?=D;Kvn&edyvkTNTC-)m&cHtsmO0l$ zPT99HIae_bYdA#X@@l|cS`njN*{r_ELjwx*^oHK;kAr|`e6iwi2#7|K|&7t-Yr3B!w5)Y33(h)Z?a>saXBU1E=#=#yyY z@7)j07Pf1OGF(O`&(RR)va0i&XqiLI3E09%>4&k?PHO0xpK8}BYJOaPYAR)fj|qe* zljfvsvwv+^KcU#5#OrPonND-Q5rm2X8x>*ulP;Q9Hip*`_#C=nu|@XZ)}h0vT??z8a*NSpS9pyXB$L@M^r3ubLv%TE@Fr(bY*X}TtfywPXC5)G7UHdgp! z1!t58b;O>1ZxCG>K!UK~m!VfXz{|ojP>(c(Q;}3rQg=>w$=H&tltbOh-~Zk@qYUS0 z7Xm}FJ7AFn)hBG!Wr>Yx{`#w$S^KKeT~%oP;oBTen-R0Du76?b0)R?JN6CG;hr}*s ziw1U5bt89rA}}dPHEtY>z$|$!`VfJOZ|nd_wpqc>hF@M>G^e3{1fb8CtDH^Tm+tGI z!iruPev$85zToF)l{f!lKle%Bwi3&pk2MuT535m*=QtXon6F7+Xkrc4+KQq#Gw>2~ zS;BEKkw=JUG86GQPkH+1d}`($U&b&cIy$kyyjjI>ANFNjc={Q5+NOx?&|p%uA@2(@iAdhwa>h0<_c zA{{)cae1uMeU#_PEm5CZ95wFekPij6G;t1{MCd#<)qT%Sa3B5mShD?}=t&NDkUch4 zimKsoSs91VuaskwQ9KbH?=z%Ky48rH3y~-t*&a%`^SgBJ>Nxy$o`OnoScrw8EG+GQ z$aRS-I4xlpn_vj>2(T%*<;7AU^Tu2>%=E>`m5b(i7GtCy95%w219v)KeGiqL(C6vH1;N`38+iTM`p zqRAqYk&<7T2N1#^gm%$@CSAF8mXs47Uwr0QtcxFkV%D#2-_n{&;$uZ8(VZOpHvnQw8$Bf^={p`gQ&rAyz3qMF|{BY=R+e)6H(7Ys6y}TIJ2CHh> ze_Hh!RR<^!V{hG7dyMnej85g)2#nr+=7zoHh6-dj7&UrABL`&seaOTSOByQ_nQcn; z2|wPNP)Df1w!&fSrXcku^`7m6?6NJe<+*Z z^DYgE|J}MraYgRtHyDu08L)TS(3@~=cAs2D+jP^`w)?y)vzPyOT!aU*^f%mx0w1oY zrA=%mlL_P^Kl$XcJ@_trSD@R?pY#O26ndG7*|ES83|t?XuVf&0qxApHfd;XivQNV+ zB!b-63JSOoA!LN1)W(u^@1ofnpC)ZZCXHt^Y1|Cz%3qs7F+`32)SC)KD_qeK=Ji>z z%(hF0%XdrMO$Jfz4=F;4QbXN03?rNVL3T+q`*Q_ zrMuDOWB!ZLqg_3hGH;aX37S8fIA|=8G3iEBu$j_UZ=}35k=H-+bb}vtaM=c9jz>A% zaIT7!_w!CSWKMikYF#sGl|P-9C1xG~2o>Q7jx8APoQZqT$MqE%f(*Nscw zohtvZYFW5i=Q;QOwvzsA_#M0SEKozwPeN_%ebOgy2_^$Cep+2~XMXxOE#b@L*FcoY zK`cxvL>NNU$+V4TEspw>nilPW#Ort8k%OLrs>P4ITASjH&5-TyEp)LSI3675Fe1G2LDD?L@oW&h(znnw}{Zz=1H3?}(-6y{wPgJBJe^f2; z8pr$Y90(;4nQm(&J+yoS-yUO}{~5^KeK`L2iJsNz6c|T%QldJSX0%{PK;d%U7I_!9l{iCe0fO7Y} z&MkEk%yf88s3Vu1+Uw&P#o8_YGBR#e)>4S5A*ZmFJVk6VQ1xYyS4jL|jAZa}Tor!( z0B%nfh1tM~n!<`KM0s)A6u!nFV}-W!(Lo~tlg0Qib(=JhYx9#xbR|)*xiFWOg1q$`_Ypg$BY%C{N}G&S+E7lWevfRk;Dk^eF^J zvt3r-DZX{960k&~M5r9N1<1#B$tmJ3qMxGJgpP`(~alFU{+SOv+ zz5$i>OFI)nk;zK=UAbE(rEcjzBR}aB@{exXGSaIcZ#uwS%C}dmiEWuJ`EVUdWVK(F zlNUg}agrO~bs=6^|C4jFkklsIfAic=e(U?r6w9XXcum6H93QB9%jGNPBm>nMTgqD$$v1%5kYW7Bq8`{RI>b>Z~Ze> zp`g=Ro66N@^Ccr;rktVv*vONyrj(q%gyKlbVZz=J&*5vSdgUHW*j3->Ltvqs`9@(q zaF(c0$Jr8M=o0NhZbb1MLTEn48WgQgU#pJsn&gssi)q_1v);{)s%heC=rAszO(IEJ z-e!Cx_>6XpQc=k&4S!7u?odv97+Y#!)d1H@(%7Ww@1viwIybSK^tXdUhEEdzp9L_Z zr==#~LicUKd8?#S&B$icM6*q_!A*qjFhSqSR4sc@KHI_+CuW5ssXoTCi^}R;>ndHrHXVXdz`YmbC^lNW~S8kPJygM{1 zV49R-#}dF0dii)IA#^yrH(&zel~q10V(-F3{=XGSRuv?j)N<# z9ptE&AJD5(ifT`zNla*yH05}p*0SPlukhwiIT9c+y=#(tj8tv#HF0|Jk88($ILl_D zEw049WZPa9<%-h!;SKv{q$Oe{t!9PmT#Ivm@!ZCSJzB_4l-lgQAUnE|q%qO<_Vx}s z!dQ%*d!KqU#x`4x*(TS>N!9;i0^WvzN68xxace=f>^7mfqRYUIx*dSnyUst^e)Zsc zUG9HDxMwKs$K>pQ>$Vo0tGr20+#C^Fif8`72*~f_Pa-z%UwV0XeBDlNLl;h(W-bOR!13KceE!sd~ktGKe-%8XufwMFAq~fJwZV$U1nD~-OXsVRucr zUWX{S`I?bpboUuLTay+_WAX(2UTb5454bREeZAe(!w=D)-{Jq z$`{#Ntv1z5PmYVTy zGf5hpsu0e|fm1lU-K4?oHrVcB|BWu5te$*e0kMGQLP9QZbVF0pe}POUJy|c2+4gJ) zejB?K9~F%k&c?*w`grpcKC5!n&@E(Nty%e7SN7?g^AcUIY)$ZbZB~e8X*Qj&aFRcx ztlOlBTE9v?g&D6}+ScBvi2>T4UpsT{IHGaJfs=qKO@|(0OFKbdqZ#0 za8+{J;eE;K4bI&9p``vN(loi)R9HQB(ISD~p;{vPp}M+=X!Ni~uJXs>G>81h&D?NO zK-oO!#r4mBhZFD4CuZB`xq2kHsl2>yi0bx%s+f4)ztrxLYoO$GJRO3#btbNFds+NzWxGVDu;wbJAdd{-mQc)I$Aje8$HQrTsk0~ zVBWrv&AChE`bN2W7!t5#yi?ZmoNq8x4ElFhD{nis{VVZ61=SyCXx-k8ouumTgOD}B zrS<(MF5Diw)|UK)1Kf2DZJ#9ZE|R-Y{M&pN@Ke{z?@oqfAHHCkE+4wai>}eB4K3?4 zRe}79*U6`s*_9on{1#Q8+x%}!PZQq-sdTtygGI0AILW+=3t1eDPZ8t_A)j;#R=SPA>-z(vM!OA?CSDxHM4>J)dVw@+u>%)bodF2-m z{^)du_mc8Aogfv2>p{YtGUpmf~gh2v$C!_EtU6{|glq zp{(Q@T=C&$N`wjAH;3GjPf~&$`K()PiuYqfp>HRb{l*-kn&p*pf6o9flPoNj5AgJ)-}WXm&ypm? zXzZTjFXZ$Fxai%xgFA+Rdl%@`W0(I%se&hIyG%%$Yfs&a-xnRK#%2u?C!30)$K*7* zK5bF`+0#$IhG4yn=((R=moVKw&oGE%iTGx-mFf<`Qdr?$$44WZVN!ui2O1s$QKR(R zoBun;X6_~BEU#xCNX?eSmE6HxkwYVeAa;`ds^O?+@JMuU{e=NQ+hE0;k%p`N`M*x< zYI5Ch@vskm2%szAlidXc`$|(kqsxK7ir?$y6Xd_8xZuRQC#uXvDR?ks|M5l975}&4 zCmwjlNke_sOEWD6+rMjVX&UN&JazphNY!v^eWbGZ=rcGIRDS6@K!^!j}a za8g=3P1{GJDR{W=PC41*x3tZKQ@v`i?-BNjT8k6WR$3|A|LXodweg&|$((eQsET<1 zwur|`B2t}rtmtU#iAYy}Aggn6>O{x`gj&okM+*Ud>NnRLe0UjrNPk@gK|Qb%tX(>h zKFY|k%iy9Tw#JPQz2*b#9Xn~>O|88^andaDxxL^kv}hAPLmQ9Ga|%E~5@A$xN^5^Q-8eIQpCu^~ZFI3+WaU#G zhVHR%EoX)*-UH2%!LI&^_*&Kh1WEAc6p5a40&J4xQo%~pmkSG9YHd!s1%+DA_ub&= z{r_gK8Yc+GCkeDhI{@499w~9-*Y#Qp^mM!E7hGsB5pIFK{U7%&^-WU7REOS?Jy&8=W1dAb=y$_Ik$bv zY7d8t2eJvOZ5}V@h+!IVwJUX}sQ-SkUGh+tctDPAMI>v=jrw;^s>e6_mdo{v!h1l8 zA1V;#fxEA87q*{tif5jf?`Srfwj%E3C;rMCQ-X!`HG;~hlBo0zclZ;%zGJ2;vfweh zm1SDmX$5#MG~urHO=VYcnbt04s+sDOHMMV$e!_MUF-6bU&}VK)S#KU3U-A7H--x=c zM%__;|22obVVy!U;mvM5GNLUQd-OO=My5DRc#dRoA#7F7I^tW-YwinPj_5%y@N!}( zMo?JthrS~@?kzwO_3I}DHs6foO z;L0w@wt{6XjjTlZyUreBqndkVZLG*9VY~96PpWF*=hOOJ~O-MT9TErEL>Pk23^DY}X{Ga+1_etIp}y@wP%?_x<(=bG>@0 zfNZ}X-Iz>@LHt`0_Nr5?PaMAA5T(lnlWqQZ{iY{`8ShGiCYN9ou-v>o&D!$b%F zmUl@Pl(8=xjb^;%91!|BUYZeVvQ$N*H#H$^M`HK-pg7pFBgtrRxQjzx@L-lbD)IK* zM9sr#8f8X#$yE^@USXp*BYd=Uv<(w{1iU3?-}|D?vE;q_mhc~dojyVWpcuaZEGIa^ zr$Xx0a9q~f@goR4HXa zPmz^@&umM@axQ!`L=Bx+5%dRc z&#J3Cicg7vQqVap;t;0I1&bN%^Vd-1E9B$(H;kKlb2ba;^v~kG9#-gMi$7nvib;Jz z=k6}4r>Et-M4@ACIbQ~X&$hl(r8em0Wi_~0xle(S=3)JA2?)+kAzFRIyz) z9Ti2>F4M8W#+5kwEXLPOHB)=-yTao56pfaUw%gD=K+%%ZZ^Nu<_>uO`c+0oQnxX5< zpI+-a_0=XESVa0k-8@Zh1iqJNvUP02C5B^i8r1={_egTC&bjx!iW?L|{G{Z#3faor zf%}~J{=LrWJHZJz;@o$bk|^{6_zVrU0EP0to;lerNaQl8vK zmuQV5g$w(06I2lZt6@bt-h#uU^@~XvM0X`(_%(!eZsGZ0UA3|bBvr6ZF?v<`Vs?zR zgP=hqEJ#mt8vg0o5N&B}E`G4_dZ761mqrmfoDKGeXZRDDWKyu#&WkOT(+69jB-3hh z6jkyK^i(5vwQLJ$-({4AOiKd@f5Yp%`7#&5_O*vkpK>ayt!SuU9Bnhx%qC{-@#w9h>3>>^_fK=Z1y|!h&DAv((+YN z=swjJ59ty3y5K*_jL#D9QjZ>fTxK-D<6FSJKKN3PxWN7;htbrY==$%2eSC`i57nl; zJ6y7*F5~t_j2FHv$o2=9falnN`nm4$ADl<8KUHd6EIV`)TOQ>avDH&EBxho&EU$Z_ zw>PU|b$y?1AgFQ%@5I6~$m^#$pXGfUPzQrXe)?wls}&*ua?eI~|f zT4is6a^3O*$;ca76iJX7ojn%`4rz7{o3r9LXq9Y{ndh7iWQqdMtb4+2<&~_c#gpM& zQp@OV=?6Cp736jI-I%j>?M3ZG=c&eVDM6)>5P10c3pfX9_&3zOFp-DHg@6ozV;`F5VdcH-@kp_=I^+BPC7ZwwL-ES`XAaSTDXLNi0#ptz^TpYhlgg> zi%Fc1K3yE49suaog8gd09LAGgXOPJj7#eG13q3R6-qLQn(HshTQ|>e|?@K91*1_p^ z7I=dToKvJTbe*O$6(r5*Dr{OhA%8&jH2Jx%CL*zcnv!fb6aq3{HaDkIrvXg4?I zfn!@M<&es@Xq7gtwYama!q+SfE~nlcMZlI|mpn#(p!n#IbT0dY8m_F{qqxmu zZ$B!w&;ew1;9PUpiMX5769?Yh=jx=P<)JPt5p}S8UL^!CZuQxRyS8(%8l}0c3cd${ zji-@LUHxmW^6gI+)tX>F%$;#4sd6d>EU^BRD)*+DQZtuJH-r+t{D4`|n##8AJ8kf( z*XN_wg1{-HrRFZB8t23c9WVWFkP9lbmg)Y^NolM zQGDtJ>dj%XRx>Q^>K`(`0vy-8THY<*S^wQ@=Vu)4qCDWkUoo+Dxjt0lF`xv(yW{cD z0+7GzSsrx|^%_pl`KQ3iCTkuud#NS!+_s9_CidV|>sMlMhjk5&*#(dbUL}jUjrRUYmq=x$w4t_EE6pu7j`ocYQo}YO~MP|g-%=&^Er`yoz9ALVdb>>Yx9joQ)rw^Z z`6Ff@VB_Ak{-|;u(=Cw@cdO@L4F|Saa z!MW9JhJ6(sfGUK3e5qROKe$pGEua8ln=YN9i6Wp@hOJlxuUpXTsA%l5lDWXacU7@E z7~RXOZ-;t&>l6rH&$xcuDWu^ZYN`Q8m=I*6iBcl~9?_yPf~7gYVvg+6^J`IdZeLqWJcbT!2YL)ncS$Z? z-n+@u-O{KVi|})OT&zXZrS*Y$)kmjdO{wZKN!%uGbo1q&WqP9FRkcyLeT70s!AMk%Ai^`)pHXs8&r`*dv7nvm6r^6ftee+dZQM6-mP zrIDmBvu*m>5rDW=4Lc13;gj~V~i}ceO9E4^5eULKGpxV4KiqhZ%h9htR z;8$IN)Q2&=d7+_5lW)JK)P6|2|CuLo%&*LGVpRKlWJ1(FOETqFE&{#(If<4&7$ku{ z&avB9x#*@d&h*6`_Z_Z$X$g#{`LSlUvzzWyI4j`gnAPDi&==c!<|Ii6cn!S@$T*CT zA+h7L3B!ER$>ZX}6*QJRdQqU~c|pdHWKJRVnbx6S7agFrOY<)Po`&e7Q3z9rS^YB#av& zI6mzRPGAt25~_p!S<3RjuVLVhQN+rHG9nSUNNI}W;{?TJ{yWQ)|ITt9B~NK<1~!Z(#h1hkBRLpQKaOwP z4RXluP3g|3xvnRu=7D{Vak(CaR<&mf9nA8qww<&Pvt#ef-QKxT>a)QeO75*{w*}YZ z%)9Q00Qd7L0zBR`8bqYuv;^9qYeyybj6Lu=mQB9h-52J$c9P zn{zmYRHLPbFwg>O5*7$Q_(3-41J+CQxIc2Ic;)gckITxP1!edu@Qa&fJ%VW2)2@&? zS}EYHN|9HNTVJxNx|jty+oWjUS#MExZQa;TwUEbQv#Y7|*YpW)RY`2MQPksUDHrD4 zZ(r=hm00wV!_z}>T;ygIMAIzdVVGn-dK-{=27%+kiBaeouf1m0;p&qi)(a-gy<+n7 zSMo8GQQjZXZ?x=v*A}HL)F4!xPf1S6^-Y<<>Fllwb{vsop_fMsp{>!`bxBF}{!!Ia z^L@tYd_-v~D>iSiL@vj+;bUw(qwVpCMcaoF_&glEYqr&rx^wwJRfvS23Z{@~_ZRhYJ6Mdf{6vY@Pg)W?axL``A+j_85@?#7>(r5Lt7&e&0 zyWwY`4r7NaAJzmo>$eTr!qulZqZbr~#<-W9)th=(FWW{qD-fBgDDf956F=FLA>^v- ztS`1gf4h4J)@&859=4XAGHb8W9VMk)eM|3sSCsH)J~SC`LazU1Qyj{8O10E~;}u#) z(DHpHwx5WQ?Ulxz%=gd8HWdnEI-l51nlk`G(N@xUdyrvrg#@RE{BM*^NM@-q+q zo=i{gO0f~K(B&vf@#DiGRlVe*su{Ijn$!`&Z?5G?hQkc5&?$><$**Y>hm05s`UHEL z);{^UONr`8kMgv;CDbLVw}CF0g_e{rj-owbGNP(jlxy7<%=SABKm~|iN5@!$5IGuiFUDf`7;ut1b2+WpM|DSO{F3kSsTp)0iK9}?-KD*14N5?p>GLxsHjI`M#AzNlx>~EH46D#bg&o8m!i+U z$TRJ8mTz5C$0tNvj#`m)dB#0Goa!2M0&A)DzvtQxEwdoFd@`MQyr43y0SV^#YfByd z=jhwqRJ-w78{>*kFH=6;8nbd;w3@34tZk zorJc?#vAZIH~8qGXh#%bv;0^6gED{mN>JeBcFJbwby*Fpv`JF=dOXP9^^NKt7bjU? zA`infSDDD{JIE`J;jfVU2TA1sG}(B9NOxqp**{?2qQ;hy3WLq$byvl2pP%>CF7ecp ziy)@)AP0srP>tCa+g6okC zCT8Rg3~zj8Qj2PT@jUAZfg9Y=^9p6tJBCpDM3w$daBJKr(2vimd+Csnu$|5mtS~b5 zL22()Ph_b-!QPm1{p^pz2Z(;Sn8&Ty5f9vJWcBH%U2WYOtS5?$f$;d6Z=nmo(t*@U1@ zgY0t*9rMa?WGGr90%_@f6#len6VUG*vE7UA^-^iQG{>;4^4<}1eASSeq%798ZPdQq zIaB|tPkpxizCn!r_e0T2n;SWg+aaX08L(nuphTWSGN@do+*8*6>Te_r{j;RA<4X~Y zd}SZp<&vL{(X>X6I>8 zi58Ln_u%-Pedj%?S&J?G-{wXijDDny&5V2#x_z+xZdx_U_K8AtA!hz><< zj@m9|3Q*8fuLQxklxS&z)su!cc{Z1h!#cs>Ssh_QFj$A6;|6d@r2SaSi`o{x5;Hpg zd$RrXt)K=)dn5gnc<@_-M3txT2IP{h$No)2dAi2i!;RRNNqG|H zJIonBRKAtg)LY&*Z$?h;%3`@jGNa3N@cukI8u+xEHY@WfdkBw_jDAa}G7nCHkBVIW zqGO;<2JsmOIGjif&ry{hRYlm>U+Rb+em9E$jx80H&G{1fGJxotx5Dx(^K*98QsBcC z%!t!dRQBk%>S80qU~M!5Nr>Xd&q#xAbm^lvo&Lleiae*58{d}uc@q3#)1D;A{1Cam z6OfPGVc8VZ@gRPVw(Wx)d-IG1psKr!OY3|=DH@`B|F->C&f%I*YbQ6W1&n zC+7bo+}BftR+QdXY9mycUPLMX!&bN(3N#B#-3L5@06%<@su^RtVb+`QeV*AfWQ~MpK+=PABIRtZo1LqxfFbWH+bKX z4^r>OmX3?ZhIVC=r}q*4ZTKG3voppc&jroQ;wpFn@4$$ezX8}nNIvvz8~zF_g+K}h zg0H4fadOGnzU>>?ajy`yC*V^mbhmzMKa=sJcsfhIV!3vlUmCsiz=w9jX60OxBq*Z zx*MYNXX?trpbbysZA|CW5u37D zy+fny0;)cF*iGwZHu){IQ|V~vQfu|;!K%h#D$&K5CxwriNR$?NL!<-wW!JW$qiNz3 z+s9STs8Z=1_BQvQ8r=$`RX$V`Z3d6UH*fkhPZ?af=MxLpnVmrFeWFk$u02H_%mwe0 zk)@a;7|R_kG07+U_5V8VGb7vNC>Fo%6w+WQKZ>qQ2P^kUh0y#<6JnH}J__qt8Vqt(KVT&XzPCb6T-+lLB| z0e^nl;*m41ZB4h7RH6NOy`gG{^`c`2l`~ASMw$28P(Z!fyvxxHk#XNigT(?GQ}mr()ufdhTBWcy|vNaiYh9x zXhpnqmU+Q^I)Rzr2SNb+4dBudYc15FUj37xscA<=ps2$4!=>|WU>%)t)Z)x_wc9(s z`Md67?7eb*S?$;Llj_XQ9mft0p3HUkJ2rV=0xx*ks4=OWPKBya)adJjHF4nbaE+<>9i2S9qvi}iPyme$h zxihzTGueP_U)H#M#NTPGRw&0j_d=w7NRZ}jO4!upgK1Ghbw8mDNj3B)+?*OW` zMRx0Ew4=lCYmQOyIKrkmEpR<5I%HL^CKyxm?AyG|I%v!Lk=SohSiV@G zq~sz5f8W9^dBN$F{Yg65ABpSc)(Z`iB?neHz*7X;$=HD=;WO^&P7SPOl@sIqAgW&> z_Dh45p!Z&btC~_UnG?lhh)ds3BAAz@=?lRyrxBg>xhDx+zjcY`Lb6{k4R$Eq?MAEY zWgIp?Ej1_ZWy|AoQt9$+T|T(BnLoXV>Kd9VXul>|`<%qNacIJ}AwlNid6NN7panEw zhfmNCmqE@{Y$1&KHzNJNKr0q)Tr(L)(03cAn6qO!N9L_}O$sDkU4G=`ne_6LnG~BF z_+e$pEy+$IBcVE1c|k|0jWU>L#%^fKNb}@X0e894a-~S-`qBZQwFE!m{#`S27hzJO zz31+wJbP_{#H>rUv2FuCN%5qbgK||&csnKEi6_CYBOkST2^(K*Py~bmgm8`c6$ZMb zfd4GmnIbz$&s`-IG;T~+24m79I=?aBk$VCEfMs+tlGSITdG_I_jl((K9mFi6cK(rb zQld6p_~tC<4TXC}l|CG*EE9AmUUv{LgGx}gMqdQ3zX}VPZzT>aj-7JPFUWhwuzQmI zb2OS${x(Ry*6&}>bNNOSQr{n(a&>oq7KocJPsyz0x1L1m1(bLZE2y-g!xgNGc|J`eT6H zfghMB6P(|N)NDw+VujM{!^p|I6s1HOaYZn)(}$}>B-Jp$G0r~NmR;0bS;rl$N#A^` zv}2KnL;7#6w?r~385jX_{;=>F=?mx~ZK=TlrlIi^(ddI;clX#>MA(V#ZA~~;E&MrR zSo>ZQMZI|)OpyAms%R(kRvvHGrwx%v+Z-viyx1<>Sc7Y~l2ADTwEE&ff1v>m}F^$u|Or72sNGd3%L8+5ls9&>hVL4I1> zm!A+oWV%Rf`IFwqX_i$cMT=Y=j_JCE_hOij@1*SPl7kJ=yvSHSBrU zp|>i>S#{88;Q86lyv-R@-?XbTd;9Al(LSo^Rr2ssbBt;h!Ro9h=p;W@sk(!4Lp<2F|xK2G|5k^jN8p{>GsbPGy0 z&)Zk#3J&gB_s;B4HR6q-p@NZw{M#X-m@WtLJhm?h>ybe$?V$U@!B!#gg}a?sgQO!sEY^Gkwl=BB&Ovd22EbY)NoHrXWE9+ z2+|nzZ$Xy51Qd0B5$-0WZ0`fed;@HF!D>qpkKy8gSV-t{|A^r zXTP2Ep7(vvyXH!W{YMeij-t2KR*;$HA}yj=HYcip4U|a4d;`j-UF~b!*Qds@$mY30 zl2omXQm4`JpCN+anPw5uJ}X^Da#W+1%VOqYl8^po=P{P2W{uRP*#_xm^q!HS!r$O4tR! zkdBvuk3p|Q!hMK03v0}kOdWuvm2uJ(MO8qYGd5&r`8{y>dE5f;QxRj)L0J`jrs`}< z#DDk+gGrfv9@jjRaWmafku2Ir>X*FOA=-DkY3iHP4-zX^Rz<@>*Hz8J0jw;=p70cQ5IB&;Oj> z9?)`L@wvoCLaG(L1PJkd44I4Qe__2EKD4+NX17{l0=3Y`nrB$i7sCv(;m_3md<@=W z`qzuByd*@f^0RnxnQ&jxzk7SZV_G$?qWM?+|Mo;R{6DXp3)jY{Lha&^}r8eikb0P#_*b zt_88YgZ%<3jQE){Jp?@}U=Voz+S_67kG~maH@3o$)?W-iUH_qQj+hDd^9+AwtR(n) z@he|R|At=mzU`{_$Lu&%(D~mkuZFLk`Lpn?i5nq*5jW5?*oSEO52oLC>w8iyq3<$m zME@b-8GjYs{0lOy{qSek-yzZ=`3#I#@{LV`8Q}pjH5ESjv6sV@OR!C(5+1=mATtt7 zPkD61qOBF*DId_N+{BI5d;u6#PF;#Q19EUVyAlV9yMGH@{?}mu+<&eL*ww|)G6Rr4 zRp?4JVL`Xn;Z?t)e{1P){jI$?K$D!-D9WxILc2U{*e(-jE??UM!*!X_ite2 zN2I)!YM8se8qRLDvEH8uAHkx00)xIeEcq{X5w8Na68#CR%#&5QfStfzK!1R$1irMvAxIk?FmwF4~JaU#y zudhzu&wL>2f0`dHPCy9>Y3xM9zk6ewVR2#=F?l|mFP9#uUNS&>6$+knOOsZejWFk|V2S6;dhI!IZxBRCB4$v{Y~3d_nEiF3^wSRe$kc2`k) z_7Hr=PyK7)@_(|mwe{_P_z(Z#M>)d)M@fL)He9{fV|z*IKq{VlX3Js5;52o@Fv`j1 zW;P?;cYxDYJejJ*zf6|D`@i;Uzb24;iMmGt01@$L)gToltpGv9fE5Gs?5b+G0ed`T z$EgTm5O-tzH}Tb8HJcxzf45u2^;h(-yWcQW?s&lSgOlF_kZi$R^BWvqxNb)bMr0&CsM7Nc;j-@&3#}*jwzL4!1^&%vmbfn$3ObU^ju%zKK+=Zuey2%03U`V-ZHTe ztMd}+$=9ltu)1D}se~8u7?zeWiHrka6Vt;U^-8beIvHlhP2#T#)*6>bG(t(huJR>t z`k6oc!#})F*1!dROR4}b6s=lC!$Pb3!wvDg#dB#to_H4iJgW>q8k^yPbU#%GI!$@| zAc_9FU--foZgc!wRQTE51w9vl*1^q5!mm|ohaeSw#Qz$pM1;8emd6|mQM&pyA^3#s zKN{MH;ubB^FKAza2lZ3^&pjej1}p9PPR5x^pvei-L@mLnai!^qsb!S}%cXt;3hg%}Rt0@3b1 z(!WFq&{nvJm4!@KW=|nXIldwTr{UiUj(@B9O4!6GqmAP3Hs5`ek?4^PeoTjlL!^42Wg_} zS91pFBG||2v2CluNKac^Znz^SHmR9p3b0Oz6|kql{txM-!!nvs4R*3)iq1>1?&vG z4-X;UVbGr?*8lJF_a1uw*35k9&!5BX4<{|%GE3NLzS$O zgkrQu%=Rd+0?lnpRMA}xTLYhEsr4ydFr1L&C?Z+QZ`=4ix0T>>3 z_fvJ8(!K+0_1moy|MC~U@P%angtb=qGIdvB%t7LjN^@;#jSWkOp>igHX7H zjLoChA6dn!oQQez8?A62QUBCd4|lzOIFFcll5t-EGz}o5^}eKknmrB79$gLte~SJM z`%4fPV!E#r^k*6I@j8pA&KRcquKZ2?8_oB3y;X)r20#e_^C1V}$zlDU=NWly2)rc{ z|ARMY*9)HVp^S>-ML-~QF3fXOGT7ntiRKwo7&9+NF%X=Fuo$~vJO9LXJ>{0}`8riN z+HX{00vg0I=#QaV!YI$!|Hm>8jC%|^WNYOUQArpTu!+uoEAL{7gk?wvR#69xZW5Nd z(}k%run$CB%8e*y4+6gZ?Fp=MF`hFo!1k&yJ_f}{oGe^|;bo6^J?Jao_;W}BmcR0q zuNc{tn`2E(fOJ7f@D*vx?)LHSeUDFddDa+!G#C!xHk`2Uz^3YSA13~a|HCi*!Y|xn z^Y^F%#*U)CzXzgo+hN7iCE8UFfXh<+%19o*=<1ib`xU|ltGjP)ohQ9-DZD|<@Y|>Z zR#^Fib6```XB_?=&+mB3J&;!VbqI$#{-v8)%3W4K^ObgZWu+0uiJuNW3>P>0i1z`u zjWfjL{}h(|y)cDg--qxkSIj>F!8iB24rQ4)xnTR`ik9Pqt_pSB##Ts#^Y(lxe0zK{ z)Gkbg#>_1K<18Z;r5gEfcTwGCU?QWk^>F!{rd}Y?4>9LcVwp!F@ZFC)?qdzoBB2B; z6v`C>12J~k0Q6d9*jzlz$`T^Q>U9C{oHL*i!~5*zPI(;PA(g5_{O=IA;eKvCER7I^ zY`Pmt^N_#M6Cj15PYoSxL_!SqNikgw?Qv`s2vz*88`r|^+bdyVdOE!N%B67mB5W^e zfFcHk5$hcQh_Vwjs$0Eqi#0ulpY zcc#kjwqzh7VSjt33d8fvlr%_wko&vqehfgFSpU}u8gYetzUa+63tBc-bv+ET)cYIX zzf~jPkKulW6<2&mC~~VE#rwE*t)cJ#X7v*O{^f9s+5X4N`1J9)FJYH#Y~9%6){Eer>h_yDHII9@ZkqM ze8zh^5O_2EncTgh_loyF z{EESxVA&PtMlO#57UJ`K6rm3;JnW>G9HclkEbX^ONB~qM`=}B3#Ox;lyW6J;7R0=|?U9@%zXj)if@8!5@ZlK)Aj#K4~u=!ak{ z?dforXn%K*0^CswzzPFfnJANb+;g7)egb>I!Bh0Vx)=&u)o^KbGW_7?bhto>-Z@gh zUP6SNdF*SRl&vC#p9kXP!$Q;1`#|GAGsdmuYGnNz51mOY{%47nIx$0o)SEu$*{rTi zi;!AmU;tOd;(s(9$^MKTGCwd|#R2 z5HtUE;_Bbfzqbkeb7OKjj6huH#$YN*)Dy?>apU+jKLgm%E`do9=*m!=BUCXVguB&l zxOHbKG}g#oIXM+R^QjNV}IPFE%8r1>DKelL^;jVH4VV{<}Z@(?5Eb^Z#VA`fN4;06+jqL_t*WJDZ^bz-ahqyy+eyrRcwHnoz|{ia-xp zyrYMBU!A{V{|a>poxgRhGs1bY|8bE}_`IC59uOX4j`%jge41f=YYU^X3WTE@7D&H) z1}V>M&x~;8sP|9N;w2>6N>VUQp!;;bT^j%yfDP=&D_D-V3CkKS|4UFn+_E0s9==y8 zfNC(e`fsJ#^>mv5zP&|eMhkXr$3{7r!yadrIXaFffN~m{wFj)*`__!dJ{atT@}`3d zryW{FR5|19O>#y9MpZEh>pk{KPw@gkJV_;#2J{IQ)SKvrHf^pJ$Y0Q_5dD-`24q~U zY}LXRu`$|h#rRnp2b+Bx>pD=F+D;X?^1pF0O`8b4i2ZH>80X-ljoxQ2kb`gFNz6KlM{@;S%yu_7(r{ zC=z(n`*tz()7rn&+$3Ck6?_Lr8Q1SSEgZss?`J-h(6NYWB!kN_C=SF!1%N)%H;Xh5ze&B=pV&Gct>xJY=0XXT@wbJBjJ z-P%1C_?A+6B%B$U3a{s0z(q~bziECl?|+fXaTc}zGH|P~aAt3;juB7d60!IfU?>%^kOAhnJy!}ssJOSHhPFf%a`UM6(#+{|QD2Rx44 z+AjuVi;@6YqsBV?DbFvWWFxh84wb-=1i&HuS!lrD`~Bbl{TpBU(w9EWv9!T8nA0Rx z`3`HME9}OS_z};i{lQPCXY-hueri5s7|hc^IZxeB9GzQHl(q6Zzws`% zaE?Uz)77urBJ!WB{}}7vu@*LlU%AI4cAe7dzeRe`rPgeyApXDJoDSb@OdVw!1>h0EY3K*=#2P&SI2Xm9BGBPi@49{0p@iQAKU)1avGg~i-!crqI>CO- z@K=NIYxL(+pO;hG1M0)u1o%PxUuw0(G{JnPvGyOwsI$ZvXJX?7lE?Rr!k97u6UVf% z+^;bkDj4w9A$A=J{|J=N)&C=qY}R_`h;^U>!20?SQ{wnK-~ey-li=IXB_jo3{HD?R zTeILlCxiIQ#AU&MS}_1n3w?KvRkVqCl*B|kjD!gf@Xg0^3GIvO7I{rl7War4*c~&E zK|5413S4WV4#20sig!SRIn^K|qe+A!+&!kj8FmIf#o^j)#mb;YuK=a}&V=pqGJAh{ zKohoU1n1nB>#+LBG=beumEBl8K9$9fJnbcQej1dtb->a9x^?AmHR7KT@Gq!Cg=qzV z=tknU#p=IZyC41iyBL!wT1qb(y6KU-iv8QH`fH^4twHc_Bl7>Z)pIZaqcP6Eu7A(V zDenOZVGZBomD{1Pxe;bJ>){jKEBN=f!zG0OTKOLqZr-mRk!a}q@9J@RtPtM4a3S2p z=&yR=Qm9W8|7wJlmc&2W06d}<&K^A;thk_wP`xb@o=4nvqJQF>B>v51`sf;-4J(lR zrP1(0&zyggNCEWU5TzV{$vgmB;T^*NC7`PTj zkjSYHc);lX3uwYLOu#bzh8QfW0pt`!&~P2G3iWnu>fChf_SBZs$^fK6u;bI9q^+|w zRR=I}brS#F@BZ%Z-e&vXP(9vRSmE~(YsRR51Ul(N%YTDRV7Kq;{{g`4yl0QTv*({!4FG~91>9n1gCFkUBF3^C&uAd2daHS~Lc zGmiJWTsby08Uw#oSoN>Y&W7cg@z9)`Cx8krfM$-1Wq5k+)n?{`F#xQr{-gZrakuRC zn3HlYp>VeCE&2#1V048Qbp<B6L5 z09_dI91FSvHeBX#$zyySg9Pd6vQ5h)E%+j|;qU*%Py7Uau<>}<79fcY?D_;P3F3#3 z)Be8gI%z+g43_rjy^;oDcA4wMFd`ysz9ZIDKACejPGiGH}1rU=~$!gp`^>GYM;C;>&)u!zEMz zM)X%~Y}B}uQZf|)1Oqidm08i9I}`d?jz|Chy|Vu8*YNo5AXb^=9DNX_V_ZBuGxxjq zq@8CNdxZSeWjt5Qhf9kKVe}d?|5sCp! z@K(56S`XcG5XPBy%)%Juosz3lS_~aL_HqFRj8N$HPWaaCYvJ1B{cv_{28N&=W~N}R zaao-h!z7bvfd`QWMB-1_>URAeYAPaelqWF^ge2hdk=?&NM}G?%@mIe3)vunT`=l94 z0VD$Us4Suv4x{b_@t(7Ioc801lm2J>%TIbk_h?`0e79D=B~=H^n#BJj4D2oRJTG(Z zXQ)GEFrFZ_Nca)^cbjYAc7jxh;Ezz${p<7JX7#^8l)rZxv*C@}e7Mn^!Qig|MDcrU z@(~{X{FW2a1Hg@hPa;?$cKrS8A$RW@5#(0FJg$EW1G1sl_(>^AcZ|bTXlQt4y5C83 z{|5ir7XKfxwSIeK1Wpycd-&sMeh+QHCs1I0S*Rx(H_76L5)>By4IMoO{4+13!=ixV!CWU z=Vzo5(hB-7NdcrGiJm0-;x^G8c26%d_v21e8HVgM0K2zoko>kZh)w)F$uL3G;GZHYfEX(EFzp<`@ae^U*~ii`TK#v)*FaE2ayO8ara48@rYS5q#u!6o zIO6}~FG>K6;OO{i`Cp%aksBrc1O}abGB?J=Kc^LSq-jF?S)_w{StNlsn24cb0Xy=1#mU!g-Qa3fj_<2W>`E<`|-p{{&U(GfYg_%(}xGb!LbSzepg}uO26_e zzw#!>pQip0b-P5LQGp>w`(s+gFp{kN_4!A%tF9=$X#1we>`2@z82PQ@PfGb~v|6u)} z$4%+nRySO(jEA$8Zuk%?ACvedz40-$Zr@j`J2rJ}mN&i(0|5LP_@{JO27p=NDpMGa zaLT?go$9_VIC($Bp{(>m^FHhm+v)0Lc(F(3KTQA5pv2Mf?<5q-oU4DW{?~I`B>t&| z@_EGN6EK@+uu%}((bU-5lhNcOcUxp+fTcX3S-zk|0~UWCD|K>_9ym9m0aKD-{72T~3KnP|MH`?AaC1?n$WztNu_SnMtD_u55I}52O3Puu%-J;59yprLjR{ z#0f_Lq4%lZG6TS^82*<4GWp490N5WTc)ZDfA_Y0%tK+O=iYYaSk^@d8lz6~LoRrJd z@^#i=jBdb~SMuTP`b>De^Fp|QHy8>4RuQ6-lTnQNXY{|7{6^RqtA_GRxiB#e1EBk# zqW_c8%=gv`J|el38rPuw67GQpID$F5b89*L(c5_v2En9VIY+(#a%q|@2xj!r>m}h+ zalhuTF2Ydpvhd667N~rONP*ig&07Djp&1{B0YE7fZ2Rz9 zgbfUfHqk3?5gex7*@Wvv_e9MH>w3ud(HnCd+GHXodlgU#XaQ%c9(>pbwM6$a`oO-x zqCV!GH^B~pcH*krmAB&eV=clCcz`zLuuLv>`oxMKf$)!nQ4Bwm#rR?1=V^S7t4RMT zN>&}vk5VXbno_7k6}~LZym;Re{!-yTPAIkvb#%r79OCqJ=&kQ%jtoDaVazunqF6z?~2TcVwKidQ%mD32FGkpPdP2i%+$g5>~Nit4j^E_+%YoZs5ar_j6?MBr zHxLHA2S({24r*=P1E1F*&=BDx82-8HZ-e-^F#c+E^Wob|-SE3`tM|xnz16(QbH5fQ z3Avgh+EwWSn2gxzoeKA?qK|4KitSz|00~ln5e%}Xh(l4rCp&Q=BI#$nB!aF^op}18 zIUx8|%r-Xe(--u?*cAN(Hc(_ejk;t8L*2Agc$)nq#7X>XFm89=L~mRTa~sw0N@qS? z;U~q$CnaFa?rxFzt3QqjWJuuCw=eboSL&qd>7d1aS8e5ekV@gdk9sQ&<3S&@?{(nh zZiD#=ujhKJ*96IHrSEGEbz5e|%S^X!V}pGk_V5o8-@~AjG>(;JA)LK79VWgtN&beh z@bc=VaH(}Bj^jzN{7^70!To3ocVs0fYjj(u_2cIkq0_b2p|Ev|qw=jVjEyN!k zKvfaRGA7 zfxK$jto$n$k5`ZcY;g#%Z>s@-$Y)0iaEMu-^~y2-O;Em@@H_H}_$LNngvd^BasKmE z4LV|RBE=G)1m~y<0MUP+KoLDd{=#Lamt+?{{;vq7i{V$jJ4P()d|2G7hwm=c!d(Kx zVQAE{|5x{UwCg9k*g)xy?+`J!h#4sPP7YG=G z>lnP}3>E+xp0BT6qrSE#GnluE|7T_?3A0@Y3I>3g-T$!x*^aOBi<_+cmth0$=hnkop%QW=(kT-BC$5m~hm+CN9qoQk z2ZEVtjrp)H__9XQqei)k0VJxB#%5R})wW)!qhqBQEa+hGQtevRu`9tdK?8_OjLW#s*CLqb79Ga|=EFTB^ZcjyF_MZ4M4A!Zmhqn^{ z!~i5Fz`?5E(g79O74ny%kqeBjArPDx@W-VF#6Pb7#Xb=j9^Wr%v}GCE1oqkL5a@?M zA{7k%D(L#Rs%xQKBs1LDCTji7=%!OduN6RKy|Es^EdxTz$^wi+XPGvEK*=57uR`n; zfvaEDKr13=?u#5Q+X1j{w{u5(?V3Ru+D)gP%66Cv4DUNX;_+ac_Kl<$Me0n-`f|wO zh8Y9vwC*wGs7%T}qFJ0P=sQ5xzS;5Ir}9<2gm#07O#Pcj{9mkALKy~Nv^h!ep9x4m zB4p}G5*zQ;Gcp2v#Q?4b)8|mIGJwGWTx$3lC8?st!jsj@U<6pA;RMYwaZy~f9`ySUJ3hyGz2B6+i)r605devN z0d4xh903~@k{}UkeU=yqssUu!lt!gn_G)_kRs0`;U=Z~ce9{A!{g*M9+fOh=@Ff@k z6UQm;0`Wv9KsqC|51=W&a=5jgw|Fk?#}g;*&uL%)QlF(!NgeH0?BzBQezy|;5yUrd zv;92vJaxNBD^2yQyI=GNHO(($DF8`SeAr=%cc}N@>=cM$JqGb-(Ymq}y7&GR1F_{$ zoWCE+SDImD67ZyDg&Ba1mt+W&dy#f`u@UHPevMVh1V)G#LTBY&h#e|{GUC}eny;&t zdRh&(;>wF*i>o%yiG*Fn+49H;aO_9K5ApY1Un4kr?)?DE^e*-I5@>7Gv$@YX_4g8b zt5Ob+-7ejT1V2YU@M8X5EPGj5_Zw_CLVgB=9Y`ywcDS5x6XVGM97h?nJC9AmIC1~y zZr=*yWdA$AekIJK0+^+pij7aI1i&uKh(CX~lcT3WJ4A;HXTqb*7^*Ka0>eAYR6E}B zC5L!ec4=me2U<2L50Us9i}Rs{Pd*XuL%%SMn;WY={NFo`?}P%OVhf|4P{vohbb)zA zQ?}vx0H33}qO*=Z{RWH#!lpADGvT8IZ<=Aqta-2!p&w?UG06hN29`4f)d9`C)1a}%ApwP;N+bhf9gMK(WH5(?z zOJRYmfdv*warJ)SzCaq#Cggj4ojxQ$P)Ri-xb{Jjc6=UM^6&q_Klle9WnbDN@{w-J z00`|Mr3ih#)ygE;-m-hL%SmSdhKDkB@bK2ow~7L+k@&N%4s`#&&Hl~;A?m>Zbg=gC zp#>o1LEId^F2fTy`m8PYKc5XN=H({9}n-Zy}e2p?(xfRBj`0I)Yu0rWep*dg4m z(9OSon3Ap*Tw287?^T%(to$o)oe7P5=OO+u!LvwX=PuLIT4+}n3AeliL(P1}@_mG$ zF=BuNP20iCG$!n<^+WwyHWjK%=1k>0q?hAEE1 z_GIF8Jnz=YmB8HN6ID(+1CTn)PP7bf6Lm|(f13foaN`=+{s?tj_wUUXS1COM{^;wE z{y(PsWtyc2XIDM`uOsTpzl#pEWqf~-;Ci(c*3ebf;VQ9SgBDX2(;@EHrNx)HfVU{V z?Dsfft09Q_QH;uXUJoXq(4RrdX+R=~Wf!9XEucsvjO>ej5N{vD!5q?n4*Np9?~6do zzHWtLL>U7agvf39ZfY#^6~_W1`tZ(lb!#S61NH$G-?NCOA^oN(VCB=%bDCkxvi zMBd+Iuwb?#1HcMC?!$-$^l@-YeD5-?UWJRlN53ucSsnV0zA)HF$IM+2UYKszM3J$` zTJ#kE`fbd27?>QA3xoemk)ULnz&{fZloI+0eg8AUk^1^6Ht)c%vTf8jhW;6@2YiSy zqk1Z;V+^bU+|mc?W49mos7J+jbAdz2J<-Zv5U-J!pvEZIkc748;I{}>Y!n78TJ{=oV26Fg*Y(p*^n2cH(VM4i(-R?R(vFU!g|0*^OKnt(FPiG!|z1Dedpc zApWW4N^Fz>VDlbB;nv2Qp+*3p9>IS?QR&A3)&`q&-!r%6`&=~TU7!Ou)gEEnSzC;= z7^*WD+c4*Cq);Qc1ky8He2@;2VU-r}Ag(t+P=?cZLA*acLmKiU(3Ee(2)xEVNR`3J zFt@Mb;s}BXs=dkmv}O0?mea%l*rB_tbKgO*IxyBcK^ze5g?~nUP$2wKpavF*D}RFi z^f3VGNnGQ2J-GBBdy4*>_>8*r3@wvcM+ApnV|RHeykdxkm#m z2v4^qH(}Qh-K~r2KnazcMj1(gNLpal;@hpqT5roZcr2rkFsIuD`0+fyyYfxM-Tf%u z_alINSHzLHv(!zCFwF&pVlMe$vH zyn8Tt&5g?lj3(Hh4&B*Lg#P#oyaS9sg-wh`prnfHHeZ8~V|18bM+CgWy{pU*<_y{7 zlnCtG{WeXb!WOnS8-*~tJQ*(Dn+P*C;x|<1!wg28S z`dK&(kH~&q6zKt6WP~T~kS=t)Z$hN1^I+pFKAZ4f|K{N1fT1xK?FxOG^uM4Sz>ZLjl9>PtbQ zt$Tp1%xedoY5g+b2-1|ukE7Glh)|+GgE~PXs*B+i881~MxQf$$AQ678iJWPkFLIB> zR&3q&;bPDM!Eh<%zQ%jH?&+_8?|LTECyjEbEHOhddK_tmk;{unH!$wQfTu9U#PYSO zKgj)E7=v8$iqeZnU~u(OT2dI-I1-|QL1h~+iPn9_jrQe;`V}Cy(M!ViJ?-N6)=^um z+z!R9S~#=b44-bi7#3RXa23t527o8k{V#Qu%!#Nm2DepIuPVi{W1KRooUVM#R$w-W zRUQE~Nv^tej9>|-6I}sCi;pUTk=d~5&JKjX{uUu^Z(@XngsT=lOBik7w@fnS7e9+~ z{$*em_!L(4j=}b#t;#689=iEEB#im@p?#NNOc>L;5_W|+m|hRHAc8S%>~5OscO+bS z`&@Ya&ps4pQ7e6-cQsr=+MoqTroh?nDGxpNeLdll#k9Y7i5*fU6z=BqRw&UWQx}Of zF-=RwcpsF)kmP0X_~srds8{CKLJP5fmr%irEV%Biu7&0ps#b`9u`mj%JHQwM6w&|) z0`SCw1ZK0Rlu|WobP<$Qj?eiJ-TX;t%ez$f?Rh3oB>o~Jr2qhRtUz|W$zyLG-g0=d z3h4L57dtVHX4-cv6JY0C{SIpzt4&PE!~a2jP#gkEG*S{1$PBnzjbduYD~(aS?2&)c zm2TTG0b9oV$Ec_VI5hDIZ`HPl1rNbPzn>dtRiw_}7N##qPfy2#FG;F_P!yR#C_$us zj9mHvxl7zKW(e~NEdpXkBc!bQ4DJigM1GHuVtZ>*415?t=5NHSldOWu0>@L z&(n2%RSQW9pi7tCDx)A}M%oYwf3&){-)NgUeEZP8^I85DRTXr5v}mj$B41@62EY}5 zKpLXU4Q-8&<&l1C0j8ud!UU5E8iy>w48+Af2~C{ny%=g%#>Y0=9=<`tM^~Lb=xG-j zAekMR9tcsf(+d*>j8W^Kt^NhalV4o_M`vdJ}!F^ z6#^bRrj(#JD88oO%oy69*8MG{R)oy%;YHES&j8cdzT{z6%Sf`us4}l2WUB>ZKnz7- z3X$Le+em`ryZnUsPOnL2=)JZJ0TdD(dH}c0a)WG*7~M`2x;feXqi{-h9$@RkH6MnN zi7y7e=?fXG{n?NMJa*S5$p*mSKW!vwK}H(hD{1<8*$1Pf?;POE9*c!;xf?nl$~L&D z1tZ>MKYEfp1PFU~Q5q+`!g6sA(A#W#*mMDzyKnlZ(3U?B10dlSQCb<02sDC$H`qF> zz>!)!427INS;dbyi6wR3aN9g5mUU~*uur!2JIwg^F58!=KSbRwih4}-Ysg=9{$2e* zC0g59W3Sh3-@ao<65P?}A6@(+2;`6JbKxF_OSf6|wwCX*N@PWHbt8;S^e|eHO9#vj zK^x+=F3R~j>G24ODiUHXPQwTQW_^8_u@x|{u%FP?Nku~}L6FFTeeDFGrhRM>B;-bX z>uYoni7Lma6#9`Xp<#SWN=}qS?s65Pv&dZlzA`gh$RzP#urKqWSORWbX+ZumHViTc zOvW6Z6?qh`QIAg_>9N;LQ!TDCN{z{ zQ!5hv7}$rI*vN(I8zZ5!35sn`qDK2rXivWgd`^Y_?2iNRi26&|x6GUeW`>wk+ot4a z?h@A!dF3z1e&5=@!yiI`S8~HGecfm`yFN9BZUy1#3 zfe})}3oT@cT?@FLM5WGI00gFbHG>m>dXeuMuQ|Ns8Tdg#rd zRz&=thhdKMdEdLA;U55l5sj*`fnXgJ)-mY5e(Qdi8?ECFFoha`82@%ZV0h3XjW9ky zyN>-4I@>(3mV?V0G6r;z* zpH#o!YfXnm^uZf7MAqxeAk-y%#H%1BAS8+Y4~|sJ!am%#|1H8s#Ib1(HG84Ge0Q(t|9?$?0cI+6pvG+mdamyh+ z9}zo`$g>&|+~evVJ*?L%y~x3xM}Jx+6=vEpW+@CqoEjeT*tj2eyvG}D8&$Q2L0~Wj zYb_I4>G~P`f6s;9xyvAb=H0lfLx@lI6rc3|mPoy5n39evOb&sGauvM*7Q)%y%lMd< zBM~|I3_!N_C!2a?0LGE36dEvT>P{uJhhYE&0LAid^Aj*@c&V%)wukBKHHl}Td#7+9 z&^X3+AKo!$-0N2Jq4oxI<$f`A3wU>2{AB2!1-C--kW0QvFpEWaVqfAfJmp{jO1Ci6{612f^@(tCeIb0LcNww& zDA^m#`p35%pnyr@KQITxxf8|n-wbcT40NFeIaq)hdRPYFy+f#PGIFCTfE5A&t(EXx z!u79!U64|;I1dld=4b5^?Waa?35+oi5O!8p>*3BiDgazV8^mFE-07Y8+4kXq3V;gP$> z`)@-0W2#?P+UxAEL%FIF+h_zQEKq6Tw&?#bFX7sF`QV-%w`u^hN742wmPomIx5t2@ zh%XWMJmFLmEz2u85LBss5Vc4$P87WixF|l(-`wF;LNw8kQ8fe;FyelrbTI;P-w17f zv(>!hh9>oYe3;M4j@jG4*j%QQb`7o+yNG9d-8q=9dECvlXTTUz+Xe|lA`1II?aBON zN2&jZKo;?CC{?RrqDmZq<}@+mMB%(jpiiOq0ZE7;(#r z%J_{3ewbs)Ko3+!eLYfgh~*(yeREzge*DTKGgyh5D2!GOf8B*q?lfjGD=BmRS(tze zp;x|`F?C~z|3?|;sFJe9yNYA(*lX89+TI>1w^adnI_@~XiLtL^XG>dtURv|}zyBpT(QPKci$D?)?0u3KTho4m%yf>QPDVM2 z3_$9c*y9|e&P-czORBctTKK7-`W*82@LyB6O9li?CJ=a!6edWP+ z`mFw&ApPa`bl4=7WmRhG~djaj@4M`l{4X z@y2xED<#5!o}zmV=_1j0U*sW3Qf*^ImTp9vgY$8lTH-SYHA>#;edmMXd}VEEKQajZ zCWA11ulw64(hm=B71wt0rqD9HgPyjRN3?wYqoF@~E))Cf$)F8@E5WBxB4$9%#!x^B1FXmKuLcraXsk;l8>?i%t;x?wxoaseNHF;(ol($C0#g#MR za`jv|+n5QL+Y2%2j|qS5mwn#ogLV|f@>=Atla|-C$~Em<_?JD!=M2IAjyn%}pfFnF zziwnOwu+6gII|q?mexXTrb;9{Bmgkmk?}rgqYwJ(Q*>SCK?N=YjyEve>#wea#uyO- zQ9-rZT?_#+CI$~>n!3tgqMLY6H8Jq08o&`A%!|JPt@%eV004cYJz_zn z01Qg3LZmNDRfu%o?TITk{-l=FfoYpM*sT=6YWrp1*D%nqga00Ns4$hVc8&}H2(C+H zzUcQaW)Ru=r|)q~??gHo-^~f}e%c@UW@+3uXda-Qkv0s!XXsgRclU4Uc=vUC9BWdb<$n`| z-DP#x8hI)7U;Qz{9-#A|e<8~QAOjHR*&Yvg;-}~kGZA9_KT=r_7gnp`Gq>Ae9_#hj zVe009fk{{Zh3kj-%qQN;gFMjoNu&%`GzKtC6K=V@Or8q70P-Zl>R$a+HYfa&D7t#g zQ{yU~Ys}4X`6E0W&yB)zXsv$>@%$Q(V74$jAhcJJfbuPhDDWy(FX?%z%b}WnC84ew(5)Bu=dSnnA$3Y*KWNO zet7kx;aqDrT%6zM78Vyb!ouiu zSglk-1B1X3>;p!CC)H39XFcZYz~I0ZDy%keMZ`%Li`^0MI7ZodYyt8^|>vZesKBzdx-ZLN5%gd0B+*{Ujg~oF{Dz;4#<#Pg;&Q6 zX;9jzyQH}e`O_Ho)H8c+9pO|{&kb!Ol7^Y2qr_nhBkb!F}do=pg!INKnUM?8->Z z99via`;Dy>-Ky)NL8d^?Io!8$M8}Jss{_G7>}W6bQ{?egMHui0(SNyuuAg?y_9m(1 zZNP)Wm48OO1=hzE9?TdxLW=+O&96o>Ov<)b7fuZARckjhYQVsU>xy?MwTK0yqUy=hxxL5Xgq# z^1@WIh<|W&i2GyQ|EO4Y4e!d|flgOGdK;(xfbh34%imDmfG}HuYrN()&yc()G7ISf*-On9B0W>f&qBydVdB^ zgM=EM6dOb*T;B-e1bI5!p9&}@SV>Pr#Q(?-JJgS|sz^UT{TbWZjbdPdXoP>0tlAIf zruOj5B~R+RB~)|7S$MIM2Vs)OqSOs{wyGqs!pM=8PGq{00p7!p*?C6a%?X$^jU<^H zt;VY`6O)lR=ZMy)rFxIncju52l&^p;Su`1kVhrXk+H)KL1u5zmF-!bcZjyx&OYP=u zR(MD;t{6{(o|$02Ipw&lvk4KX!sHY1XW{--xVk(Orim_ixp9V|O_R}R^RP*qT=`oa zpH$T zXwGGr0K|g~eMXCz0FgCwgv9#krEaYUq&Qsp6w3i--&1Q%>M&n8ybl)H=6T(>gKc-L zxMeJ||0?w&b-RdmjPtMMe~kRs#D#_>LFDG*Hb{_OKhymH$qr^GZZ(r!oo^7e5`W`M=#RsGc3>UZ_0L77BArhs%OV3`FB*4`WTm+&k078ku#8w)?aSPZXV4|1p84!`%xy-*qF zH<{RT==JUEp=HmWt@n5BGS0k6ync-NaL1~?vx$M;Dz5Rtg_}<4XAacYZL;FmFHGeKow;JxdQ{BX{tz%ZRd;{;vGr40poshCf9WPzxUm zFN7ZrAIJKbRKom~y?QT2CZo>i-^22MEw>q##z<82Azc69gRz&S@2CfF_J zAuH0FSD`)kzx?Gd1N__c2*d%9Wb{gcZ}r$>lRdT!?`LO@>90ieq!l}7ceRc7eyX-x z&MORD|NfEt!zK1U0~ihdFzhhmpN~DPh)zpWUH@7#0Z0JqN&ztbsv!Pv_*;A_%@rAH z6^&6~W_jW#JTLq9K$;3{qi_a$2_*nsLM!(nu04=xi~}#BQ1AaZVzlpz9`i#I1*KJ{ z9Es8K8kmj40OVrm-*r;|))1MOqSg2~^Bs@!L&MUeT4HygsER^m8Gr^vz$ydKX7w*& zc<)7P1q(6of!$e{)jCG4b@-fey&ejDtAxAjY92LLM0l*=y?);!Qgn=jefq9fK)fHN z2lS)zd8u*{rec&;{{&RbcH!a$%(9H;O zNcANC!cu`$!X@GijBQ}+P=zp)tZAB<9olP{t$VMxJk%A2aKpLB$@^ZHM`;Q+w@TD!2iR=^VDGMijcXIMKlV zszmJ?9Bt^@M?mqeu3!`fv_nG{_Z=7BGMEYRNq-mG^PeLXkO7buDFLuLLRJaC7pBT? z+#j^a!{aZ9n+Z>+y=k0M$GJ_N>J|*L&2cTWFN^k9sDncP`X7WIv;5(cZ-56wJ|4yL z9|2IPfei0s@V9};e;Guw#mc`5pfNQgSfn>+Fp|B0``q)LNB013Jgs{~^un;NT^%91 z*X7WE;bTxF2*wP<`|#9^_Y`H4^_tJicB1XM|tG1MOtR>hY5-`oCX6sxU^_XbjE6 zxy5(G{oWm7@Sh76Bw1ZCr;L{_cZ&HRRb0i}Jf#5(FJvNq8}50l41yUgBSY|*KJ#ba z9sNOhsN=EpE|Qp=5dIBJ2Cj$Vi+2(GZ-&yDdX^l9acHj6gBbl4(fMC`>ui|4IThwN zr^Clru7<0Nmu9fYa{-BsjJ&HHm?{B^H0S52(jbgkB2DrK0U%Xpfe;;`dT7h; z$taJR*-x#J2`db5Q^&bY9cl;L=2+3e+++Vgqi&bT@%hKq2*{(2I8p{cqYh2^4qI?$ zLi9fx7Mt^7jac-H_@=WS1Px?Q%h0m#8$5ga727+9edV)%z1`(k@+XRHZ?!{fNs~9y zAx~Tl{g*$B3V_w({N-%5=!AP;7yzU~(fEz+I-s z#!&g3!SL^F=VOq~DUgcd|M!OM9}ILRNz$AAI;daYas`*ktW0J@slbygu7+PG%idYk zV&%q0xODxy;qLNMXk54&8l<4^8G+J(OHqvf2sGii#2C)BPCJbYA7)Soi=Sv{>+e)! z*CxAy$Brd{5#29YP|29xc{7B!{|FG+2xC{@2<4eYgbEF;;+dUD0L<`@>rfkFPvpW*=LlQfIlf6VujxYb5?`YZzj%b_u^h z&B}oA+rO^%P5zUU@GHWJb%!BGx@*sE8X+zJ75{Hw1F!)jP$hQ0%;!Vs*c-GMPb-%_ zpZfgdb`Q{jO53{xAL`YJ2Tx?TE=!!=43^}Rh>>v@W4XuZGvtpY7~4-h_>Qn5@kgwj ziJ0+;Z!JMdSp7E^5&ho``DQ(oF(#X!ZIc+wp~)VIkTdUb0rSZeQH!Gfb`&kEXO>_o zu$EwH8xWDtlX+QuirxU36a&{l807g{2kFLE*cxM%i!oqll(A5XrlDSv0PHswX?)yr z-(!nneQ~36#y{K4vnQxZWUwcQ`CjXY{Bhq6O;Sb|H}QerBzaa1kvLHdF*5AKl=X>b zS=fZYuNJ~M7XS0>GvWN^LO4&rp#@Y)GCPjgq1At}*VX@bqqu*WRlh5L$H(z<{AJWs zD`-?`K&T8|u{lCJ_(3TVJ_a8vm?W?fZy@QB z@iP%szePYOR{Pz;RM^5ucO65|0x8q$*aLLP%OVa}MRee<6OMsNX+}U8PVXYA49X;fc>!bxGp&)B@!)l&sn7KVPg8z5O$oKr9Wm&iSjHSs(dA1`1qcb+uMvyhU^-7E9_e-a~` zA$<)1yJ(f0n3t_VVycj>ag53!ZoE;V@T3`l%ykXKNmoqw$HU95d2C$T5dX1IS-eGP z>&?)fngfY~`s^!LJ!O{LF%H8~2E%?I3_h76qt}3vg2XgCCMI~7_=|L_j7@V3v416u zbl(nz1;qYEtnMeU%OG>4Xtlcuao!*g0C_Ra-JTEQcgDh0bsPi7bK!Dt4!P_M>vGb= zdhzyTJy_fAZwbFv{~G1pM)?00e^(+a(29(OBwuMz=2@Xc=&&rtgSI%vsuNWIRME*S zO`rl8T_fc!D^ImBhW<6M(g&=>43mNmAlOF@XGm!iPqkKI$4Thap*ESD-Ra5DDb0uF z(F-`E%%Kh_5TUh3x^^OX=14J4BBc=+tHbu7a1h-A$t9CB@qlAoD5sH@_I%_3#(=}G zb>EqABFaf%08-}+Z`~h0b_QD$6OjA)pZ|GvFTYORE^_5vka-uqzdD?5YYXHBF-Fep zKn}TaY~Qojj-%7T$ghL3UlpQ%Q_KJQY_$BZVp!6Orv1Zrg0$3CuH6M`tq=?lYh|LV zIboyDE`7=HEg#_hXz_2fKlHZxir2e85}E~q#FWwhPk$zavmeR`jh*+T82|~49Ee6` zH@_XixBqWe{_A1%@*83N{5$BB8AlSXvk1vLggiGP$YgY*#gE%={h6TW<9K?Tg zRKIiJMfz%zE1-TYzyBb7H|m+qGVqD;G9+v~{w@pfB#V*-B>=4RLm8LAzqIx7@HyUh zjTLvJ`K55XOpf()SHitd|756Md?i!GEL=gCKb?)qVXe_(zw-@xR;Xf$_7)I)jV%qf zBqOka1jgU7y~wX$he5lK*t-!XUR?{-=0_we@aU6x2G2a(;`fw4J%IZ4Ltm?-F~>QK4Dig zO*QI_$cxxx74s~mLt!qE?Ge3h;G5l5PgF=@Y@Fz(D;!1CT zI1e{9)x{BI3PNv~j|NSsA_=HQ%YT6K!5bg!xs>XF#G+1laD`v;ygb|kjuTxKlm4Ir zK)_BY1tzoU+%VpWx@7gq+w9wAiiZh^2UvC$DwFW!OJ>2Kq)Vr` zsh&oSOe`4aDdHVWqWA2MS3{`|S)v+IvkP&KiGHGSAJZ@~XAh9!-p#bXUG2veKPov8 zYG^Csr~lh908z)vs-HXp(epz8>lPA#Hq11(0C{90c~<|X!!DqX%b||R5s;}!UV#x} z8IsY=kurTT-cK-L z?`2Rixba9E7bwC&v?~Axnq>mpj5fnaDIX?*!EN3DVLs(ZM7HZq002M$Nkliinf1OhRFQB)R36N$vdHo_sE>(8pIk(4J zB&H{+qz+2k#7QMa!1fk@}=7|v+G!TwSDSpu-7pFaUjV!$6P z|2H8170wTgPj|jLA~+}-BFngWw41!aL_U5`vmwIVbxz)4W&8i1;&in_#H&c^*b~Y1EcY} z;{SPqOw30Wz!AKP_ievO-@qknkokm3-#B+Dy#67<2hHTi9W|#k!sq;3#$@XKv4hg*#e(kB86JUJX}!=OO%KQR`0#n5;dA z>@!#XR@3m_%dLe!3D?3JnS_?6*FvAP!)2JAnd(@$v;|Cb=1C+xN$({9JLJm-muGO$ z0uCx+HDAFF1L@Rx4F7P1DNy659PQDk?yfleNC&m@?~$syac2r#fg3FNxNY(%2z`%5 zLig3zkPILiF-X|Cs~8L;Dv1##fkVcq1Kh22#=|XKKwE}sNBloiWX?yxJWRI$4M>r@ zFseDc!3wG-ZKUyEEE%r)324&SzWBv2?&l346CjYJ>g+fX<+vGuG;>nNq)ti4Zg&uW zjyu2ji@%5xG5lJ(czesB8}+Z-&KLl*|LwuCZC}3Mj-yk-AN@WqCHIN=w}e=6UH^Z$ zNPlxQcNWen!mNY96lsFM0?8=Ar#l5fJ8$~n9??}@66&<>v$oAM!7iPL_+N$igYAqh z|9`u6s!9Ts4n(9# zVn9teT3(%Ix3 zy8f|0#-IP*cvxsmg&*8{HGI1MVUjYH!`04tqWn!oCMGk-<3Wcml44il8Dpj^-XG=O zf;p>(Hs|k;hb#4kaJh2^8-U69P7&2ni^Hm&fo_H?`OQ#)0q9>Op$*eQ zp%{WEI_0QOKVA0;=B*_d07U+sjeMwle>OCii3yS?E9j+9fh&MJMDV>AK9muEto@_= zsm!Qwr{s{W(%U6ex7XR$i*+P>J@D6{ zNuPiLp!Jbmldg*W0qA&vZykPfI(F#YcY7@5xEX--(W!IXre1ZMs-0JKZG@|ienH3n8|JVY!@^^IiEDm3+ASvFNIrA{G zd`-lKd*1ZHJ}Him(}PKgV3+AaJ+QlYc1q^ zi2O&kn9L+}DI?x50b&eT9;rkD@v;GBMoE=B0fBLatVa1s7F(A^murMAR>Qmw!#h&t zqQ7j^ILGU{WHzg@D({&1CVqz`J584-)0&J4$eyV#`)rqZ{;;_@`s*UeF1iGyDbbFF zwXLw3V>N^)Om}JnbpVh~e0tXCnV}#Ev8NY6<|iGAcpQUTB{R6(L<#^=&5z$loKNMs zd9KY9u`Oc&nC{LQIwm?<63oT?5ZyMJA?chE>g?)dn8W~Vo{WCyn{#CKJHyD7qI5=U z|IFa;=>6h&M14Hpxk(z{WsE}CM+p5hW-4A*;+2h-CPRl*16Z|IUds#_)R3I?5~j_xqd{SkEixUGhf z%Mg5EY?6H!3)^@@Qt_aukyUNGE<+2kHhsGR-QpY)#uA=*aLb;1&Wi2mv2Z8u$HvlN zRRWn!K~7pU4{cih%2&Q}mVIfJG%L|Bw_-fEezi3|n(eU`8+zQuj{_wvTp6HpCKW81FDEdcNiP*;D1CBF~_R?MM{>QP4mp%N) zR=e_%`$Qz#cLgiADPa2r&&$pppigq>HuDqgFcoqwR##f&WQ&+15_-;SgW-86sjgD9x z(G~KGQX#BN-6D)IcOX4!&LXDO=ifm~_Ata5$Sr*rHNab}q7dtkqt7RVt9or5526dG zmp5C^U#3u}5T+|*VH{C^5f`sXeETP;rN&5jsd6z)q5GY~JL84E!FR{wxV+a8ymp`{ z-T40Nti;!7=iRB*uyTGqY?2kOI*v>Psa_HING_CFUd5xB815V{K0VqQ=wYx#tbURqT~vau`b`4X+`NRfKd~>c=jhIw4jlbHmi^)EOPRDOiTWd> zDS~~tgS7Wwh5;BMRzQPT(U)1oHIU+F%%v-MvHd}cqk~*XyaFQ;jmwcTyWliSU=G8; zLHUoNO}`BTaFOFguWVduV0xWfs}D|Fc8{kVCj*c=#4k^slJ--_xlNsETO0UY*4h4j zFSJCBovwcxX|U?=YP^K*P(~n|(gz*rY((S|P4IIEozu6`AKh(_g?j)}TY|oC;Wrro zBcb(S*#!y^MO@)N>b8BK_l*7^$Xn=>BBI~Y0v5VV{#@k_OJ78IV~FPE>ZeepMezxJ zx-CK(+$^z|uox)DeX)m=(=C4cQNQm)6+7#0CQ~4Dp=w6Avb9?wcmE9tP(750e?Rt- z7FNTEp;hhi*g}3`u+2_Cd2uaxiG~%e6@Qeyh;v+G5q0P zu3rqZT>|ft&2OCJ6p_((4=)Oi(l<&yO!NCT&X`Lh>)|^WuZMU3+`A;?X@>P>i~%=s zDFaSNVTjJsGsK%4yk9hR^pfD<8bP4$r#Q#6TSAj~REz!{*e=_d`JcKce z#=wo+c*AJn55BFef0}7~E?W5au6`!;r!Ik8T^LYDsp15gOmXf$r3t=%6A!K%q&Yng zWSqqw;D?CgqHq6r0oxNff$bLT^N@H2?_$9ropDjuC1ysqRlyFS#VjQ0l?IwoWf}fH zwCSG`69Bz4KRuvZHZoNn5{r}9nz~?kKfB^7{XI?wAbp}ApNbuoI>)WYaplj})xR=C zpn+U0sl;(qJepbm$JJk?ybuM-@WazB`)xJ;Q+Ff-pvC`YtVKcrv$}aC1K^8j>WGA2 zz|157u4WDhXZtnjnLKY-nSL1KdMtd&w~b+#G2WrXq;Qo`L%h=jH;P=GCQd-Q!%j6; ze`EkWHy|=n5Ut0lk*hEs1A2a?0J$bwqXuGVjmix2L(St~l*iyIKLIC??%gS?z$oCA zP--A*M*OHxxiQ}L^UfmwIUI+9D6ikEMDiFv$7uhX5Yi18fGt+Vy>S?z2`ro^Sp7^) z06)Zor#(%4kk!k_F337$uLnPobBU13WccNFe6&FzcEcR4Fb1A&F&J*4Pz?+9)vyN9 zYL^MVLJ+6cm{HRxu9RXdfBLzC6aZB~9%gN<1sl_qWbyh2=h!F3ym?&1-D`WN)Uv~5&diS3e_**bH8saUNHp0d@A%EtZ zp;_d6SfLic3nSoy5f%i(geswo6+0?SBsd_;puvA~sQl;dUqvVMKgId($oC<(uvWwo8f&wS=H%WVHE>VqNxfmEUdK!1P5!$&BN zLQMLD&Pe@#or%6BBLDy)IF|o=xNHv{O;-FLE!e?iSe5rpM1lAza_`&MJ^Y9dZ+`bvc@sy}%CHm&=eDLo6C~b)^Nmp+Wz1v(8c20e z#b6~6#+MzCwatx0Wr zZ$05y7<@;Drh!eu(&&0v99s!Xlj~t)n&d<3;t7j9K^~BCJTqphq!Vsp4}wTp;-8qM z!?z-X16@3|qA=p$N*QC&NpcL1*MS2iBq(H_(a^t6=k6ALAoEwj#tOAghgEtPX0Jbi z6g>wG9R+68_lsLyR2_t3?=cX{fZGuNDllq_;87ARnaT^O+vDm-obqz;ObjazeTX<| z=jDF|8udTG09@g;G%L|BX_-Vn0j=BAfVAb*(=W%x0Hluai&JN~pE}H~=j}M#=(hgr zzy9lB{_uCGL&e}fI8!xn(_yQKCNq{Ay5s=6UEDgV_(I=rEuh~V32(Qj!}kzBF0rDQ z?6^4Gw-_o_(e;&&faKO$xzV2Ht^5W2I;xbeUt7lrJJFC?Y03+X%%Om;eZ=#2iCi z5T`_)ed#2SQ~-%boil#q`4NK2l(pz}g+(1T*Ef1?#LvyUjMsWT%&*RbKiBx)c80`BHdi8t;Qklc6!oLSljdV-ii@N~q#WX*FDX z_h!fwC`Y$5JrX28PopHb^?efkKIC6%JeIxw-3*QQBvq&p0lU(R33=hF%F8$G^ut1vXx%H{=vF?i)N>0O+ zjKwzDuEQ4Lz@DkVsMaw!d~d^aQfyU~w zWq3b3^A!F*9W1i{hxpN{Brs1MJ8~fYzs&KD9=HFJ_+R~w9NL3EW%m$8pY#@- zeUqA{|IIS~9q18qr~<3<0<)fJ1K_aRoabd{570HPY@+H+!#k|3bph*x2=k=eB?trd zHuR@`ijFOE+AaE3eZC9;*XKqM>9b18H(2S9!T?BETvbBMRl69(r+|*xcNEHOS>=mI zG^#32(15{oj1rmw$cU7nSm=3)laHR)mF|-_{L5y)gvZ)~5!osuZPEx4gSz;=ezR^( zN&!H6-4dc`Q~*Yb8;xY+u!w7C_aF5rkzN`JL4Hs=QAe7I&__|{WR~d`7J(A;+}=lh4I1}QB{j8Yh^Df<+4{Fg~-O2?DHqXy0S8;HwYCgv!eKa zvxE^K0gyJSqcDe)NMmF|M!^Xa1fZE@^`B)Hu=N5__AUFo<}s&P{rV5%vKH|UYUO6A zjw=2yLZ}EgtNQC%D_O_KDXp}pLoELu5jVTtNycJ6y8DGP46xzAod;3R|K9pR0ip}M zCV_#P9H{2?++l|<%4`r_C~=PI<=u}D+8!in)8!#G023Nu&ah1e#@VF;PNEE+AM{H0 z(i zNq&cHe|i8^sM|6B_rERsMb6ZuDbsMRxQ+E#DYfxom6*r~^yd^prO$ob!#*It+Z}X| zV$P9sc%q|+?=C>3iS=H-Y#ayr&!ta909+VF`OF!RWe$CLj@7)Y_`(cm7}0sm8jL7C z#!Lrla>P#8xKA9dG$5bCGQ(d)=t{%k)RUfWaN;)4TEq2kjf67zl)Kt~paS5UCs0Hp zihQ;FuR(Y!V<5kUOQb#q%uRnR(u?o}GpP!oL=dXUjqv7VHB={7!X=Q;XB+s>v#OB< z`S-YCi(aPze}vM%y4iP10+(*G+Ye)&JzH zp+El`@Qx%kuKJz-Pv*n5=~@AwzfHiXS?1SE;Q0mMEK>v63F7C+mv{|}Ofv-v?_KDQ zt#<($;W-o4{3l=d!WaIhAvM4-E%QP?EKUR;XU!%(mLp+m5lg z^}O5EdCh_K|1WWFQ0Ol&lPW*p%D zwE8zzI*dq{ya8>*oIOO;!bbU0`m_T)>w|C!qZ^GQ-2#E5R}jPN^Nj)C*wq?p0mcx9 zEbIPkn=`Ny-RQ)_8VlZlEf2}zLoSmL=bqi{HQeH#Y(BCZ&kvqs|9U(q5rjlc%e?;@ z_pFYDvDL9~p*sfyFa-J`s7ULTs#-T0;~OLD1iEZ;Yok` z9EMP+0#@g5hd-WK4>zid=*FAjFQQ8yMNOr2LJ}znJjUoWS(b_ zyqBjRyr- zm%^XP)U$Z_WM>4oKx_eAObC||86Dt7&>C~g=w6;jwN)fQP#0rl;nq2u1qKSg1g-k- z@dkixj1$x8A;xh)-R{Q(@Kd}dnoDWK>Dm<2u~>4tu=L;+v4Xx|9Q-~u>}H6 zQnSJ;KmKzIl8h^VO^G8nmM(hq)}Bs{FmObZRp%O<;sypkbwoywwfx_HJWp}uri%(K z?h!q%1BYuofd8Mp_lS{n+YkFr<<4<(zUhVgGQ*=pQ3mx)(V#8C_Cn%9S{PmlHeh?9 z08krk1PI{T-gqek-WkxsuwfDOGeC)?Wj;PW@}(QzO*3~wPv@@c%H`khe0{oW`u6lx zRaf=Q+&gFH>+h>Cp7_t9xWF}synk5JM-QL>0v@D3pugn)<46E&yR(d?qW)w3l@}m7 z8`xzCK0D4vFuiPue)Rn^q;9AV3UxTIT`Yz%NSY$Hye?*X0A$wxBfS49Rq?ZmeKqLY z1qIZKi^SXq;LWiK_!8BkzCx)Igio_l4x985YVoiL2UUe|Fmjxol-2MlA3NvMqHHA+ zsr0J}(z)lkm-F{un}7RwUTozEy-SqCM>E&}EItmqq#0gZDkFG-utIIrYGb<~$BIUG z3Zx-HV>HN2DsYN=Xoc@Fz+D#y9Oosp8n5Q7{{AbRnp^ zHB>@`@@*4Mu}3_IPy)2iAo0@5Kk59(RD&qpWnPkd3>5?UHjtjRkP0XnC}6LWkk2ze zCsQH7Q01kK(t*mE83GOAV7a<;;;2jDtc~w~|NAs7E{KHF`jNlq{B21OXTQ$z@4#)J zP@Qaen&#=)ed;g?l!Bef{-5 zYaEG4-SCuqBpU$>^bWQFEdm79FI*3`rIqlAtY!~TB5XlIs7~;m+01%1zmEF*_>mm9 zx_%=3!Et|DejI*2dpEp0e=lsU?1sW+mhWXoe4c(6wzJcLp@pTon*oUoIc$=l%r4~k z`-l7ONJ)rj3~C7Any!XS18r1tsIt;D81Ahv_}#!ir7CSRfocarX1%ZoU$= zemT$oaTfbp^HV*#-1PFQ!{}-2B@r;v2W33GLmE?s=5d0qNVRBiyHsN*&iloU)5p<@eIf?)Am&;`XP=-=sfoM*njRj=#MB zxhIb^_mCD7VH+2b57Gbs-_5zOK>!H@{}^{|pyI?Oid)p-BBE{GeKWKld@bamaJ$8= zFthUsI%@Pr=%MpUb_aazK;Qm6+?4u*ZWQN{xVwKb9Svw2+;sn0+72P#sbPVPh__hF zg*QIE9A3YBBV5>83SaHrB(D5ylmJNckK=PzT^+bcNd5o+8-7akzgqZcW;N6|sr5}WUbLrm`w*czzms?@_8xVmr6+B0f2F>W50@A?ufAf7j z9QKM~dUGaRgIm24eM9sMvByU*N`XZFe;Gaun@A$=6HF;w#+?%H7+qwIlks^g#%8O3 zg!JVDh*k;P+rNy|>#Gm~xce<#W&T3}9nAT0wjDZ-TrR|QVcP~z-^0V}x`a342onSu z4!k(18X#3nbpV06T4WQ=v2KgxC&*KO6>^l{184m&?3FKi!bL3&l5m?KKRN-k)o^VZzUHw(142cuo>w@W#*=B?Z5&)_iTYqjtdqN#w^i%zV z*MFSqebTvfZP-2Iz#7h^c*GK_AmW{a0GwmYv_Ds`=fA9+ebBPGmO%uO(H;@?;k%|2|DBhXjKWogT;6rU1k+Mq$z`00Zc7i7~^v3f5EHctlyOl z8f>Q(RVP)f{kH-7kEeG+gAl(nvm|{YGGz|$5RFI=hh0w|EY)*_J}wZRICD|V%ofi| zYFRJmK@HCr4G|lRsc0hV{$Ug%toWP_pDF+)p-SBlwjz!v;-pfqsOl2bQ^vW*vp2@S zf?qexhoku4xBxA-ks2Sp*9rx*62@5iU#k&Ar5dA5I&G zkpOUiZsi!nIk)fjf2h9$`a8(F6`-UP|3fMs6(5LUf3^B|LlThn=g~cb92xmfQP3`- zMU?>5F#e0V;0Jm5qP)l1bkRzrIV z>5*x5BiHZjK32TOoa*B0fXjV&|JEgb!gY|d;Q9u}gh-uc2#tFw)*M2Da#jR&tOhUT zPgNuP^to2{`r7}+-235^%3~1!cKGDhqfmSuj0EB@U81)Tz3WLL2#)TcApY510{%Rj zCnWStSgFmE6pA#&ScRO$E<|!orH%F3#+~)U#YZvfU~O?Hv`IG{xqm%YPM8KSL~&|xw+ zH-12{8)!{{P302J{5)Ftex^TO>=SbT?OnLSPdQ+}urnWC!^-8RTr>3F_WK0fg*pc=)dSiM7ssqWssk3>?Z!Ntmt15-PLuMEl*h5g~#NC_~0T0z#LfzSI9v?Cc@~d2(d6i|2hv0{-Yhj zcD@!K5_RxLH$Dgtr?@TGzP#1E}aAf4=tF#If6f3Br)00!>J7#xJNaBZh(2>He^g_208fg zkKTU!?SIHV;W77)YTAxV0228yJR;+zqn7g|0Qw=4$4}erpwwAabpLk9?;dYp4E|%3 zF}Z&R!>h^l~8Q7iqb zoNo`LzE>Wo$LKC2uJu1z$mYA#5x|Q`MWW*@3LE7{Ygq8th+$BjpU1DCZ%i{+1b!Nk zKCMVtMuR|NrE~w*GCT{2Yi(yUJet}hcLCNaxKZw512a$VfJ}Xn5dztKw$bBl&(o^< ze9zlXt^75%%zXX#^3|}O-wvCI{2$D1VC}ya_Lgv?T+N3WwkVZT=Wh4=IAB@LV&0q( z1f^Q45fXYovj;J*LFRZldMlMmC=F^71#+K+GCQ+1HUeSIl)?;I?hZr$ejbO5;9oI9 z=Nyg08b9A7BPadbYvFQ9B-gONjhr5pfZ;qNDE2-E<|Lwc#368q&Fx~W7u^6GsC>o5 z!x!qU=pVy|9`DOy0X*@R-~D@k@9#+f?6KJzXPCInk$u``^(!D_dV~T50{77n1+V{QU)!~GCz$JCCvG&O?571r1?;la`Eb;bd zkOrAtcHGhb{3LlQp*3n4ej$>^0IE9+moo=U(BD5=J`U1mCX2*^meZBFut$2{yO*k= zNuGmRvk`jEyPclO^6od=L^MZBmkf5}eC=DLzG z=e+uZF?5iu;M?o)L`Kw6j&JeL&ENQq z-`e`4Kl+0!wwSFS$E8oDJ(uHyzTn)-^B@3hoQ+Nmw^KY$onuGE&id6~{Z+;P|0Ua# z1#y4Jn9OyOylDO3#!+_!)UCK*i~kQA^Wh-|U=JV!oD63wPSmMPgw-RLd}j|^?+-~x zS*wT2wN{w>6)4>bD}WXjO!Sd@;Y=TW_3%JFz|!jCiX@QFk@k1`?o?R#QI>1|Qf)b0 z#%tpOdh~He*HiQ>^8YBH??nZ0k5H%WD_B1-W}^LIe)DG*CW>NF6HeXv7IU5$_Ol;` z?-OilW@`iFUl02~`8eF(Xb@NJLinZdMnqhICKi@5fzS6ulK{}rPcMrP>E{P1T(tK8 z^9%2V|L68!ggOx>JKw>~_eML+V)T~>=@!5-LY;(H)FO7s-_gQhyu6+Zi+i)-%XoyC z7)nozEcnkMfPdzQ9lybOV94P$6cdk;O6<(+hM8OBKp+o<5{YPoaQvaq(Qk>ZB0-J_ zeSslhJ1lnILpn;l1#^IW{9dU4lte(K<=ZjI{HuTUudogY|AWW< z#f3!g!}UWkM(&@Ecl8cgr26X7HKc?{C`_|o1%|XE;LhM%YEwAEo zWZGK@M~k#Z>VWLbtG^TP0hXJDdk)cKsYZPFZ3uvE63@W>PhsSx4qf9Q`GK>SY&JPx z_1BN-UQq$;6_5zcFfUB~d+7f>;MW9%GuR9;-}kFqq^q3^C9K-Ja3A+8^-wBSu~wgs z>HuTxE6vazfTt*<>8=N?*}2~q;Q(Jv{j1Jj&VM_Pg@1kvBTEAO%sdVsE=p)???)wrrDSkn@}KH&WNLic z+bL;FRFZp*kXxdevL2ORMbfTxMJU@Hn52JHoDt#7sD=qypjLL zhxoJlh?rc-ilwWF8y^?vycE6dgiUm_*bpij}V!)8|K?tyIzF9_N>U%&HjzSbU>`S)qOhu zINS&EKb|4d{-u3l?1Nn8`a%2=$tEy-LPHED+A>%T(dtN131?W2eWwg%^uDs6g;H4@ z2r~d;!bvnjC=G^Cv3PXmNlgfRj>&K(TaSz}2W@ab3%K7zCD4lE7s5ct@W8{p(?u>$GC`1> ze;(o`2QJ~q+q_8}CN84^kq8jCS@E>>O8}e!*<{HkTRP_SWXgFF0IBxA_-)Qo=}27L#EllKt) z{|VOr_n|T+B@7IA=90u!ifdPIliu=s_!6(-?sYFT*FGS=_R{AJB3_DY`@cuVG2@l?Q z92!gLXRmg{(rff@2?IVk|9(IJ)cAun@BFB(5uoP-o?9m<(4$JY*}WWdLM%c`X#hBC z@e|hB=#M`RABRu#>tPcwfZWwis2~>4h?8f-uTj7MqCKb4Wtk*kbV=x8moaq>c-|nF zOM~!8AO34p1L)>Sy)b01lV?_d{)liZLCERRiaeYWg+?vr7a`?NEw)5c>-d@cEs)&>z7}> z?5RCKpEF%zAQFb7jM`@&{>~Wh$$jprkB)F5lK@2UKoA-b3xR*OF#Kv0-@mK7Q}TNr zbq>Vm$vJ_yNgG49-KBY^9D438jGO>wd%2x3og>Z##;AHAxJEjzp#%6b7|A?B!zcJi zsyjUxxqsa&>#QxJAw=Z5qt*ZHcG%Fbeu>C>OK|avaAdmPy2KOIIjN2=$paODY5=7~ zWkNz{YLv69g?N1=2+iYABOI~y7A07>=!Ib2z9>cTcz}J}_egime~ba!p@M+u%3W7$P!hPlWss)BzKeF5wgTE;SZW|PcfmaQXnF0FF!HdHtZt5bH z&auvYOI%{vc!J7)=YNC%xXo<|$9YAZC-Qol1b|DEFXu@BWZiMprsKcuoYXL^9ge*<0bK34x#BmhbS22c7k|YYrM)s~f9Im#za&7$7o@w-wikpL z^WS7IRU`m=Q_MMH`8Vg03>YUOA^*t19A64Ue%pDb6k&FS6;ujMxZaJg{&J}9B1FTL zZFYM$eAw)SS>)Pl8y}I{HV4U5hO=Fu)yh0Dg5tMsZW0NZ$>165G-MM_zC9zJl%nWG zVM1XMeH}DfBNF1>nKib@F^>NGi}%8#>CLb|O=i$H$kcWfZh!tDw!fhEY0VK*Ft?6+l?t; z0a6LWgnwZRO_u<2%@6>LKy$ww5S0xQ5!3<&0(Er@+o6mGKquM`lGXNOh=3wCRUHgr zD-Z{UU^j_Y1qplfrWw2+GcPdhzXQ2x;gB79p;0;+j1_$ zoqg&H`PVfHch@8lN%cc?eY%gX-tqJfvlU}6bpD{MU3|VDFO36(r);xiywraT>U6U(CdB)vHc|&gek~`%ZSwp?$awXq99hc!{(gOEaye^ z4B5|x3lEtI@6UzR^`&sLbs^e_C?%2r7zIkWtR-Ho`yO2Xy}9-9qbna00q{X6L8L4o z7*+@F%ZHR^KhNPA`?vFYM2Q|9t2^u=)_bjPs9b%3RN!%prLuqj9dZc}tu?n0nmhjm zAp^K^8Y18l`xOlBWwvm!JsNBdPbqqVRgDVRnkOs)5gs7`A~Q%8hAPn}jc4&p%i-gw zOJGJ(+MsZYObhX(ipf!Kv=%SJRfTfxpu+hvP5jK>(y$_jhY*X#cg;A%)-k z&EHi2|6013_L&3#$oID3_4kPFzEAvr=*(HxXJ-B1KShW8%<;SZoDzTxdBL%w zw`?seg!TfkU~ZYE&%78X#Mj_dB7oAyIIwLj3IWmPgRtIsh+trs#3wyG536Bie+MB{ zJ}mcEq9N2AE1-f@OqG;~PHX0DFBxz|3S>uFANBWC|8cB9gk#y!Nq@5;Ndt3qhhlw; z#1mkYUzzuW{`^}xjOO5=ALcf~T5db6Rkp*2^AEy%D|d;h&<%6fi=liKBu)304ifrc z(RK9lryW@hKC5wP4)xr0tr8Y@X2UYEJ4F1-MUrIXX|H(Jc_kMu{xzw8tyB+NbJei9 zut%s6q7A~q9&-N!RQFlmdMU5l?$ma$K#_>4v4}?t*h^uw+u1>q@))&GLrLl)ZoHp_ z94_2oY>WgU0@{dgEU3JqiXi)S>R-A21{VB#%>8LXwR`;8S$XO!;zggy4AaF+9y5D6 znVQ6@*TiY02R?8-jmW?6a=i8U?@_7}zdy{M^CSSQmyPV-64Fn5DIy5~ttS6-w!Fw?>VM`7 zuTBim10sHiu3Qt*cfAbvKNXg$M0jf;2uH^&fJf*!z>9{tB@6!>ga4ocsKK3dHCi(8 z&#)25cQhAnezE=pOLuhRRIL0vB(UlJPe;7@#@B2?Zq#B2w zA*h$9JDKaBMt`b>kRR~q$!&V-JNqu!P9*@^V7RqPgan69D;@;@Im4^_zVbOeq}v@! zGb84~^+f|XT?Af3uysi1oXbxGLzy%6<$LH;XI%d6F&Q}m3DjLVSZ1noEHJ` ztkJMD(q?1P`h@?=gTrD6qhsl|cIj)xeOPVU>BAPq{Tp!N_Zkaf4e|e0Yl12OC!xAt zZ2%+!s)(*00zfe^Dlt!C5woGU5zp!&?|D^*?*W!l8@Dc9FU#xYaOLBR;l|Idg{A$u z@b&hca0yo<#s4C+ry;N5KdP{y7lYCKMfgQn$2IMPnXiV%)jN2FFz^xplZ^Tj=bUhc zLKeZWdL5z@djt^ukG{PgRRe{swNU=}=b^B-6^dJr!t{IpA(YoXi5Bm_)OjPO6%q;F zK1eYn^3RMVvq*_bO|rarC9PAu3le#wfcHU5DpilsPDe+e5y;l zrrpGQL~DPDu)j)dgS)rZ!p9`<=}u$2@j6CUOQ6+Rwv}#JULkCA9^$UwkKPaWe>~Rb zrAf!q$blRlTzW+Bu^WL|y31Dq~`PcCf zxRSx$r@S_u7Wv-;{ud#FFBS0;DeQ#raFO&x{8bJ%Xkjkmjn>A4A;*9grzN2F4 zr2YRyVjy3b@LaY`Jack!20!tVlW#lQ+4CX*tYuo3Y2V)w{l~`t_xG>>j{7z4Vg1c31vo{TtNvr~Rc1Zd&H*5kW946wRzqP;fT#E18kdVP^DDFJ{u zH~3E(Ta5WSG5^^z0k0--&svMacUH#vkpU2~uNeUASSxoG%gd#Rpq;yuEUE-7?)@I6 zi`@(Ys7zc+&VVov_US_SAXc3&?u24~jdjrsYxxTiAxp%pKm^!7B6c_1B@#C^uE&{F zz<3-&wv32U%9a}Fk@t!4sUj1oU}0 zLy#DfCrvLEVl=sef)tO*F874Uci4WV-WrF-41hR?myy(&S#cJ!W;~uDnGvAsAUzh^ zL~hJs_-D9#x!O4OhOIM?eIW|{BIvXzNR>f1W`e}LDy=;E1T^Z-H#gC+;xxwCg*IZW z0pY5*=^Iny#ioI8@UB6hjg{*ABR+~TX^1Hk8Pg~0@JrlkOLT9Lj*r7@RV&p&N=k(W;oqYU>!{6TKN8BrK*#q&f6ZUrsui-54HWnI3LPmRlSezdHJ(Hb%_4kZD;56xydCU;6U6$VrR`C~m zOVRkv2=8a(?><|(48fsK1lVs@y5Sxc-jB#Owmt{9QUU6#2GCe(01@S9-+sn3Ng^dQ zwH{bc=a8!9dpjY24OGr47CcGwfI0AIKql7l&-Bo+aXGZ@X50J24lS1Wb=W?So7{m9!?bUp79mB;<2^xYyNyy0Aip-wNJQ%(iFU}Ko8ESzd^TFxd(rs{U z4Yl6;s0MZ*6BNKCJ94 zgs*pRA>y75S0TpE65Qo@H#kQXZtJL~>)*Tc?eM3oxo~f~7@C)-LwyMmC4qY)a7wJr z@s~{UxAV{>RT1mKDXrdwB0~MK+zG`ipgRoV+KAjgzVHb`1Nil5^!_Pq+z%6g`yS9!^*A~|DL^!;5FLKON*O1u2^=sK5Vf$Iv3>-lV z&yf93sQfP6KXK`=bXLL@WFO9vvk-{3RY}J~P|Q2wF5!uH!h`7z+KdE+w7AjzPpJ2* zJi7-NXS1osg5+fSHW>sNvi2qx7TbTt{^tk)u7p$LfU&SbwGcI>~Q{fyx3nPq7GF6jJ%!R z|DyhTk00BM-s?V5eS3<1;QpiKr=p)p6<=-Tg;p{01%@jC7JLGM4xCdY@v2O;2f84( znBfhZixR0v=h6A&;XNi1?~_$`UMk>j5fEe_tNTr0kQ)$%L?-~F19AMollRHjpZ%9a zfW?SqWgw{*bQn$LXEH@dZwfcUD}={Fr>iJS&g*N9&L#ZbXLa)tWLvNn{C z^&nL6^)C=Qd47)6tw!;qAFWqJoWk`nltc@4^*LuNvpqGxgAt1(z87z z1C3pHUf`h0y!JGJ5V3t1LLt9^*c)OZ67tx;#DFPC2C&CP{LlTW$&^maWr>cWTNeaM zkBYQA7|%XN%}~aWleqp`(Lb?hhg~l;A%PX!R@r49tdkgOkHk>5DLerxac+$6{wL^H z8l=HvJ8V^I;US@**QSXHF;_zs1Y(H6e`v?Bb?1>Ud|~{|>M8ToQ6dG`-enT?ayqmE zW97Ib!$s#lqknlzq(_Yjkl}~2LatE8HYMuxnWIA$Z)b9u7a)%WAWAL3H`L=FfZP7N zgU|KjJYR1u`!~;7JU3(o;&TK4IS&HB%B04niupTrLOPZrs$xtb=s`|u5u~z|09M_o z`^N`V4*;Q#I+xftK7M)u{6Ogyas8`=9SDFm7Wk(euXC*UUwAdSLj9s47A%Y20Jp!1 zxO6jgrb$F}@BPqTM~8(-Q@v(h=t!?br1b1&O|HtHgEt%9%_(A5xBOkgx&9Pp6S4Bb z`h2+DU4;P92rx?kG_K|fqwEzG>07*naR3UN+$Rj~9bsf?DDv5}Mg@(RGoZGIK!rlW!u%zCN=J0qc zgcT$L-n0av+^E5oKMakJKM0+lPE$9G4lhBd-~o_VJj**q>dx2(>JJ#n?dQYdr({(8 z33~tCnQ(cZz)%E+F+h?Aj-xC?A-1ZZ8oH3(d@X#q@-Y1Q>Mz2>xy?|y+QX2Mc1XnV z@XpI?lFGMx$ZVZc8z=(%|)cUudevnT& zY>^kl(JNuI0x59BzYkV5J}2@=EkVd)Wz;>0-(r-y>&ZzM6|nE3RC-7cw^LN^t&UMwX=OHJ1YidOpk7%5fkMkJfB|*Kd!Zx% zbPU{os8>Nk82b^yOr$U8AGuRFRIyV*P!*SLYURN`Ej{|U;~eI7EjawbH0w;LqO<_9 zy^{PK25-d`ya+C%QD<)FkqWr#^LxA>v#1;{cs&q$bdNOKTa4(&TA2ojQm+mYfF4mB zyQn96`$lfFMQ z1~vFkE9@Wvc)YL^*5$B&+$baczomir@zm6AIdj{lBEC9$h zCNX{LB%@;oq^=wGduax^ zPaB7^_&YuBe(dF77LNVBC%rH=u7968L6n#Om;dr#+Bt8hheh0(dj*|nXEMb89;GPa ziAf(2%NPq_w6~1%<@5~A7WygX#QM6IhX5cJL8pcx)c#E5RAZ7FfYNiQT&m>fVjt%X z()!+NQ-;>D|?>P$+{!0_Ce}C}EWOtL40QA@Vq>-@ko==^S z-`w1k0QgO|gF;sV3{0}nRivV|(NSlno1VExXo#_2C2Th4!xkO@bwWRmI>68T*wb!^ z$RF;cwXm!v<<4PwIY z6vEdY-41uwu7^uI%i$Z{JGgo2q1UJO61Fu+dq= zg`80WfP;JJ-Np?IRabWgWc|iBLhjNHuI-0?zL)zHcP->2v$Ovv#(|$Ag5M$1>yKcE ze#)z^gnI3JAWN7di3n3^8`>Cdu5<0L^9{H>0t3~n|9c1@Qs>$IP`<2G0itEtA(RGU zezfppC~oJ&t?H%l&F)(e0CV9M9>@lU&WM1gHU9MTs)Dow`50BuCI)Kzmug||OV}SR z!~NsM5Y;Qg*7@{Le(tZz|8)rH6}M_JZ2j@YP`}TdC|n8cTg;nZ|1NU|@&CnJ*}M_n z4pGDh`{0JP)*M7YD=Zhc!;-}C&_%+ufl9)hH7*c{K8!virVHV3mCNNn;^ZODi#KGy zkAKOJ`+|v<1O+Gck^UY`$L`Z{A_C&M-~avJ$BZcaZhvL^eJV4*$`N{nZj|fK(mrN> z|B8Ihy*MeS0BUV4o>91Vni#F@&msu`WWW)b2`dUZ&b?xvvkx-f(FOocL5rT5RwXR4 zu$RdFZGe~Ya{ott2U?9PfL*wMlF>#9Ku=5iGKzIM*^w01NAExTksae=0Gi5a<5C;; z37~?{y%GRJu13%_gsA+jd2^fc?e#AFI>*9k$$<|xEV$7y~ZA# zI9Bm{1jj)&W4??`e@i720FOj7M8*6?kUudyF!&1X?;5h#0c?EPXtBwO+m_ zMfehV?7JjUYpqp?=Yd3sD4w0^H$v~S_EaGLMK*J62up|L{8OhS98qNsmPia_zL-&P zg!n0D1B8%`xnH77O!`WA4dN49@0^UTvq0SEj7>AQfA+@J#5Fo#a)lLlZY4Fy52oYP zaQ8+@g4FLTG+nWO7m>M}M1T(t+at`MnD}R#>`~i@c?<(Q>^u5ub%sM~AGsQ8Bx0BX zuwii=rm;cAcq*q0Ry4jk!zW%n%AAq8?S<`+@yOrlVBI|*Zgwum6u2u)v9pMGk9V*0 z$awZU*nF=OJmfx^%-((DR#;~|n^zG}&LNg`oJDB5x;>B55rWbwRhHOCKSKPED8BUb zFmvZ2v-S=POybh(0>o94_p`}L0Cb&|)5Bh2{|9e`#)B&H);Cx$nKB|wHN#5@BO2<_+vK)?*Wx-##zCrAkv0+WMT%_cx_^X2IS{l}c1 zY?%}R(BGKUg8p-XiG8FqvD-| zQGN1rll~QZfIkr#2q@tUp;~k98UJ{B(slT}zn`&|*^L2e0PbBZ&C5-!ykmIREbZ^O zd)mN15&_2juQHUoBzfPRg~*%+X*sqMeIo#+u?&@+;o6ZCfrt*(^$>O*g#6+<9CR&| z3BpsD(*uAtkyI2TPedLR3%hAWEg@k31F8^#b4O_a5;*kixoFA7^)}0%Jn8}U3@9>t z&gWBqd8`V>y3vkKbAd>Nz)m=E<4V*6z|_CnczkW;2?10>@`4Map?{;AWso|KW$<6(mpDdlbX{D_xNEj|DxtZF z+O!A}Fa^?IzLgP{(-4|UQ=KDe-VE7vK82JRI{=7)3ZmE)AZWK9eggSBE7HtJdmr-H>ZQHs##Sap0Q6VTil+vpk*f}SFS_p z+9enz0q|_Hzh0FgdceMAi-tGo3CsIL{KNHcVQ(hPq5_yk^<#85UH`_}x00y3{^|d} zhe8?2bm+{2q-Hsg3+_i|Lp0~iw>pU|EihdTIk(1tr2H-RPyrM_W%_L(lGgV>T#4T z@NBd#xJpz-YM7*;^(5+ziMs^2zGp87|jtp0j$Cy0l;iX>+ooZ zzV=(c^&9^d0^kt$amlCpH}6irow*Y$=Rp8ic^hL%jq2aq5&24`Qf2=e-js^QI$hHK zcG^`Kn0=1nV20|B49)w<9=e?e_=|2C@0sHR@R&YzzI!LD@c{081Nkvx;_kbl`U{vJ zxCX6+3-g$%#Xv0QTdkM*Ymr-k8|>keUI1uZ`gkt9^}}TdfVuDneSEdGf{1qx^e=!< z)A8&rmH<%K8`IaqhJHG`idFL4h$N9oFJA*Voraap{{0i*U}tDZ=fvNB6v78Tj9h;q z_b|*B|Bp~uz8A_DTVdvABj#8)Rdqqt(^yJe&b-NeU(q(esA^MK_S1d~0q30ebY~_Ic`LwNwL06c|_Ft-lt+sg8U(P$ZxQ4mq-vl!Y+ig(AR1gqY5Ae|H*Cf5buT0?%s^O2w53>!F*o0wF70`_YJacBy5fNu0vd9_U z5?g{E@m`K0t-ryEf5YZ0-K_ZWjZ^WQ`-zr;+ciQhj*rOk-%oS^;eRy({5wy6hm{P{U3zl)D}T|2v-VHEtr+gZaHf?ZAp2}z7SZ? zL;Ok{iSVzy5yG`EvwxF5qu(T$jstX`6A()X%whzn(bxPXJPM{+Gw6p^^?=-;SpWpi z4+bohkPuBHQl2LH&omN%DVPH1M~3`QYsk~T!pI{F>LC6n4K!l^&Dm<$oF@Z-5&#Vq z!Bx`!&lB`Kz4kB26{oGVD_s^P01yGqM~MD6kN_AXZsiUe^Txnhde|iH|BTgl9g7#T z)W8Of%W#C}hbb;SaTafjlP&XNd*ThhbAapOir`AZgZ(!hpMb}I_uqS_W2WRpOKN2L zNcx?YL25kgKwK8DryJ8gy6j}VN{6PigYSLB;b=0TRdoLvdYA?3xffEUDh};IarQt^ z-70m0YBb161X8K3FF;kFdtVJw0R~wlU_uvIu~2E1BFC?9w~^gO7wn$=aXCK!DfTt< z-#Q^**T{Ca&DK?CjnP^}SP|l%{Eo4o74SH32%#Ip{E{0zxA!TMrTe((-v?H1hQcDD zr_uKtZ$e|Vu}-fvX9sSWUuTQr+W{YnwgnIgNb-85AdWc*lq|T&Pb=JFawA>;VA8`h zuDGk+dAvh3`_nT-P&9gRE=UL}0jML%Ym@84ki|tqd@BSx+v`WK*vs&wW5ed$75TT; z;k?of^~MP|x`rkPVzZp+pKw zg9^ok0=N;nL+*bU3jZz^o~i&m&hj;#@WFFAMI*`}2(6o^nB`JR~;18X0W1Or4%CtS@Ub*>H5W612w`UPcLRSL> zp$_Qvh_tW|sD7w>9Z~>-#3b;LUfsWs-Lun;5`)ruAza(J5PrG!m9R+c_nW;70G|~3 zKQ^NO(SeSI&|3bJ^fx>%Y=!NGy)gAgJ}j(~U;ZLU?_F>MN zgs3i(!Lg8U4g`i}SkVCxcLwR2357V8I6PLwbqVL$h_t2EIKGA*`|$Cflbn|Qjp#p4 zb?}@GcC#~pm?xF2^RmAHmPjg|bl+#s`HUZt22-T7&!=L_M~;Vh&1YYH)-zG03E)%Q zNnn#6(71z@YYr)ZK~4rFHqTm%&)4$|b_^0?h*lvU3C7B+1B7f5&JJ;{5SO|iu#Llg_wNm z5agV+GEe=`DHrXOflA*;<6+bdC+Fhn%8REA*4?J*Y^;+0i2Q8L#?6Uv@sQ3EaDIf$c5&Yzx{7EAKgS-7DZ#w>wT1 zfS**?TSJOhWvfk>Lv86o*eB#~V{VxQHnP_cc;}_?O^6>q`_Lq+Uk5X$0($-u*8bCL zaQqnik%6wTz={wVC0gkCsyy>VN{jRO{>(2vdV%XEstiE>67r6_kUM?y=*}mPxUQ6d z=)=)-phPCZ1(5$dFgPO+pS*q8Uw(d{xv)t%lMS|N5s-#GV+{Ude1%Cs+F>jCBHeF? zr47}c>$dq23EpEQpk*xm=idyy#n-U*hXBx?#t5pql%9xA#?!D=9V7TEH5PZIH1f}! zUx!sdt>zTv0j&sZWW-@g0*;W^jRTzL3Uo^=^6)JO=e^cnj{okzHq!AVB>+~azrv}J zX`dRNFO^CX0AKk`3%modW{TSUdKn7 zG1WN9=|8^Do>C_v7HsV{Tz}p8`o9R%vwsd}d>3o~Mwq!xv_C}A(YT&qQ)91_gAg~~ zeSCjPt%tv4-B~vhS5b|?Z;`*-X$#tFaoyYy`}f*mYJ&hk+f(6MObeZb05&}IS&FtG zYbXKU$r1dgxEUTyZG`SJZoLHm$!l*BT_Ml%h0ou!UETdCGCQ?j5IWnyUESHxy!ao7 z&XrrNBf?2v`5Nl9E5J#l=8Ad-MF3~$E^E~!b8L;+5ag$4@^m7r&NLdVL_~jJxPA~1 zpm#vD>aId0z%PUI-sfdbIyYbKmVUcWGurc6M{zLjGARO}zpqX@PK`}_#UbDPOylTC z!~g15(L>gUrjJ|fi~d)B=BdLInr=u0Xw0DmpvIOY0I7EmZ$9sXNG8$_-B?U|vT%nz z+#}Y*ZIWH&V%wSb7)-w^r}RKt8i;ke1a@hYlfJu6zg0^l{Smk)34m*ATt$PgPE7c+ zi=J<9rV{EG7DIg*mT!>(Qv%?EKhI)@KaKzDyLcbr<6pjy-twNV_Mt=)n&Qd?>yySH z0!tfxcw+oLaIkKA?v(&Q&=71EXwc{3l%2-dY4g;2Ok~EptX&A_&f9O0NfOTxb4n01 zBD4F@R^|*1>$rxc{zelh_cE2FRN5Eq4DKn~Rc(d${NDiQ=_X zJWdNMojdb>QUt)WDrRHSW+zAh{Mxe~8uq#ge@p_@g$Rh^LS7)^AA2tjTe1H81!Oug z>(+u*c1#jf#UPLbHqmcdeT9{_w=8L&{rbZHRRnDR(@&hbiHqT}gvvJM;&p2~kIWNH^P%am=5z zfZR)Xp{i2-qAP1mW2uX)^%xRxTD?RJa{m&9`=w^sLzuZYvmfdeI-ev!N?js&Keb_B zyo(ZK(Qp%;e|I1F3?bGdb#||KnSR61Ur!oE{&5ba(LAqyQh=}cKMNq2C62QWY2u$= zk5t>Zk3=!g9T3L{*S^ae#CeGT@O0WvfBBfNPLcrVZ_q)zW9|DJ?Qxq7No{;1?UYzD zBMPY}#3*rjNmJSRgAG9T5)%NGF#ane&N2Q!R-FI}A~X;4maIaP{Hs`N4odece*>)2 z2#t@YLg$ABHvx!G6R4$pd5eH@026vJauSoQ%ggp|0DBklp{ZS`@fCja-i>hm!zUsYnd>FPc__{myt&F z$ra+|Bh)4jf?RS31dVrMoI_DC(Z3o;sVB>@gG-%+MH|cd{dZfT@hM??LB{O@by&WM zpFV&*2K5=`15bO#c7hlR3_Q``I{DWi?7xEzz#iQFJ@m-iA>YJt%UD7LHi{5~ddgwu zNeg}b{nar2qnU7VYbm_mxE`($|6dnCEks5k0fb2g|1k<=HD3?!U-&fq@XGt)!O})3 zzScvaN532V$NxgQSLLt=bjPf}&q`vBwi=g!&3`l0FMk~>Z6$QC{t9#*x_^ntNJyS< z=Q(d$1Olp)psLQNr_e8YZqO2?QQpi$5pPL-g2%GW3*o!sJoauj&J~$94rB4RC7mCp z3fYqb{5>y7Wg~288p+fs_f3o=q>~x#zLJ{D-kU7xRQBuizup_oFnD#80`O^#J7S9F z(;q$Gt4aVw7=}V6Y-=ySfUDAU$k!^NgW(o&MYDNh&)KNd8RuKe7xQcMhknCdxQJXU zPsrb?u)4nxR_Y5;{4aOsHvWR00c&>;q3;g7U!5Q?S}aH3|3fR~@qhKyH^zCy5`ybA zroJ)MMf}mFRQO|Y{*0se9^skqrT^vRVh}6+@ll6FVkEjirsY14j~=`u%29c*){Hq~ zXyC^m*#qMOP#3Mpi4b)7!AvT^IqF(L>_59V6=spJO?S)DI5Z0l?fpm396mh2f!~(< zZ=njRmm6Vsx)%0kYhh}-5XvPZ6OQ)Y0Y3dw-{QD*YPe-ez_*0as6WfsLJu`)C__Z+ zCM{faUO$JT#5hTh4-xu+_4rJU;r{)1K$7y7Tv?olEdZ8FapL(%ddx-R<_ep5nG^w# z8e;>FAE(CJNRI(kFlvW|u3~m*G1-kil=OqM#V%wW4oaQL&95GjpgwV49JPO6lu}T-ocY+S))wDv?noN?Q{n))L`b^Q%~I8>b)cO_wdX zw@LMd>&0&nO|Vzo28leNPAsE+#O@df8h77MTW6zd;-wkp2?f5|Swu3l5N7cZ$@uio>2-H;tsr#=nD_T?deJ=v57U?8h0AF$aPp%-kD~?Ab${Ng{>QZR!vM0=McUE0L zo5)`ST8%uP6Y{5;5nt#EXj))x$UHZ6ksywZWlk#1KFlx}-z3fx_W?yB!WXosjl)>{ zor=dJRU^INr2V7_fRnzJ&ZS1Wmk2<E$0*O*?el7I&mqK^tK3(t-G3#!YBgK%d_SmZud%(5T+{`Sy zXEA_ZBJJ-R-D_brED$twDFXO$b(Pby38)g-Zxa;cqnUR26X4a_R6guoo(c6Oh&EG_ zI)?p$ZpKxCXT8U7Dso3}+MB-<+L!(|>VQX~HGMZUHvWVd31k4o17PYVRuLm`rRvtB zM1dvQT*ILDF9D7uTk7O5hUWaQhtBd>BH_`!_Uiz0R3Xl1gZ7NOq`t*1tatUx^fm46 zJjVIqqtM;_kbD4*Fvqz9>6j7!MCnB9G1mCF|6Q-GhBw={!o}`lxJnYP%sM2&RKd}3 zMPiU#f8o9gAtFKUE!INuW-m-#z?b|Igcf-0RXOT`IESi$bj1JdJz(?wH$roLK6IyU zh4zJSh2HgVFlOLIjiR3`^<>!iV%Wn@1f^D(#a(+?DL`yB$jq#OZSr173rMs2rh|f^ zL&SY7+C#)Y{3J|o8*xvSCRS2o(ms7C{dVsr0RSnVN+towxc&_BXa1AJ4T0UsuR zGq}t63SR*IYwU&5ACkK&G5^~*A7Z$;@i z0m7;|ymu;ujsdJkDa$Kj{b;Px5yPRnF0NUOb=!3$0Q<(xz}>Hi=-<33N{yU5&x!lD zs!nCR{EB^k0{4v26Bj4ynlj#_d<0rw1i zfi;tNGBU2Ng?;K5jmqCYa6woIgRUDt90>ZZlUevq$_tEdb}+ zQG{!MOmNLbsTss_3=%{7WdezI+N%)D7?Bb3+qe)CEFJ3J+GXtEJj)P>v%Tr49x^!8 zS!*YBYC>UbBL{G66mVAtf0@bi75D$y2^H}lb}5}biFQ?*Ab(<@^hog>GyEL}&^qhL zeD>Qzonbx5JQB>8B?5u(OnKTGIrYUp$AdIHGO@gO^O6@Se*%%yUY;;j>-VeN+2o`+63{N3VMtET4^VA$gr40)uIrB7qfx>VO!``81jpG?@*dW6d;@f>>B z0sAu$st}PeHF^x1aKc1<4*i$K0MK~cEuyNSYjLEy7HFmI@HICNaGwoMAMp5i2lW5; z*cXkhOo9M7t#Zd3ldsik5&*BIhvE%U^e^p{wRO~1s{&Ablj;BaKb^kz0`3K%io)1> z7@`=^MO9`Fy5LC((hFGkbEr~WM&K{)A_}-jR`A!ICFI&%PoBTTO3KE0+@tMWRR6E* z-ySono+ogLT)zm&Ku+g{_y+A`jpdv$y5mhRBB?;Cgu!B`yMnJgkhq4wJe~o0iA$0g zIlm4C7!p{Nb`|1NcT@tkbegE8N{IPqLH2s77{WS=`;~c5Slpjg=P7>~X)BHwLa68x zNRCEQ{Sq1g>V;*5ifE?6Rwp6^#=u1Yy8qHVdCE&qJuNW^U&n0dh6aQ=_H1F7ZfLaO z7?Ct|rsz+qrM_E2z!Im&xF==y>cReIp!5(A#rz5B$>bXyyV5^aIP2Df<&^FmZGZ6X zr~<&Su3Lv8WA5}c;FRHUOU9j}ePPT`L7dQVyTzrDRo_k-vYh_N9o`0)cZmGc%TIqQ z-8H8DqzHiiMx^8ZeWG~sh(RO(UQg|bXkW|!m;#s;?5sH$f^^Rydy#&F#a<<6cohji zBf4^=Dh%?5=WvhJldB<3aIcPQ+13L%E`k{$>MmW(h52uC9n*j>bOCpDwn4`0#17le zhqv~whc9(*V??sdB)S|qyUe$HJiU~GdK0}gN%guG{(bmySO@5TJZ2}8TFQfKwuKF!Sx6h*_qDvy@#+PFt zq;BJJsNVZ|X#VtPp@OZ$rM2a73K(w+@(>|a4ew1lK+77}1I{@?kaBuK-*4J;1d zUFd{Ay*LxrfTYGkX#Fun=v*UIZsEF%dtz}BO)_ehypk5W>bVuLSjQL%jxWS>2h~nA z>IA$-dl11a!&qE^IHEgs6)ny~CW#@=0yg<%S4`@siNmme_e$9NsjkjfLibBISwGAp zrASeQc9su~uV<+$!D$E^4+FN}DPn%rXS+YjXM7>su^A`M1DYKY00}4hh13ygpU(NF zv6e{@09NvN<nXqP4otMqB_I9=lt%b zOQeJas8YxnDs>D+g#nY+#jhj)_5rg)OX3Eji$%JY-7CHMuo9#Gk3Z^PHula$xIKVA zQQi^v8c~+$VEX=Rtm$|qWORO$<@7Hlc3ug^0{T^n6awJ19{_Nh%&RJLj7=0JZS6}S zmoZ$^g8;f4kw5E>K5i4BrCB8~Rg>p&uI$YMurIPy<@~iXQ0MQudfsh!%{UHHFL_Kg z>(p<9YVP(zd9xIjcW1*=7p;G{5-I@mOim>DaT~4(fpz~=8q_5CPn950n@CnRi;xse z<^dtRu>}kT5Pw9lB3%K|2;Um6X3x0Wie~^ZBLYx~#QI@R(=jNmNLtlJnVT5TocH?7 zIEwFy-v<`&6X|phU@D0w8^~zajnSJm35KfB)}eyVH9kU2tzAoNQwj3h?_c4sjeU zIko15n)CSOC@h4i0zf>L$GV)LB^|hyB7j z>ZU7AUH{1I9)r4`J*mr+RRswG?qi&H!g=lzTxJuC|4j@s_ht!vBj+jdPl)izhhL0e zk)TAxDnX!#+<+^fz^)eSowwlz)!);~10PdYTL+}(a_QtR<2m>mbMQLw8c7GLge*cE zZH`g~-uWUF2@pBRDcRe7#LC3bAU**KqA*2-xfRyXa%T?TkTUFm!vE0~0QL`_-ADm2 zFvJ_AQGr98#{;1}2h5u1&8Q$M1YgRnk$rHB{w18Z#+HebPHQ&pC)t0j8PyO1(C$6~ zZMGo%aKFP~BD63H?V+-Wc2Wmw#(W3Dk2dA2NG%`)@}+7<5K#A#B^a(-i~9(JMf9jQ z4btG|yo}p7Iv2tPO#jUMr)YOvMPP5*-zwWW5%oS@u7r25-wNw!>EwpFg zg5^9Nh!;wS+1CRCSLal;N~3RXe+|JS>#Ff4`s%N6T&2edY>WY0o&ZOo46#gPL*Y@c zfT3gYHQ@AtfA*590OlrZ>4j>qZB&eG5E%%Q?%Y>!EyMQ@|G(v(+3*#D{w$H&bs0j@ zxc_Q+voic#aZczB@(@|jW28Vk^ALhJzY1{#e5qhBfmEoQW5zW9GVJ~2BQi4XgxR<0 zPq=F{0~(F-T$o*&*n_+8A_Y;J(|AbWouAC&)q!NOycjww-^O4OFAC;vFD6gmkhJT$ zd!OJuK~9CK{jm7PPeNg;MqC4`Pg?QL>n5$85#K#hg-(CS zs@6eERT#%TqW3i-?ocM+m802n`dhrp{aXLyOWTc77214MD&jthM1ZBg13XT@(>~rb z?mw>dahKBod_aT0Dtx?QNe6ON2m4F~q#YOc@x;;fL63MW`EnY}AyRRid*O?SL?v8_ zJ}3|+tA{-Rd2YL~yS>)Oi0y0y-55Ex)4KYFZ|UF_bP6z2Bm#_yU;>&JL_oU++{H+3 z3C?Q~^l##yV|up1zj4By_B7#LV)VZ~g8yvIl)|G+7b5`>mW^G0Aig}|*%#_mvP2X3 zT4xJHK)3!ntPUDDxYSN<3)R3rQ;Yc*MY7B-hGa!Xk%Y-rGTW0Z$Y0#ux=Ng!_t-M><}8+wbOcx7sq=Q2m!{FI(FZJNSb48 zofF1Vus(G}Y7da2?XH3Bx6$&vi@T@<1mI@n0Pb+x(8WjN<9s9%%X~BDa!4I<4xKS% zr40cblgF`dJs|-YydR>}@_+~spUKo6D|Uc5Fm-_YbbRdA_|t2jdC5sP4tj191i;h2 z-QT!0@=`xftwYumXKU}-o_<idty?aLw&~mi8L_m zqjb#oGaHh@P&^lrKG!{uEkqBi|1OMOX}cKaNF*}1k26=Bq%P=nk21Ptvt}ICwTkL` zl>*cu00=mj1^t zJ|^>#y9XY$5$nhN@^DPVbb)hW4WX;-G_Z#tl3N)UqKo(8>eyCV^WnzsDh6J&k^eWk z+vwWe&$f)3M8E$}@bi99=!A9RGjuQAhAW0BTNJoUiM?#)VEO5~==>q1aWuqIhaP>y zxGpdj4%t2fQysSR;Mo_s$zm@g8lkxt3e7r3qBG$Nb^wbsR^R`#%nuQPu74ZkfcynM zA)gWu>H*p7+KaeF&a)^rj5Hns28X@&*Fx*&e}*`HE!3Mo47vAz8VcpTP`-$g%6trp z)BP_IIjL@CXbp>OM#wH%Mmrb2ihTmoiaG2)ZhwGLn}-i4`!>=FyM%&HUj=+A3dcANF@BKqA0!nL?=k{dc@KXgaZagY|^XdiS%8u%H z!chdYoR4yEsK>^B$Tu2c8mZYb0isj^RM<2C9Ia%Ko8+~i|0?MJak$6vMwt{*goBRm zpmNd&-UvMn>MlXi);FLbL$XjNFcMevmq= z0?_CRjsmZD5TynvkTWoAiuD90vAn3wOZBsoz!r^?tg|pWawfp(UI!i9CdOvCrgf3A zw{fK+L=7AZk{dXU?h?|ECi@x^0Pe}LP1kV!Bj*1y0f4fQzw&kC>;!vR{=Z9>w`N!) z)7xV_0CoXdU39*|O^zi&wrmt$zQ0c(_i^^$bLff~z@QUy?G{0Q+M%-F2`g;#Sh!aR z=W1?<(Ps&s5pgycW{A+jfa{G?k#Nu$ilGkbreHQAG3SKP&G})vVwP~XaTUY+TOfcL zlHZ_8dW4ri6|-a*@8S}uhI_m(kAYx(b{yTutCTL77Fn0R9N*1#)>%KyU8QX?$%BZ= zZ(463U=tVF25d!QVkeDnF<|WMe-zrAuv6k{0v&187|X%#sa5uRf&+F9bY@{57>12g z&KT3pD&OOq_LsINFG#V<8S)3_j;d~rZKtmx#G)5~FMYDV#C?oTJnO8n^xx5coLwFB z-w7h$r`EK;QKGTq)X!5N9QHy)G$I>1J~0TxzT>&wf3OI{GTF{%Sd6v(u>T(X3t?Q< zg;%bo`SRRq`1B8_1<&5N{SoOi(q`?8K}g{EoA=os@|(Qujo#N8BNDk3&0VsW$PsfAoNGYrCPm*9unv!fzAeb+J>%JDnK!V}qJDNno#@mk_e}dH-T+ zGyI_PX}G^o3=bA>ht?8qbo1y>KMw@J(?{^-x+3R_1-l~b((ZP+^Jp(zy}KW-?zF=j z5Sa@xL6mVKNAnSJI`1`M1u(}P#ZKqYNK!r~MeUs;5i-b2CwY(R zV~8H=Eqjg`NyN%FBZ0PozfOA&{RR&Dq3>C7pPxwOvv;H`6WTNC=UVz3=&{t#fdXoR z^%#28CRmq2Uv2LwVpam60ZC&9>vtv-NVIf;21z=-48^{8lpzEMtPORhUjq$%lgu7fD&SMbkaSIl%@eh=yF5vUCup1j9L#fxG1gW>Nx%t4P?V_zB5<`ahFCd;FZ|U(`ZfT`>X|e3*Mha=W9=%=L5$1QEd%#}J+_D(T4cZklu2 z(Q|X597H^ea~xQlU4x1yMXw}ukK{9L!W;L9F4x&7I1?c@+eA<6p~vr30FVWMO$B5> z1&3Y1I7t8`S0xbu@Gj8iToVotVnDsFKL2wN0OLsO$_EaMYgTb@lYb2?|7+M^?9I%C z>TEeQrm0g3{1Xl34j+4U@LYRc@#e5vd}5&sX5OO?e9o+^b!~5bq{Zc47vQt+2I6C}wo- z`7+xq6*n!TYnoS{S+K=>qI$vip}s22wL%HiLl*6d46XbcS+(Bh@@}R+TZOwB_eegi z?gtY%y5`|yY{odH5zS3i6B&oEt6rxL*d!@Sa|5>`!lNSRBtQ$|{n9LeXBwnWkfU1~ z(xKj%`v!d{A`^zmPX#qD-j*}NVub#Flclw$n9vsiW? zZ>D;G0sUi4y>>9#dc3j})=90qxil487p}v}0q`XPoKG(dpgP`)FW7JO|5aQ@c0i`P z)o`&<3U_)JQ5A(4AnI(Xe}vGPG3ev4O&$mmLgDk@xp)hMIpzX+JEGY9#JS)cVII$e z{MBzuq%2}cY8FZIGW5EeVfWz=@g}W?>E^>QQ@96mtb?pUkYs9%9s*|^N&^o`pqCf( zVfszNAYZ`FhM;1t`+vr|ya$)hnlzx59s!E~WjJh$$1|)?`nF51jaK zkAKPn-=Lm=r>pcXNPUoEU5ZPztAq-HXoH1!ejf6hr~ziNkI?%-iGyp)zB;i#2l>j` z?-9glIIazV9sn80%g$1g1-lsV8kvK6@l8$y_JldNM1W0#rjQid}GBQ zrFv@})D;i_81L2Z12pPdM}y#ReHn!;m7PJQH^bjiDlrfBfCONT>Od>q%z=+ zau5KO^}Au} zsqSCG>{WSjdO#b1{T*yXBmnlq3WlOLx~mWXd1PkutPL4~(dUSBLcjkk6?B)B3Kz&_ ze;EQmZxH5lWY?e49nR%h=DsPu6$fk6bNNf?;Yl65@o8xPIeziYZQg-uZ{{J~Hk>*f za$y#t{;aGKpH6tRK%%GV+eqIopnKog4}0(Y7)!=auv2&~gx9{Ear<_Wb^)$K+hmTD7zX!Z+`-$(({cj5z2`6H8Jf}sLSy^ULKe*1%vyMI6A z=7{=w`&*nuP2!89dX4Wt$0CN+4j>W&ldFe-ght27Y44wV87CxrRs+)Yv`>w7b-pU6 z_5fWLi2(qPx=vEjcIsHmb1qt_f+r&>m3lVqPkrZr7yD?<$n}HlqofYkybj4_4A7&I zQ3nx!a+y)0*9EWlh``pHCX!)60svrwjz5&yDjb*KI$}y$pqvXnS|T5t3I=n*syk1# zx@o>KM-1~hR1H&PchvCDe}J9=8#35!HaEupXI<_?0JJbn>=NF!r-70oOuxvbZ!X9g z9u>wZ={KW~*uj-Su)@(xjveu_^iKCGV`W?t@znqTKmbWZK~#LyE%l%Gx8h@>{)K%c zV)c5=n_|FKt(@UzLRkO%^#x zWg-WPXu7EQ$d=b-O{=?CM{aWu%NeJ6lWb}zEiB$h zi1Xz%ex4)OL8w5;luWmb+D@V#pwq=D*(UYKA2E;@gG*f8&MWiSMOdFusxhPx0UC1J z=qLf;#`Jy8eol+MandM1YqY)I|J=yk!!SI*@-P0yzhL!FQUzci`3bkN^cU}W4#i+0 zS{1+bYhWh?)az4Whjga}xQOyC7FGebpE2V^00e!<|Mpfl?7vSclx;=- z3t_+db!>OwiXrK{t8Yf}epswK`H{4dsA$@fJj^fC&B7ii+Khu z{fOQ7iIDsjhJDcxRH8#pUs1Zp8i#sZ2XVaj|Az4B{P3-5+UH0OOROh$TB@%ijBtj%s;(Y(u3M0s5o4?XF z)_Rn{fjzddzI2$E9gOfWkBseJd(<)ngvcKF;{BzIT#RHLQv%T4S_-Wl(rWGyw;Lc~ zTF*%1q#hk-2MPEOXs8&e4_$w2gXBcQI_9dU}@E z3|=HM_(shB#NNr)s`74*B>?=E-;rZ%aNOY9=A#g{9%2Lt=ij)El!$l{D2Vj`AC&;G z@&1zts6qx90T54mQbA(`XDVoIRg?;)c|1r1o$E3BAAMAzoy)8ri2Cl@GNN^CV_HST z|9ll!-zWv(wkO75kZ+uH53kdRjY2TppfQ8$ULG;V3^H3T&9 z6-I%cis_*V4AjMfzY7u3MSYQDi=l!~8}Kw2*yjp_X0V}0w7h|PR!_J|$7iLj8EFmUc!VM`4{&Us_#^xRV zk=xS%PzgX4{p4DSFu-(obqc+yqF&o2XFFi^4`2MU93-G?zsuD}Q9FY#qK(LybGAK>oOc=GafQ2v=LjR=trY{BIuIT8hYDLUEMhd^k)5 zrT%}qK-9mvur*6kommW7of9H|iQ8c(MIsm^>Z9*FM5d~M@^$Kk(wp+W z%}n<=QihVKl>v6Kufo0w`YZGxK!8>hKnail0a^&qllE!%Mf*U#>^>~DT7n!=+>t1f zGbG3Mw5#g!F00aKWMr7Tzu&oWvLd50vof+GtE;Q)RNcHct~vgk&wpP;RNMp{JB~Q_ z`544Ln>Y(GLOm<1q0@vbrlK5kqCBaef5wQ{qNhX4Oh>ASzfB+jat$a9{~$YXGeNDk zZc(94_BF&g?jOz(kx4TgXA*f$2u2(WDi!PLIVUS}>3cT7XonxoQr-OZ7V-X`z?c0RTk*vN(QL>rufx!I+uaPNvm%PQ4!{WWu0Lp9$ZxqoH^ZZ_R&Iw+FHDEe&wLP`PS?Wb z6|~}~m=CVUG|xvJY}bZJQOpCt%bM<8`m6NC<NN z!#t13WjSmtL@?zTIp0n0T~P;Y@j^? z<2*~^Em^PjNfI6IJW1tW>GYgC5 z4HW7|H%dyc3zSgm3TR3f*ScY*HHY8-Y0SE+X#cY-9;;#dSH$M#j$YcKsp(&>8$OxK zKmedmrf~Jz=x;=h!Km%ozsT3;u8ogWzwCStf%EF491w3og+Klxgbk=}UA8{_jBCul zCJD52?mqJjqyXngMZDM*nRC5ukfj^EXsPPL4XwriRh;JdYlnW zYgz!LiR|JBDAi#mh@XM(=AVRi8>iUxZDfnTR6zrkqrL?=3MI@8UEkd%)OX<~cow=l znC+)pAj)}f@R2<}n2`vn#p*Q49yLh})b0Q-wB`0Qf|i@}dmCdWEc5jk1vjaVr; zdpKbN8?Xpy}FGv z!QFu3ljVz-cC@@vOv2+|ry<0V&CBKx+c?fLzofjG2DCr z2EaJmX4B1>vy87mCh89`sR~He3q{H)QC=Oy0I+M!=Q13vB4rk#_RD;x$(ii%QXMln zyxUm@HK*>(6=<{u8~Aju7N(*6lWFMaz(1b{XxW4$f zj6g%gW*l=q=D}uE*pLiS&UWRo| zEYP-z)bE$PFTx`70&vcVhUnt#RoH*B1*Xy(l0N!z6R(Vnk>Un90g;2jr>VJSZ5Hud zVGa=>sDuZnLKzJlxk8BkqAy;fD~bg8?g3TGb9uqvgv>ba&0D__?llH*isDMzq`1mN z8w((P>NQy8v5QR~MtvB5c;1^18`ZQ@2fr|b{q7IGGt%`*AOKeIxt1PKD~FY>{bUkb z67wcMl&AY^3F-u>Is0p#tTse65Jz?WhkhYQve9(cLE_ zqbI-i);V(z-?jeg^f2RT7_y0Y9G@&C}HKo#Wr)S15mDknBfMu2yzrR zc3_tXr%s`YjTP_;Y}^5%9b&(CTdCo}5h z>PpzYHIMS^Dt7jS0sD|XQtUyKqN&}>mg_X=d+zKa_wP2RLT3xThB`V31r>Sw2+qDp z0F{X10FVW_AXmT3{6QIzSOeQ|5IURZ89wCrpZtW^Kn5mII6SXnBjd)hjZTgjKT{%3 ziXe2=3o_bKC`8e-z5FR-i&@|V{VW0=4UN!T~aL^a2;rjtMbMya4P z;eC9iGe#t zZ+HwN%08TF^A9D`YQ6&p7|MSFpg8p|4t!W7i3%EL$BLatlP@&?i9tTU^fbJ4>p{4% zT?=Q?4qhN|kefS8DgGPR04d>H2gp5Q>wgHqS)HV<7ii-Y8)5X~#wK)}jb~gH99KSW zAAJr>)TV!YD^mUiol4#L9Zb7EX3liN#CJC_@dB_q&Da~2LrWAIv?e;I;W|I(h*+9o zDvZ|7KaDzk-HnF;u}|2{>0J>?@C{u+OZ8RHa3;?Z$ZPKOhTrT&6=09~N_kmk0d~LB zD|US<#50E>q`P>N6Oa{A5IxPKvjZLEeZ2wCo z=7APHvQT<(8M;m6?oE^sTjwZ4?w;6|h3wOZ-WDM?*$?mhDw)7}#9X&^b27A6t`fQg zH^X;7CI$gqyg3RXe0c>VPzOK)!AO+Y4w__AWLdj}P6GQ?XM<>qe@Nh=<%b~P7emnF zVno87YZQL0bx4B+{!zpQcj5XUh4ATr1sOmLFnxh?&eH$1`!s8wIZ$Y@$JEc_Ze@-h zV19YeiXJC1;R|pO3vg}aR1GB&fMaJpl-IF-GULXU++L2_7~eHH!yqq)l7q~Vcl%MZ z9LggN8W^1ZwU3R(4QKmW{H9N$OpeNEOI%}@hAPh31iOUIg)IPqf>IXFbK)Yi3yd_ z0-wOai+~^M*ATFA<7T5yaVH`*V|50*hSgjIafo4`LD))@L~-149_Fvf4i*8>%U!fs z!7Qyra2WLm+7u}@)A`U2W&veK-S|Fg%*pQVka%0EG-p%{|u>5?_ z_d(cHX3TW-)nGeEq|obJVx9r?uu<-8!07?8?m0I=3Q7&w>wIc-K%E}NaJh_i5s_sP z6UAbA6@3Eghr_cTm}7JhWS>W!5)@C(O7~YN9gVdxhojv*OM0fPT7#oVT+8RUo@p=S6BHe^rxxD!X6Sy2^K-{U|El zl`8i`W8&w)vt=lqP3Fo&;2Ugz6HjcQ zACg@l02Gv-HsT@z?toH)2Fh{z#yrVCUV{*Lc95etyy0>fu$+Ox1sinr4lLTA7Q^%w z%Aw11;aqnC5z$mc0$wyz9D9?x9}nUD;0_1vgRStNDnAK7EPo!B07gsG@8W^`udqb} zAU))|*)SXGG0tSZ_A@|7Q9$pVUk`!ZK-}@0UI&Rtap^Ci^ z0m#6$olOAuh3~@EI}fFOfjKYB=ZN#&K9CqNX(e;%L#XJ>jPpixR#s@QhMk?KVdwfs zL}_H6RW?HH>;oJJfouYEYiB{=Kx!ldooA&QqXywJaqe?qJ)DUWN`|d(v#%k3G(@-^f=T%Tmcy=gAaU;B=yG(LycfX^vUv7;*`)o7eNLV zsAPW~92JyAoB_40(n=_`9qJ7`m--pVt(apoTGmCm3hxetrDJ#0@+z_Z4q027UB~ExDd`~a{&K5=uf_>_sc&hkCE=@ z4UqM_hQir{!U~jMF)X9})l=C^cCVYh?f_&8oCG|5^GTZ5772UPh}GA|7rY0OhLU>K^6CGv-{+e-^zVIY@q+~82-;H zvj0zu_rp)iH?a9HhBlh$9isk4BrwXwSwu$#jt7=`zymuZYTh&7jGM7=nKOD5AO;<{ z9Kq;&=vg?NFPr4hs5^nlJxn2xv>7ZAdXzV*%pHPacTkQ{QtA&0kywBBBK$dYL_BrW zwDur$Zc@-H96X$Ah3*mtArNFBno<12aEc6+=EoWC{3zsCg&$E`wYVEW$1OBXy#^iah91vru4l`rMt z51)Oo|CQ@W9hN>p5wGK>GipZrXaD-#wNbLhu!oLb_)4(hN`wriYxxVar_I~}yT>ul*e#r|rf3?01{o4s!u&39cK-X~m)2uZ-(g&_n!oiJ)O+AoX^rCJ^&->@7AUNjUi)?GANfG2w zz+Y`nglTO5>o_5L=KAL#@SiV!coEU!Be(k42~Vo4;bHX&J|MQj%ETJZpPI1#SwC1i zMCAp%^F@mZv1#YN^L}?RjdkSmycIPxKmwST877h4CeC+2PKwZqJf+;S))aUuF zga4*|kEx-T!S0%f1!q_`ncg~8_E4!Wn%o_n&4EwskMynAiZEc|hZdX$eT9e&qEymF z%w*h(-XX*~lL>{nXEVI$`7*<=9+YZdWgZd*PU|_^iOSh(t?hV!+ z&PogbwDSZEA4P5PIIIt_P!fo!)Mrq-szIm{eqK>%{^e@>V2 zBqyR_f4A6VHnIJ`KUWJk=1+%5Gu5zh1}}$hhMEVtsU36vji;s~xe46qB{Nwzvi;plzMyS>JUS$a@3-7g1 zaK$U-xs3&E|IdZ_9Yg?~8B77o%#@@h@_ZwlWp3lTdVYw$|2(mnEEuBZwH}A9Cw~m?i-O!db3$b_J4ZbLf%Hkt3!%D7cncR%$|I8ICJ5;# z*RZdL62-cp@y|_^G&qV<|)iA_O~+ zKzxWK+S9UxI42pFD5&Z)uR#K0{Bic2$a(0O_rgx#Jqb!?2imQ ze-A!;>FW_&^wQ;}3~ZE#&|?n*5Iab@35yKeYwtj(ua9sxpE5u{A^@B#Zz=-dl!~l3 zx>E$;JP5$tB?y%|8o56rZU82AGq^_8GZ!1ikrGof1??ze-&+I$D1njpc3?@iu8^#8?~5^~jr zPMG`~>!EfUiU$!I`!_(I4>Tu;9|#`^z)!;$VWqqg{`kyC;m_XxG;CvzSp7z>kzR$1viZs5(E7n2 z!|cM>#)WSa{O232HGoKDcQgNA2zZXsd;yi-0T+iq_2`as>?0Do%4|vf%L63nZ5rH|{ z0+OGxzT3-pa5Vu-pSjt*^~1>RD{O(RE}CWjG)LH8BLDN~FIvJ-tn$W3s6kh5hP zg$rXhNk}?1G%1w3qPT-%3JpwMt8&74jHzPvEWRU&aGEWxg>8bKH8=1Gu>m3mViF0` zSoR40&K!xlY`gW{^R2MYTDfXHUU{;oUv(O6sO9fL02mT(fi1;;>UY-Q7e}mZKNoZA zA9>D4{QRr=n#yVdEq2Q2+7tWUUKfpaG=6)s;#faH#~doNc-iFG$^k&TtB4Q!Du_mzx=w{?)mUY=1rct z=QL!5&Ms7_12F=6SUxD$i(zy}n41}aoTBuODWc|ouY|WoJbMyGlyU%yyU6_B{yTPy z5=LoT*mI&d*KyFjFZ)RRT|r!l*iFQwh`vQu^S(daUzpD-{>6~t)X#i0+tYW2brlJ- zk3^WF2BFa0vP8_>ybegdH8k(R_T9e1`dbghkAH|501s=^P&gOh27p~h>57UH{NIzj z)$b|+MdST4>@gw$7KjDDeglylGO-5iP{j=*0SC!}1Jblk>3o=1}^YKcDXaqhF_}1+>UvZz~Eic2k)c2Wm7&MDWY0^|4Bg zDk2Yhq4fyoI7@{vyGn@Y?0i)G%l$*_-S`FkgvtWk3;5gNr-d8gJ|=!EwT*D&%DwRE zySGCN`S0?(tD$}c>JQJ4+M-8Y2)eX}a@fqT5R?bD`Bvfcuzd%LymBVD7e5a-KvPi{ z&&$mJeS3mD1#%+lM%MfQ|NOAfyQM!1+xM@B&J($Mr5O98N590YAn-n86F$C zrDv{DzDOYoiegUGJ&$(^5d8%Zok+FuhCx)>7ltC-ly_)W$i&-)v#JPzmbIx)~ewY4oc49IZn22 z9@6#jY({l-<6nanuV5@OH^yXj-&Y|%e*_U*VO?$1A1KmdeE+~6x0m?rP*-H%Dm(eYe$+3nEA9isU21lb=Cq9I3e;QFo zL^Z3yjCrr=`9{ISJe+mN|v$6z2y$p;aJxZaP#Zj3c#9-`Rhzdl3%@ zH4ZEae^xTec|7;$wT{8mC3t!_gh$sy_|xCcYk2Xyd=GLoN&PQ;lYwUbo9{GhSVAcF zq3szM8z+Q=t8=gDaTLf<`~;l{05f_e>QQS3tCd6*i-pOFdYA;MsAG~?>;rHMR}?T( zq6)blz@D#K!anXK1i z-C!nSPB{bLC;79ZWS+mxe2Wf%&@yF%&vCEx7)FN_UTMS>=_CtV*z$MXX#L= zK0=Ik*5Cs|HOfZJh#VL{;Zr}49dGyaJ6aa8@-ZKF*+`2xjw$SbXn+xCu$rU1S?pMc zL@@(D9wE7y49?L+5eR?rlTcgp=r7FmH2q7l-1?OnA=`sqb>cab*w&%y&;ZA`{R&P> zw$wycd?HmBMF8U~^PsvM`+nMhqSr*&qHcaoqOi3e!15ZQ%Sz!@p;q|5Wl*xRYCVETj1Nu#9tG zw8$SdmcvqIC9F*kF1hGb-UwYf;$ct<9Q%o?dtm*iOAfN}3$$9AF^J7B=OY(s$ zpxCEp*@z$gw+r}(`!=uXp??$Azbj6p?15~q3;X`=-~GGZqQH0@nqU8+?~W~v8v#fa zJFJp}&w9W3#V=fTUvNYOz}_gZnDW3BVC38oQSx7&2D-3+=b)3+e+Bt&1+?DluSH7o zFR@`UW7yd}e7LusqCMPMhLCs=y1yj!CYxeuvIlz~%ony-qz?N|IR^VlipVg-C1hlw zycw!@e+O}g_rg>38}3bhkNty9QKcmjfw8kfk5k+IzF{2fGdHO< zsL}_Yvq_@K+@utBc{>%6yn7z>pRqv^4G!xWmGc?;8J_VU2)7pHAEhKc2phY3Fvh z^X`MNvbY{vILB&U!co>ckOeqADj^n2%VxLE^pi@nl|`sTsKeUwE!gL)5dO0$u^~{n z#kV!6O`X%oc6RPZnLQotrZtXaJ_1Q8T^u>}Hm`=A-gnTLZy*vtG_eNV1iRd^Ek-Mj zp+bR=(VaKv&KjYb@6EzJK`&^Eb^EO=P|qB?^tSGUplK+Z6aQ&D<9g%lycPlX+;#Km zV>tC%D9$3f1iov(Kl#1Kp?rFix<4jr;u4|Ce-2k9EIrh zYB!TF`moO;QaY@Z!=9z@M?Rkf0$@e^y}er>@1?_=Ufb}j(J6B z;$i&J*$eOF6Wk^?Sic4F+#83CoMoMC`)fmi|yk7mNu?I}zE7sFzAHp~z?kFA?g&Bs=^zKV79?Dx31 z68^05dHCIhKgF&e>hW7pl2<{V=$|5UTEv!+bqqBVJ|RW}b6@?J=zNFIs*?|JWsAsw z@s8N&cJF;SaNHyKS7+-cnX&^upaT#ZwcPlZ%MZ&-a`ae26 z(213kpb7w;fg=bmWJJixZ!Cw}Ww--uAI*C=F&$)Gq6$1<2{i445XvoJR7?AP9ZkSW2b~R90oXo9oAUvKg&LL5_W+AKt;t^0DIXq*ZZ)~ z0wOHz7vt}A443>el^M<}{yqr=AQf~_We4wP-7b#aL%6Z~kx!Y7Oz9jL@iV9X^S^`h zBYktwSoefg%4cbO?UCfteq6 z;5}I21z4T>=LQ|7&*kb;_Kb;2|Gjp>y;@_ONvB| zjJxoc&d>gG$J^k{uHJ&p-_@r2F$gXSe>GVC_+mF)Zn4g0shJq#*vF$^y7Vt41DYH? z*D0gjMj;jP(+qko9_ojx-!B4h!Xzx}gs>fergww5s1iI*mFYP5(#p8d|p%zL8f5m!N7o9Ij5agn7S0ju+u zjLa(mxP1#dmWyjKMQ;7*Tq-|Jy%;k3XzRt2o8N(_jS`@(+p zGv7lJQ#X#sUNgYm55DNbzW7@I?%?(Ai(DLZfAF1ST{}ZhIyo)-GkCWlHYhe~V`D>* zb0<~8fryKR4lfV@CdZs$@40|R#K!akP(=h#1p_0%D;e(=Yay2OW~aF6&}La`I2KXk zHp9Puw@moX)+08A)v$5r(@?rc_+Z?@PP~H$KF<1cHz=5)J5BkRaL@IJZ}$>%(M}5x zx(3^AnFU5LqHc6Yj2J+9s4VozRy?449Y;4xj$&&&%q-mxwfncisWqy(c^UctT=f3u z20zYGQtrPE;7?*qLjuTe8pGx%o@P zoH+KW63hp$e)aR)xKV|rtzHLBiOqNon=(q*+T<>Zp>3=~h!F$9Js&Ri&VQaBmC*v+u{EF)37$V5$>GE`{5-591+Q|e1U$M1@O~1ac&=Vau(VkF7-afB?C1OVy1z?j1Dt2B;#lW$ju5*BWZg%=!xo1w&2fN8?5hX} z8A!!?r><}Ykw-&*=OL!6WlR@OVG%&|PfhA#;?k{7W%`{5$h7gU*WMs>_`>^8{?t!R ze3AAf`#%P7%L_W;zt+orM1;JCFNXSMxE(0}f#`O7x7mX*bJfWkBCb0AEV>|xt=rde z8-TBpE>=D33wS!@+d34#A%9~W0rE@)iV+x3zZ0_ez>;=g{TH9$sOSR4;e>2+Q<$Dc{ywfDYODNa0EtP-8=l3w;6vaO1;mJAOe;6O-H-R_b-mP~>{Ei8J$3g+nEK+Q zaDkZdXPc+P83O-E-z62meZD@{E!qD93=IFmQ&fJREY5}1_vZi<$OBJbf=j}tD3$QK zrbzuWZa4lcnogD{KY}~_-yn>ThfZS}_a5CoOW!ke5%>>`-Rs(<7u8GZwX@>Jjz>>i z*Ip)c?RR?D0RNb0F-vshq&3H%ginzp-VbY)&G7Nno8kVukE4=b`8+xh?_&DOuo~XD z7^!|rO?~sC3ivAhSv?1kJ%fLEh|cQMhoScP5r|1KG;h~J?<0V#PO{GY8UXq)BSt!% zTjN~#2J3-2g=Tr=Eaed4s9V@j&8V>ADFW_f+pM?ET4;U@P-z3;uV$fsH8+&q{fHvF z0RHApgd%AFw^1bQp8E^b=UdbVz!zELukl>BA$Gh3g$W-ay~z&&;$VSrcRFpjUBnA9 zM70QzrkmYu+PVB=O#0w>bQT~^P?+2VX0Sg+ai{^EM0(O1C;DW#3_`I8VgW+k-9W6l zbOT(i9cIsV!j;n<5P(8hoKuF+yY%TuDLDX0`!K)#*H8EQu+N|7oR0qEkxNV8jdZ3r zPBaa7S!!fD_x{O0`6spC_>JFqyr&jvp~Sx8j}yUr@hkqM=X*XH`k@7YA^>j3gX@w9 zzeTIe>T8qi$295Du#apsCuemFb{CsUag#m)2%=2WgKE%eP-h#K8e#!EPX+(jiF^`u z1w0$f1Lq_~D3A1t>Cy6 zU^x?2GAb|=ye7kICWFO&cN{WF+@;8Z9>|=hFHFAfcLKyN2t7_6dOgC{c93P$Oq|xo zbDYAw8x`ui=3g-Kzb@H^A0rV6J3>!30* z0;;v0;MP#as-VBBj@Tdl$;-GqY>EK<=ly!NW3ZflW`noJcYV?b zz+g=W8FNW~VzX>Fl++xFW(;MD#V_bSR$MvV7 zvbq*N+?)#+n^(fcR-KTpvyt|f`lrOP_PaLWOVErThuZ*-Vt6!pEp*OYqCeOGw1>97 zuVd0IN)L2UJ%z11cuV}xZ2S)i7Pl4}XtS5+7$0$%QC!2mj_pi!VoTI-y$rt|cK^K_ z*slMu7#;CFdAboEU<&pKdBC0drEqs{DePbh_Vns<*qq-AZA4hDYt7I&&4x~Ys2v}X zBlq8fv`4z@S=8}HGr$wPWNLp$DeS3SQ5Zz`)7*)Cjj;Ahr|(h z7vRl$)AoH{#aV!`^Ud{`fZUfR)ek=hOi%UetF2 z(6Gm~S0=#8-^a|2Iy8O-@x(Xqb8$IelaWJrXo0WSL))&k1p|<^ABU#<%@_DIK^!^x zEdW1f8O4ovE0J5%ZK3%6@JBes`~u2;9!uG8h4$lH^fzn$!u$C+#J*=h^@AXnRIv>{ zKng{ilAU=N=I2+!ydi^YOhn+vkrU$?|3zI8_CH{k1V*k4u)C)%lOL?2U7#PqTfdCK z>mwI?oEP1lPa@fX;YOr;!)LJ|NXO?>o`JFxs@X#Z2S||1e3bQKH|zZ`V?mUV>C{mQ znFjcGIZ%HKh>O0SNr3Exm!gE_ow*1AFj@+1-(u(8LJy#Q6Ak0*p-faPEgFyrL;$Um*Sa$H|7Tm1 z;mQtXT?8DOL9#3GceKZwbPJUsCEmvW7vA8&W>Ab~Qv?}87a-JG{I4qlpuPk)%Q}N8 z5Ldn2{R~&NcR~e3tO5{Hn>`|D;xFUww($1Rr$II5n(IQ_dn<)<;i0-R!@cF&6-c3! zmNge}UyVgT5m|TlR_JWrWSLPR5difK;F5H%(nM zzvX^NxL9u-K6#X{QS=xb! zH1eU=0a3KTcXCC%cB0s~#tA^dvWkUN11C`pxSUn=N}@RWIgpkrH+*)ckROM^>u#qXq#CPr=?EE>#=0$TX+ z)&Q1g*;t6q#U|X{;JN*V`HeQX8LT!%r1{aAlc}Z0KAQ zCt{=8jIMllh-t90fD2GUA5exqJQ26cP?59_SYoOnKS?Ea=ILbykREsa=rxV=$ zM4|<#pA}F%?k&LmK&iQ^yQJfk-}Je}a|S z27A-%r+p8RS)gx=hy=@=%Wz1_AdqETEtlXN9Xc#~IwbFVySJd2l`rGJ*x!3{5#~|b zT}HH{=aEvnPUqqK>Gw;W$Bh8&SDC>E>~~#9OR@_qr0wY=T35F2 z2z&Zz;Ps(Pw)coIR9G2xu;Xcz3VTeXWd?&e5mgF@KKXk6bW$q&wlnlLcJ^JUOu}!r z7NF_@D%;;dGj=(G4`JyJ4YK3TM##KgIA9**z|p@eM@o8BXB8UTlR2 zm~(wRMH~Q>dma-3uscP&MN%R~uxEjeuL>`llT@R=(DC${U$pTfCq{; zyNcpqL_)z_ygNDsNYkKhm%XC=h^28Oly2W)|LKP6d5}NioTw8}Jq_#t5$m;> z8~Ds9um6I+Y7iwA{g5Y!XW#~8i{Hd8@_W2I34YW-KXNWiz%8yp%v8|@(2-nG_J72# zj@UJ^j?}^b9Q&jlVIKFv$Y4nC1!()h$bGUH&#hO109ez(MzNCP?{qHz(|`I;t;Zj8 z{7sHMsQ`vt0P~Z93uKC{o;@!d@*^Su6jhpPF|>INgJg+gkJO}P!*|I=^Z3b!w@vCCLGR}7OJx}_G_ zM%ei(`=Vb~Jh7b^Xe-mLFq5tZGp+FsTmk&{?>t6K@$@=WXel)BK)HT=1|?h8#;I$> zx@T<|@JIHx4z&dCFG>PKEmjQ1g)fiJ!{yNY3<`FgdBQ#!krKoJy%`h$|KhjF`NAp zO95hJ)R(Z_z=_l9kI+>@JflC9-qpVyl_!f63!zFtp(zN0Nsy=p#AXcypjv3b*%VeE zF}dMTSBd{!^S=mh_UtWxBFyW?vYYLVt;_ad4yFm1-oKpQ=uW~?e;u8w^2QWqgeOKrZ z=KyYzdyv zWbqiG&m4N^tth&OzY?$;$mWmwFfYQt{{6w%()I9pAdB%_o)iLL#fN8`_iV7|bi@v5 zHk%>R#A$CnfFs~WRA!;hVZ)3fRCR4LoV$H5oW8pePUF_}%yucv zAS=y%ySZq_mvj=dj^Q6V;%JWVgtck3v$4-^Dvc6tVpoNV`NDta+gjrWkt>Y7>>J0hqE{L@a8&SUEN zV`pPMsBWB6w8dBq*0YQY?P3+h+DWW#nk`uNJ7H_-|Ke5r^Kbt}WZHj?b%&LJ>rSpz z(w!Nuh#9*^wddCx9=`oMv#inLl~`~r*KeosZ7~5WBI@C=cfJUz7%t~^{VfJ;$Zpz| zwWi@#ZsNjZjy)ZA(PuvmL2dLgn6{;2UYj#*(&-dff2>j+XFl*@^Q{1w7rpqg zfFq!Dr%A_a(|~@RJc$6rh>Y+ZnT+K*WXtE*P|zz7m}e=p{~P9e+i;_h`IlKMlZb)Qm#N?dQr3J4#lRj8l)8uxHa_}U=-&M$ zAu~V#N?T#^!gs=4aWYJGHrbC1Bu756&zxjONxaRt6>;0_QP_Wf5!MOw%-SQtLN0ex zUTpq6-Awn=@0UKG1Oo7)N~K2co{@!2{N``|=AGw0bRu*34;(Ik?CBWYAltu&Y^TbA z>JaE{dO;8DZWipc>6+avQ=^zry{O+p;X|e1cRLV@GwZ;mK_2ObS0sX00aF@7YN|k^ z;}&9&V#0=tPVA?1ZUy5lkEHZO}0RzyIP!^@6I6@)!mw%NW1^Xae9j1k)+o zAo~ymK>ddZMMlZ-6~F6Lm0KkeKtwp>(A&q6@)e8iFN;@PtCKB`HpTWa&1_$E-7D+P zxrNS&&%P4vc5M3N6EEYA7Y8)nFK)t;#)(k|#aYmXUj=8mJ&Jpd!sT>bnw^TgvcvT_ z=#5-Hl;4X=zINCflKS&7~g`t?PQ2*s6!~gzo$xTp;RSBP#x>)OMV)J*e{e&>{~6_}_#6 z|0vuF51302vGeUM$QFfqvK>Ox*FCkHurVHnuzD9xn97(Sv9K~DCHxhr{;1vSkjUbX zz771CUCL{hewvD-=J~q39}yckH=62KP~x1pMwAltV75_k>_By9tP?Qk2-uERXEKt) zH}v<8`ee-fh#_)c@m*5#Jz8d8p|@zCN#*5fMR~M!=QISy-@(L>wSuzj7XA@hcMu1Z zaB*IFjAZ356AO+2_`hqXi)pFB|BP;`QvL)8*!ki*8~~yXq5vq&5d|0(OcX)7in9OZ z0>A-~fE`N9{65E#D1VDchp!G^`}@SwNg@EL5uQz+2OFHOJ>>1SH)|)S8!<*~NrOrx`J#;8JM*=RYT=0LaxW zqJVi=XQyxz3<5BLgBF$5+AAA~1K@nI;Ofn}aJuuC!nN>Tm<9n*_Mfx<$JwDSUa5b= z{-ObJ12o_P+GI=hZ=#DJ5(5IDoBnB57`<&c0a^nbg#%!{-P{xx zoVm*G>Q-t3gR-xj+ixlYkT5~H06OzhObK_aJHeX9im8hQQ}_0thQiWKl>C;!Au)>V z-J<{7m@GqXpg*Du<=#2~0VY5RCBX@-%+3_n!z`TQ2@n7YM}gL8DGoA#AD9)nFZ;qQ zVVy8<5C&S5N4m#l{GIOmd+cf7+P!2cR@muxSW1mbjRlR1jlItK-Mt?o6J{buvpt4H zY|4*ENmiyL`yVa#s=nsmiU3CGzGv^c=v;6nP5Ln13&`-%UWyJ!utVY!%o>-qJv98a z7AWD5y@(P{QOp}H_EMXLh;MGh*r-0$BlWN6zZXrIywIcnb?G9ch{q;nui_kK75t@H zL0lmx!$Uc0+DML`^{aoAkjVrtXQKi*=n>HQE5n5SJ$Bry~AV82Y8#;&{F$s!R8HWDNgg*ELDB}yD4uaO;!2eHwphko?d>3IAgPUO1&>nMx zoXylyw>T0EJW4@Fd50{Io=yS*7%tsP4^}+=_H5%l3jgpQ{=jZYAj+?bR-snk`!O*~U5C8{QyUx+kh|$Y^v%g?0TyTyNZgewkl2JP96_;?#fmzb+ z3AAr_LZeAMfhr+eR~ds<-p6BE1NW%Y1TmS5QU7%Po4o&xr^gcIZ_uB0y#6iCG{OUX z5Ifb5B{GSX1$YBBiGqnxgp1Oco(m0vM^(@dhz@}4(h-uq9tl>s)wu=Rb1>^a2C{+;fR_53OjfK=hspmetJCVzM5=jYMn2tVN1MF8xf$o7wHETl0}1mNA# zl4cxL0KpVCxE%~bfYGvf`}SZD#Kk5OOH$MIyZ<9tHBL!ZAB2tTr!dF)1e^_1 z!3(h8>i7lNEQIR)iO^WCgxRfWoc|El9p8UC|Md_{A6L@!PvCES_+?mrH_lFnkIr5W zOY@VVd;ScjKyWTp0<=uq@j9kdEmud>0eFN6;0{QZ=CB-+DDExkz1Oh~Z|ih$4=}E> zpt~pniU4#aaP+-V;z+*f5B_@SiE}{`_-meA%Q{FhW#~odh)nN@D9?5`3H7_d8iJd) zBS%f_OQdPOK|BJ61`<PsUhO0`z9-wJF_8ziqfZoc-SK{hpoj3y$5CcP5}gc8a?l1C~DA zed$OS=KH0xH|3O-M`lc=o)(V1;9ALe?G}%|D*B2!Gb4nORGTukva=KIz*wqvF-;q?e%(M zA3Oi4H)qAe?q5e06Te<#J(N~ny9K#_coJpz2I6$02CQ06%h`|}_C z;0JO5gnj9-i3zmrcTV?wZ>)*gb|T3Nr~XToPiG7CIyF9CfB*a67Xi5G!<2NTsPi9z zzcHXoUOT{ik%RBSEYnxdpG6z=>pX=vs5Yb1a06yQ26jLM)b+$FEmr9HFW=rdQV)np z8%Hh)19i-wauYzON}4W5 zD)G>l1paG?*KVo)hwcB`EXc^&b71=*C|WV>%0Lqo~1i~@CScziJuAnrL!yD!!&#zycb^>*PoL@01m3(V8c>_QwPYqc`ht)QA`RY zmkg38%2XJ&2>ktePrn{iWd2?md-Mh@ogMONpmEax_(PY*o@S_bd;E}G-ab002b|z) zE}JlYiCW3nt!HTB?tG%++7tLZ8{yp6<8W<#Gn{WV!Xi-val8qREO%$TNfE#nMkSAM z{$t>$=HvxreINjHSS`pF6iFF-spD)R4{+$&RRS^Spr?GZY1mIX}+O~_NeuomB%yyN@N8N^Onf}3Akm6iv*v#uk$W9WO@CIo_<%#W7pK9%nafw3UIhX$+{nR( zr)$rNEpnafcXzv?k3Hpq6=bcjdB+XhPmY!xNF6_5a1*To@Bod@tP!6u6Qgzv+0in3 z`_{odkTxvO9)w7BoO%VQZtQCdDBMhTx56we&zWwW{#WjwnEy_Z@gz|?e4`O!s}t7I z0A8mqiU6`2)63(l<`dniNodmO8Wv|U848u178>95Wf4=rE+KNkqv&(ycys{M@5i@O zdOQ>Apj=*J%0~FZut|vaaD(0D$Z)0=Js(Q&xaTS3*){8XiNXf=w*Fokn>2WRP#fQr z`>uruGuW4gQhda{A{-ahYAO(l0)KX{!JZrX>foPoZ2K@uWkAc7V6`054Gsa9#4hGM z@!H=Gu!q-!zh7qH$?C=Fq!0irZkyA2xF)Hw>1?A5|LmXrvq?Mx{ubB&^Y8~QiUKmS zk|rL=kGowwXsOH*i+Jws=WaNl7yv|n01GIFo#&AK{Ge9~TWW*qBl2w;PY*;lTmAmj zISFwDD#Yww=uU*Qc-cA)_}BJ7$FQ9O<4IEf0{?Af|4+-C;j{8mSgDu73Qlu6Q?OUH z6;}E0E4BI2kNSK+rC;|6fW}1Fe)2w+fKTwIh|`z?j)5kzS%$dLu}lF^d9J*;<@ASO zJiYrh$z{0D2B&BLIuVf1ww{5P(q%dib(?UV%?7|vv_33ix@(i6w+T7YbYElK4ETg+ zy3k~7BT~)vZh?F|czu+4oJ0u%Bd^Vq?=o%FkMjLc{okaYq61ZkKzx{n85C=$VEZ?S z7+ObMtP5cE#*UtZPkA4!_!q?hQDm(-;BGFzC5+>jcbo|x7Lv|fK9^D@()qa;UgpM0 zAppa5vhsrsNWW9VV`sG6xQ7ej_c@+N0Nm1Gsgx?y0Dj^@6B{5$0C@Wa$=-G_i|8BH zSODh${_nx^ncI( zAa&$S4}Ve0U$5QD|C=o2d*#*eU1Y_yU;un1eWgppq*6*v7^tyQQL;L_V zLwDtDSpV#!P}m|c6CqH0n`@ym)g=A`&3X?ihA^m1>!>gIRchiZsq0afczVxWYVg`h zrd=%UV4NdRPtVeGUmdtk-x(cH@lChMoLsMk_A;S?H$h4_LGo}&6J0(d8z|`WArd8Q zjgb@3&ulQ$0mx$Ud9uR3%h^kSP)u- zJc&OijR4q))DX`R&~pYA-ECyL*ZUX$;$KYt^MC%&KjPWGNtSWkyyFJ$@Y%5``+Yxo z?xtT<8Snt*`obth^8T zNc!Kfzl8Z9>@Ro+tp6=ygLldZe{`0jLQbTr4$0(oeB?&0=)!(QPMj6zfDKTQL_h0w zrg0^Uyb|w#y)As9v)}uA(#Ldi$4w|r@^pR`?R?SF^ttuf@4fx*4Zk}0&fs-w+kW>3 zo~3D;ZtZ(cd3f$0@jG{|fqUt?kT{7vGxTgqyZ58kKg0+jvb&q*P{S&w%n|*d;t4QR z^$i2?F{ZDXQW*Tnc#e4uR(f9qz_%=ygXd8j-81vQSKEnassFYdfVBH3E+{E6 zk}IqzxXw`lE@&Z^ti+Dm6ONR`O#ZJAm+12-w%(h`N5lXCRo{h!gR{sthku*(iKa9K zPNI;!U-r-0XCAx2zke-u^aaO0i4JA+E<(X&0FvCx(mt=f;Feh31TvmE;sVHNn?Rf( z$2!*L1>e4Xe1slwgVJ#g0?sn5|5J~jgzBS5;oL?o%x^D-Y20p2f&v(B!)_l}68IbN zXA@q|DlVT_ChKA4+~u%3RST^t0H(IpQ6m@V_*F|HEmCX}bH*>Y{GG^I=@#b04wPND z`!uvS)#!L8Odb=L_A;&uO*2E^%^J4yP6b9|%!TDl*pZ{PD9j$XgKD2w-=W&7MT_^rP!%X=Qa z)Bg<}K@b`CChk`>ZFN5(_*D_HVj1T?A_4dwCBD4Z45OY%c|X(r?~`hnUo#Xi6yyDM zkho8YrunE}wt(OAIFpC_RxI0_*5QzG^l_f}N_fP}J9xs}Ds^KptoFoIc=C?zmqYX=e|qGN?pq=2yQ zZb|AeyLb6-1Mlv0nJVDG3j8ltHsJ(x!u7720I=ZXF1$@I-vf?^j%$c&R@qny*RJ0T z(|2x!cXnpNh0eR-bgzL6;0Aqee~+@v4zHT5|8?|gmM{Q(Snh-e_?5c%jqimG5P{wz zp1@*wRj8f=siwp8|5Bei&vl07At&H_|2^9WVUAYsgsq3~!RlBdX>P#no%k?gyJdh`QN!%hLz{l(^+T4>z2j$7G9{4D)4eQ;*d?H}) z*C+n=p2>33eXltn81ZdUz^_FP+$TGgP~O4x3nZY@Er*FVb}on)>plElVDjpm7xAsb z1uFrWOFXN#5QT{(tS^P)r~j30C`VA!`VjPsPWh(4;eZOwBf+x>X`sMu|mGr#9 z+IU!437bU1+c*Q zjFKH=1KYm{Y>MpvD0bN$rIgWAVH-b?^+aKhvnkD}G-T;r&->jQd_I=zSAhW7kilcH z;i&`Cz4E{Q*Z*2*{O>sa{$LC9>F?}kqPj?qxsm&sgIr~$D+(}1z%jELtlrz})B|qJ zl2n8=EpRk;2*L!5dV&}LED^Rp4gXFe^pEhM1O49)Ey%JR9C~zc0@A4^%73?lTs*fp z)5F*IoF=K1T7x}AAh(TwgCcmcb2uaT$qv*cZkS6bn047|+-~$OW0culshM1ae)HqK z)M8g?KScnXex&oj^K@(X?6dSdUAv+IjuD`8S%m71+npcz%oJCB4ut(aZjb4ifZpqV zez8veiTU)ufr5_!o!jcprS~I}(Em2l2lkbp68(*6uMvqTfoya^2o$fQ^A(R+#z46d zSxR;AK6%741`vQM+{hZ@Eh+ta8|#)14zEA}svQsjtTm+k6?@f@%{cR`uyJz!SH2D= zpcvz7kc+UbR}zOuu0c+acd|!Hi^}ty?c-O zQ`Dt&3q;*Xuxo7)v-{foNwA>7`cWiY;mG^{7+pYSx$9qHQ$BV>x%?l(wtw&s{(&$T zji@wR_ngygbNJFRl+Ad5TA7ndHeh$I_6y19W&R^I&_<`D+iVglE`##!PBbg)8^&srjw!-EXVNfA!i%X2dtuL74Yf&Un zJx>>aVjB*%h~l}?>7_{*@LuZQML|? zUDMKtU{Kcrtn~=6xt7f?sqFV9^XgO3xsn}^;&-%5K+gL;+TIhf=znY3`S+I1H7T;; z{f>9yGy1^tO5Ce(_@3>n*hcDFrVh0XF&AZ5I3pN{{}LC#7Fv#+0ZTBiyrftf*Z#{> z-W&ZNM>ttUlYl?}D+gekm9ZSw!IOYN(_|s)z0@ufa1@xQnNZ6#~y6F68cl37a_aFMOEuomKoCx>wLE3#S4%)L{ z`BfUy;rlQB`y>&7;mV~(qz0#R>WJ7ezwsNtG5e4I@jw2_@W)P0%>avNS7!ZdWiKhy z=iWcyhUS0`26_&RxDDo4chEV%O=Ic-O*2IRRv(7yN;6#PE`}?}{m;PmpW%S{88^N$ zmA0FWVSk?@1jrG95T2me(Z$_olXd2v$eX}MNZPITmrk*eYpz}0HH%2 zT=@)898OCN%e;6EHpm7(mmY`CvFDhahSvv&? zLZaXz>NTMhU4djJWh`J75y&7CBSIjcCuFV9^~N@M{+V)0m%7oooLrtir*_ZReae+B^- z0lWfOL8VAUentDp(_f+tf?nsG@A;0v)b>W?!E^jJpOapTU_{^?5eKPnkrV3HM?ich zejj(9be#`J{><<5HdsH?GXS1n&$E)~fE%S+_`Cm6|V#B*q+z2ZuJZ+a?{TH`bkW8!Y zO32h1>2a?Er6b8I^&d5%0X`8KaP#BvdiS>_^nZK#x}-GKv2H*fKqt@(wk>iyfbN(8 zbc-N7uzY*nCV-eQs9PIwM9>>x(=RapV>nbipNIems7ft>rYw5^eAeX5E3(&nTgZ^< zE?1{izf^N(@EWquWTT4!Y~WDKcU(NJ{M$N|@C@?pDMCNX5})6h4b$z32)-A(c!BIA z0J6ii3W>c>{cW0nw5rb!?)uMbS?2;yQAnToPE@vwR|$FW4Uq?dzh8Qtf9w5cNP?y0 z<;45EoudGGJ~^Tw@Xrt5%%494-G29?wD*m?WqG;I+Ej-Z)Ts2%fEl+%4=pI&^( zgUcKV&Uv;l&nBi2dRt>f@Fir6%d23^!)`WF4)EB zsk_L*>y~1jSR2;W>jrIIxDXMstU+4}YXI*n=nEkBTKha?TkA30Y4#A0XEfKqObcyP zGx5+UOS`&Vi!5!H1puARjI$JT3C;CLIY-2RXCecv*xojLH4y;Dw#@so$g8mar|9bj zh=5f86b_6g-~}@If1oWS|kM=!F%>Slu{US#j zasAy|EfNBdzmu0W__fzZNtTkYk5u|mz8dE{_Jb=BL(wqN zDTdkgtuWVK4?C0038Hwm5tBt;fnFzLuZ*+w*E282!YHwgQWMLtR=m!~XVm&KGvrQ3 z`+qc@M8x;@;hzfAxCsw#j|aen1Pp_m!QX?|qgL#N@8>J;g|Cg}1sjr%!G;ea0A7df zZKB15@V|5HA^>h|cCZn%?CgRj7jAeRb|A=-Le${#>%)^Qo(AlmI;LXKE#Yi=D_qhK zG@HyC?7wX`Ecd;)X~Z7rD-so8wO8(af=2Tnhlyq_Tx$MWxRycvvHj@%&y8qY$qh@d ze@6UUDzAs1&fN^(U-(H_WmBu1tq?;;@)j?E%ZLNedFtVOWoL;wbWduz9;fPJ^XEdCJ(VK@MmC)0TEsvnJo;yk;sWX(7x%bYFvfiJbD&V)RA-;DJ+29z2W|d$ z0CKni%XdTehyN}V9^VKP+iZI4YoXlfh1uRz_+Ib*a3Rx0Qw2+nxkzWrNUy_9@GJ{l z^UVsByYg=3>;gouHGNC$^#;$S3eVD=R%0L<M z8m1EGfw~oT*wk5J#o{zBnNfP(s)rgH@e^w*!FIw_PY%rl0Ah-@fXF6G{2C2pbC$b^ z+hpcb$1!KI=POV}wnWdPSHK%NHSRm6@s4@S^6j6Id%&@BTv(kTYlud0(p5!wqznO7 z;JSdhL{tVHIp?q52d)x*zv%5xi?A}if}ccsh8;yQ$PrR}i~TN#L2e2C9_~~B>3%<} z@Bi-a{s0Us3dw|V3Er7aI(&7o@N}KdJ|BBJX#`-n!l^Ny(_v?LojRrWgCG2^o%J)0 z=aU`Hp+lfz8Lw!H06LO)Z2Cv!0+^}Wl7qg8;>UX^flPDb4%Gi`Hhkkiy-g$ZfPCQQ z8q>QS>T7G^o#k#gwNwe`0I2gEQvOnwNy%%3oDY3fux{92wf~oJ{o7vH35_c_e4Z(V z+BxK%m)P=vLghvNAg`89-Q6JcDlp%**sEeM0L(X@Zm)#ZKp9FOVAiG1-6g1Lt~+Sh zckxi2NnOhoSiGEz2lUTBO=w|}0uh1)d=IVhD|)C>puQN8>lW7@h05(;g!0r%^;sfV8bE+F%tLEe9s$baYH2J8B_ z21i(eaFkR)G$^~j04ypXI?)wyi~hUbnCCeizV7uaORoX} zNDUf1rv|699b@l%c&#F!`oy1eyvMOOi2z^?P=t*p>&NWvGW*xz^BnH z%$V#+maSqNw|S4bwR8^FIrwN1B;d?DAzb^*xr}`VWI!`K-R&`JUaKjCwL<|fj9NXE zRvv`v7k?hAk8g*?&0_eqC$(^K{d_osPQ(YDb5Q*iDOg(jJvUa-rOX>I}exdtOvmVG|GPy zDgbf_KZfV_K|PUE{2;sf{ztc{1QAgZ2}n+WBnt8*3==pB)6|q1gmbC0W6$&Kpx-9@YawR($>keEyd>PhuW62VypZBA8ar0)>+R44N(}|KH;8 zHW+-b3Of`0t>i(d+#-?joFco4YFgF!2kN+s>041Pcb2503)M-AQ5zZ+QEq11u%q!_ z+(to)(85_0E&=9ryhK~kAwYBx=OI%tpO0x~?UwjzFJj{;vP-*A>{7H*+TINH^>sKi z>tU){4U32a&VZDi!B4{3Y!1Ps3VCYE3lee^ZG4sflKW$P4S6GS%2lPKs$UdqDN4=a z-bwSmCPU?(UuVysW(^wz2$f*acU8g#Jx5P2wWyR%AEq-qMdVHob>_bnmXWi&gus6o z-uc^I$rN{|{PNZO9o!yYMTx1QHrm~0@VEC8cGUU(-~asu5P;v=zfx@O(cyy9d$2Y| z0AgGzxBWkQ?yd?Snt#kyn)pGEHU3Xlq|tTS23|f zD6bOXNMjuG@#v4zFsuFl6d^#g{VzNX8x2g}Aj-?Qz%8QCzh6p-xkDV0^*Xb_40%wf zu{q*hu81%F(j@nBOjAaz&{@NT4mLus`b7*Zl%X`&-MSpw_sK+T17|8>=1i`X8aL7} zVK=3I23?ZsFRwfbjoUxRE%16+e6kuod{1XDu-(7Zr{vg;&*Td)0t9QgNUIhX$Se3zs*%4`rPMwm@ zc9vL^vXdWk{3^$u6e9!TeW{1S#c?A8vRk7Gic=uC0Ch}cswjb|8H#_DC=#B;D>5;qXrlc;3wX7#8P-tbY*z_AtRlb1 zK{Gp5C7t`lxOn&6@&~iESfeCl15wA6cm^d*r3#qF6;TWf+xROb|L@2UU z)3iRg4P$?T$fD5Nj(v9U6{-Iw zXmgW&Zku30%|?T`062{*W9g#RND>FU!Ce!@zKDCL-~uT7*D2hdb$`URM-G7O|7eoV zW}_(j`Sc5J3BwXBOYkk7{X&@N??Kq;{a2D+)lOyO1{*kdof_}Gge7?{{>y*)FIAlQ zHylHW&DxF!W7YLyjsP%>JivgZ2Qa+q9x6ejWiKS`vuNvKQ#jnw~f7T7_}7x?S;cU##%@8LF~E~s0R*hHaxau0eGz7#E{AtEr@{x@r^3}8L@`8Q)SOQvzVXZX$Jd&- zIgPsqM3i%6xd|M4guTqY!jtd_-zVGnyyz}m!eZuZUvxE&#WL>tk3TTk3%7SH#W`QjQ$Pse<+0rN(Nz@1$rdd=U3_8@U_2BEFDBAomhcn zoO;{FCm8EJJIH&fqdLF++rNGKAN`|$^n2VJO0aG#$X+nN=qiUPFXu==6!50(hd$Zo zry_s`lb{yaK-=Lm1NkkkQDP5wuou4%S0Iniwa>?2_ghf?K}9nFPeP zaAj*cT-x~S;bOKJwTz`Y$GNpg$;iso{O>WQe;;4D6aMVNXJK=(8KyD&o0Su0P#RQw1{@N{cr{kyccmCgh=50H<;OJ zY9G4>Fa8ijqkspu!p?Rm;pC_GyL%;E-l|0}jF-Eop!`*eP{V(m zqw(S@zJ24%>j8oP4%?|n^L?~s{xJJF`Z6ow5#BGKeCuz7?bGuio17(x6fny9`qGQ$ z%WLb4OU~hf1m9w1EnKKA;rvI3aEJgR*m-ddd){DUD3{@J5|2Z1w6F-MwC5Fm{Lc5k z|9ym#P%F>iT7q$Tg`Ob-ew*%j{YuhvH9nzIQ^WQ<+aVr4OV<$z_`wf;pdJ9i<-Hx_ zJe38*mdu507$$#o<`-=Tn3 zM_yh-UXC(;1pdhdD}yuEc8LTS`nRp~AK3oQ#!hHWu+>>`J|*%ZU$$7kPlwYB*^s&g zh8ZZ;FtMu;YzOnh0zTD=hy$|^>R+Tt|iJ39Dth&<<;GIadLC>lMtV>-bR7j8(6f zk$wGU&kF&aOnP+yWcydyJIWjef;%?eBLI#-alhzasX^_YP9W3ofCmSzdg^uLMdPk@LOE}J&t~2vNCEp z%tr?RF+jOOEOZ8=+reBbcTApMKJ=WXy|RDJ0k2fI*fhIg6`AP+%)p{j*P%IlO&`Mg zk1TK8idJwXdJXT*i>>p7|DA&6Y}j9!%`Us~CV~G3lFUa?GEYjlFrC5q4>tdJbP5&1 z;W{TyJTYlXlvTfk4hnwoyNEtokN%v={2*kD*Frdbh1tw>Mz#uu5a;TN)QP??EI$Y( z0=vvEJqq8(`O@hp^Wj@W)IQr~9J0yC_80iSO>ce=2=rYavilX2HQ|(f7VgF0Urcqv zPtPxgdsC;v#=-*B|2aYdBbu(F52Etl8=Um^x5(ap2G;*PZr^qOR!7`x9Dq?20QHn8 zpjYIa%l;8R%l=mktuESLLg%+o{u8`_Wx=j|#^FwIF7@~z92|s)>G_GCUnK&N8fT{r zHac~P_tLdz5rC{xsmMb4UpWR40QXdOdUA>wnCzFzB-k9x9H^llPF{{K*U76T8)$|J z@qTS1tfA0#2aA9*am(MP{d#~tQ{fHPzoCDtE9>Ed=0doLy2}L+r&9o)T-xkVk2e|m zXO;DI7w!M$BF=y2(A~IzkHL9t*{8(F$6MZ>-1^N?AD}c%aFwe#9U}NmYwd0*-N&8q z_97ATRzvUFU+I4a+r1)7V*LFOxi4Gj96Y=pO8-B5ZyqCQde?dW;=Uu#%A+dl?z`P> zY;1$M#s)NqVMe>!mCZ7PSgo|Pu+j(#gc)p0EMhQb0SU?fz^+E~$7(gq;DJAOmPH2a zZcJmFHpcC%-B)#W-Iezl_qCtz^Tv}EnH8B85fxdLSyfNflkXAl@x0IRyASLyMwg2A zf%%v{wlHCH4aTCLcLV@E;<*1E-|^_+2=qX|b0&ae;`rBzSs~;v7ulCu--J}&va7hM zzVghowm3CmjqIouW=;j7e=Qghss}Mg4@oa8-1`Y&`}0`;%LQ;2HE#y{ArSyU3Ht6% z%?%9y#PJ7+KLXx~IPpIsLG|CxKK!FEed$ZWU3$3Z{{2?xJg(Dgb?h6_xv$?2wA@Pq zpz}lg$Ep(qvUTh`#3O%oR-GKmQ=j<6C%(r1t`aN|N0CVkLlh?2g@*`06HsFQ6}xWh zIP6?vQu8KI1B@~$l;9+ZI$#k0(2mDHxVvtOGE7SQO9a3$u4f~Jm7OH9$QZh2>HULY z?d;)UbVp#&R1TE^YFPf0?ze_0o`}$fq&x8I7gc!Bg;#`Pr~>euQY?W8Qlm(H(VE27 zZ&sF21rQZcsfHz51wahFNcBPulh<9+mxK&3H^^&FG{Y05;GKl;Pvfa@%gt}-EqLf2 zDDGN-X(yb%b>url*X=Id&h5TN$NoA!L9^IDDR{50Q1NGPUGMkg86#2uD%tI}aQ9ng zom>w?2(Z0Ltn-!8tgTI;RZZnk0kB}=es11_H4`-czWfy&&j8OSG58yyCV}(f{Cj5- zgJx^lIlZv6mk^#2aW83rn9F9`sBpr6-% ztMBw3;X6Z!-y#3@Ryve#QeUG!Mcq|+lyop;2ZRpb4TFACpc~5K8`?xSlnCW$tRI_Q zuY7bENB|1!X6uU<-X!`Tu767NN>W+SzZS=Eiwv4HRb+g{$KR6c&L7zG-GX9ibv`~spYF(0oJ z_~@rU{psIk|No-yD5AciQ7}Mq43D%jvE2)BV&p%U4z`aX6+jls z`E+XDw(tNLgOiGu<%Ou`-8R5|Joy2;)N!Bmtqk67yn&g^cP$3gIaxYokF}%!DYM)# z`%ECt1H{d6$zD%fwa=%%ZpD$ZRVUGdPeZ)rAUfd24^#!vF_dEN5*T z1>CFFqE>zNbId>H&SURG1puIsm9>Hdb>|d1o_dE}hx~C{g769v_-E|$Wjp`1ui50y zc{^Jlx92NAU{5w@p-G}`Da;+7_dxx;dyRTnI`~HhfJu=aTDBD0v^A=9>&SVw=c5pE zy-gU9U4n?B`ZYl4`pwT>&EKF!0m8n8wu86S9D$*y%fMCodyyM@Leq*(m=f;Rd#Ww{ z8mtCPUpcQ|)CQh_)pCLK)tAnmx6KjYA@i>M>`z%U4ac9!S#@mIn&SM0upD8!yUzyi ztHXS!V!a%T73}HsB7xs<^(G2nKe~VaZL;!@$nrmZ491^8baC}%S5o4)g|oO%_*HQL zJTB8D*(>i^_wIB4q)g3RR0{m-9E9$d);Z^hwLxNSQM>c09h(q2CM&!GBFb0 zSn3xUUyA!zpY2z6{<`yMzx(vt{#Wn+Yap2jJ~{xO+Z}MH*Y5ed=7s-WJ--ty2k+bS z);s(V%)BZHwumU*p=G=;gytRU4HK6F@v^QG0Z?NO1a|}oJ3!B!yt?P;c`ctE+}U!^ zRbC6Ba!I+A-y$FY*vF_@->2hpi>Q=rbzG%AdYXBgYg7hINnpIk#&Wjg#E-8R&ApReq6Z9}q{*p4gD!ik&+*bawjk6s7;@3`` zrp2+l`Um*){`kPR_nH9c{2&h{{6~v2^3`{o6P;j9DFWbiDgozBu7TS{i(5e$!jb|o z7z)au!3nV_<&LEV(hC3(xRewifex*~qCSqh%(EDcNQSdUTG;EP3a%;4>%&|WbjBr_ zfk?vTY-+h+nVSWhAu-N)6(4-G&WipQxSI{HqXa$)^MhFv`pwv;6~^GSr-^AcQYG#` zh*!aX1o7|3@CYUlQaG9i7{nkT>jg{CUP2O;A~_ zl`c{HvclE}2$*;xwrlsXR21}QZQjDTU8c8+HcM7N@)g=-Xw+qOQy-}tgaWk8;bZEcj##nC(G|)}W z0ZJVN<%kOI5ptKxLHDWpeVuP`o%_diA_!a?*>3`~^sEX>^#mgpcn-JlAVv{^^PJO zwE)g~immY2Zt=gSZLmm!DZ!ze8rt6Ta<2&ht$_d%+}i4+-P&k>z3-q-A|Q)9UG$`@{KsOUY4;_|h27|y>gJpuNnj`_e6g4Wsgb6WOS|GY}ApZj4W#{?f zZL+5=@$3M!_VTm`^ctnjBjQ{LA|SQ7ZfEB=Z1&2gP2x5=O@8^YX3}w>*yInj0|fXs zAOIBnX9?H8wMmG8Cm;ZFcmPbG0*WL4_cQsn^*Gd~bbVNa*Z^VL5XChx9K`^z@Lk*k zqgJ@OX3e+WffxYUPs~~C)VrJkmc=1f5y#@Y3Seg6>tu!e6aGWGyo$N3z7LakAp`-I z-zeD0#+c2K0&!ev5LpWflBD8ieSk#NgF+S9PC=b7dy0#Qx6cPQ_H2!KIK&_iSj1qFX2`j-7w{2y>XUAG$Zy@JH0$v8Hr z-)qfhf%PdkZH($#acs^VQrAQT$!i1R4bF+kgGg|aAb!w3ghOzh&bP1UjO(}dTy8k( zmUHe|x?DRD8nQrTS6Tf4UT)irMlg&`@hs*M=a5&k)q3PYw`KPsDEeYz9oi)Bf72lS z*+|hQh}n_C2vBhVB<=0Lu)c}^ABkrX1hAD0p!#)Z`IK-Kr|5XxF9IS!xXj}|Na1-JyV@)?O&tc1~|u6L3YJSap^37AU)p!-#HPN@oad{6rT&ePpXxZw~n z0K%kR7V?x(H--U3gUci=?wqCplJt7%AS0a4`Sa@A;5Z-w^xg*JdZ9c zA`vBkdY-S4UV;WYI<%)3>bq5&jO#|IXbYh=7=l%+Fh=DT--$t4D?uG${L*mP@~H>; z3gNpV#H{gk2p>?(ZYwYzVV~c0-bsJj*K89Gx=v5vkK1ycwz^(`s7(O4q!&8RGg~o% z^7i|jy@|Uqcm{tTwj#@arFw@Ha#Da4^ED1EkD=ln)Vs^!6s>EBD5OF(@ z480Y;=Bl1|wl#~foMuh%o%+N8%;EE|tbZd&0dBee`PqHv4st6(3?O*L1^i(v>57N|^|>F4_LGF0 zu7az6h^+{Ky@&ukc6TGXo#V2DErJsFy0|{&rT&AvZ5^!P8ewnWk=c)Z>|^QQ`@P@$ zP0sy3^;TgNg7pFy3V>}T#}VUWwgbSdHwA?I<1$!IOdhPhlp+u5%A^ctLW*kI(vdATXS}s!|iPEw}0?h!<}~n(7xVZsBO@%y5rWfb{%X# zN7ws%wcD|;TOPt9+0RMhb3BWy@G%I0SyZ|r3i|CDd6`Mn9|o^Du|Hb{|8c~C>+>Cb z{qKaM=ADs7zdaU1_|jlC1bW_0qMNPYhP4vev~mLBvGna} z##s1i#~K{MiwAuK?NGjei1JC(_zxi+j z83=EKohkA#*NNCpf03N)G{IS5-EsDLo9Vd5iDHPyM%a1TWlCbT1s3f=X5Nj zF8rcn$Cc_@j@4mW7rM`N9>-47pkt~NOSkv6mK@i~_0m_X4SJ}aqd#uTu`3V+I@UTg z2$dvW8mK{1AkZ-9B0O6Lf4W2}BUSIQ5Zr&~zfv_w+E5|T&1!hlu1ARo2>~!4TebNJ z0g-q^2}0Ew%W1LRMNvETWol!h8M90%fh3@1@z|J!vQt4Q-5f@CN&uA-%%`~i40a#= zz4txfXQDi~a!A7_NcJ{KRi;;FFmtcpIl(Ltr?2RLu7Y12=kMRN;~W3DjiWr`_qeN* z0Pr|Y4e@oyL+<6l{UQMTC}@qT_>R!lca}O&``Wq=C9%RR`+rLX0)l&PD*zseYcSMs zx*7HdEpq8nsK^AsPXxdO_5e*Fb`=P>-ju(#NeuhAxVZ)NCG&P z*Ft=hIaCWc5+TP1A%%snA}wqKWT2G6l`uaaNC0Fg7{R4bfQQVNmLd*7sDO$~k_Fwz zJdbdVxKLufJ25oT-U6L5zqwGaLfmQyfQtsX^&zfa2SQpx><)SHyVoHL@ypQ6|EBYf z0MI?b*M`tDvnKt8j24O~-{dn2qtnTAfcMs3cHApyuak}(b;Afi#ob^oI0>1BcH zg3wQaHwegoDYtG*nN?dSB4ia{9|Gvh`R5kI*#F6Q{x$eWku>j13Y-!579OB(Dxt zS=b-qIe6!9d~mMNXesQk=-mu+L2z4Xe^YpLN%tR&X8+$Cc$vx2Ttq;79o_yI;iT)} zs2^s#jkDPIGg4bsO=w@)b!GRlKY!rc!7=1;n&v;e+qSdgL;%17S@w5-_jj|u`m4YC zN%sGb-AxcO@FLI_`2gw_jIOXw2h#4obl+py0Hg^Dlpg1dDx7lyo<|G;KAOn+A;HiWtbKW?-*AA=s?m41A!-7Wip|S`@^X-Om+&a%C z+O}tT3yD=rmgVJ(oJ0@r)CL%L>3j_Wfuuu{Bs9t7R(njyALF~_m{qSQAp(#Pz=1Z- zKW{ekOn{Vf69FNhmbgxGP1^ORqvJYucV6G|gG2J}fjpDO@9uaAsv=LS z)O0NGkpE9MK42egyvuRu=kNl^LKetu^v1LEA|ghylVgW z)N2^()@+NI6wx}8JNha5Dl_pa?Uq&KT@>A|IW00p?usL=9Fm8$rN_=%__6n+qJh{N zVIsz$?za2pE?)TP*1PHfA+uQw{j$u>W5Dn8i4}W{z;2_s0LGXjAraPn7ROMMXfBqX zW?2B~@Bj#;X}3M-lfq4$Wif7x|2uJ5Fpb@+Z%^r4`?o#pUY)pK1i)_S(b+lbG#zWJ z>bQTlj;i|eKmYSN2!KE3_%;H-EmycC8ECjbKu~L1z>dptkL0c%ixU?i1(3^#tVwgQ z78Ul>0Mk1ItsY-;Branp#F~Ps!m|D+?tipYAW9+Ea@FGzWGcLkw zIE&PeS3m@4mMf@C7(>61TshUxE~4JU1rZKl<_ztTkYbRQRK`iUT_nZzS^xZK_VqFd zyCBFM0k&9Y&eM$f*roiba1-Zu;46+j9%B)^eQkYZcf07^Juml*0MLi}57t&a+Sw`E zSH}TSwzulodRqF#Fk+ofQ*tPh73noq?DFo0t}EQScW56Wsr(*Frf&( zSx=#k<(a_JIIF?sZNq)#Fq=Qnvm6tN#9c^U-zF3(q~FBTA(mh(j+Rv*Lqkae zqDc88DbQkt=x`W2m9_{#bQPWbC>X3`1T#8$eW?sgy1qi8cz1_r+-}UHmgY|&){+lrYPTVD2<{O~x?tOpEPxrRm zPXfSysqYZKRcEP+tkzZ?sp>m6OJ0C+Vl97+bAL|lDCp`${yPYYD3Bl+jYJ-wbs~1v zO9W(*DxkN%)>RI)!2L^v^jH#IBLRV`)f^l!7TExuhoVUQkIrAfJ-5DL&#tHJ__|X6 zCT$vGNc#VP`yVdkm8sVzw%!u=F2q-@He0pWS*ZH)upi}zFk1kb;# zzvA|ZPN>)rp~9L)UVqubL@JzEt=k9JC+)pW#Qm)#c_L2OF+}L%`gaCcB(?Hz*rtmE?d)zjaxw~k%2;u!JqpC%&Z6Fd)ZiUty?dWpN*fS#}J2B^Eg><(u| ztccXjk#(xX_a^bua6w??wkf1Av^U+MA&-9Ew+G_D>hrj6KL!yn2F#wq_%Dg>U-n$R z!u{X{jJRC=z$HTd$~6;H@E_;;CsCee*N*Zr;Uvyz#dcc%dm=#7Su41`iros=xnP>J zbHB>{lwIxqc;6wNTXmQx0Q|O2df=0sf1zuqX>b5|L5fBOPzw}2en1r5HgH`Zp_Bef zq4_uyD9?n-GqEHMkV+s1pi$7E2fnm9JH`Bu!D)_HV>U%>`w40iqbMQ&K$PoyY#2Qv zfv>`$Rv`k)wna+Q2Apmp^ahvL%R)AQez7gh`B^Ch<@qDq^ULPa)YEUBDp`Zueq-N!6B;MnsF+?&BG_81U^eJE-?QdTwt$AW)!+;@9$u--6rUIPf}!YRLQk zYp8lHBC_2Ro$)J+Q7UCIl~O6oFm@X|Y(MdZHcrx_^LWZ{yCMDEh-3Hh_Ja?4M_+Tl zi$30WfZtcAbynY*V&PS%Kl|Cw0(I<S(_odu#P^wN)kNVE&w)LGT>dM#TXFl_p6Ce4=NB$k>eujEmk>OC3 zpeP!&7HNWEP=HlSyh&rzdr{2jB(5Yv_-Xv!w=gbvA2|Y+IDduXw;Bm6IOpfypLwLN z6jE8ZMEu1iODr~Rjx@>VnrV1CCH@gBKD;92uc&eo|0}-xReZ@`vA1j$-~Wv~IS6pM zjsf^11OO89d)SKzp|Bz$f`lSb=5+<>Bgoev)U3|2R*qKJu&GptLNE4LWWv^kui^mp zhGmN_`)3y-c!x~c44yLYE>B?tFyc6VA{E+ zEzi4=L>)&0ryx)egCc%p?-Sr+h)3k2kikVV8(&PO8hekoIXSFwsX`hQ2;YY4hMDE4#!8ZyBUK3P}<)t zBh0{SUfnMK|1IGnnxU2EB>>ubywwe-`Ey)$e<#mjApq17D!ya1^%Rq*ruARMT!d^Gv{&6R~B>_-J4S9}gUg#aFsD>hl{6heCKu={Sx>vv&wZVt*B) zLE7>a7ZozKwqkRONXV8!_?4)gsO2#BW1c{GOK09|k>Y2I=zbyq*TV&SGkewEN?x%L7DEOH0mwRu>SeDLl*q+3Eht?gucynrD580CKh#!+g`DXZ6zq zG0*wqCM?VU94cBNei!yvW7W^YbhUK+h}N738Ajwj)9fCP`6b~Xej_5(ZN`6EEFOnx z>npoE_H}&U%3&Y?)G-<--$A>#A_9E%$Y0yqZ~Vq@oPhxNEc>?+0D7b(01={>g^?3B zYQ%6Rpo3fio3#RrExJqhN;W+dHA=AoMwn#p$}HF#h<_PimE^erMC#!oN97U$`WoU* zjJpz>Yj)Zp92whW`N}Lc7LIc;n&>1Uf+MG>tyaKHHKo$ zM@Tgu!Yjrwh&6dY44c}xQ)3?ezTE>!ko|dFV81W9VPok1j}adtj^U^zw!7!W_Dx-O zG=wtn3p=+zqFBarr~pu3xm5EI1l@toXN7}!TqpN0+~o0k_=&c9>2VpV?E^5}`O_Kx$$c`Zs1^GM6 zz#+d==IsKs@B&g&n*7ynf$n19C!g0QOuzus&SGCinJz?|t;+ z!S#SR{WNe`KL3H=KLi@*Tp+hT@T-#;Gq#c$s5*Qh(Z9UNx+DMp+{Qg8_&Se|Jbuzv zI7^d5TVHoi&HFxi?w*C?>xNK#M`&65eLc3b6Mg5Zvqf>KCO-3-|5L_*zs~+oQ@a=G zZx~2P079f+Z3%$6EP;A_e?^p~;!6`&2$56OP9b`VViZ)y9$>LS0HXdLcQ~&Wr$@?P zBjwvjFo&Y1^Sm=cV>CdOcI?4xmq`BHTNwW4HV(0L9QWlKePrLND|LO_hk=x4>_EY0qBQ=ovxP zya&1P{4h2EvIEe+N9Er3fVkEijF>`YOoIH!fgPjKg46%UUCjRh#)N0NSpQ`Ea~@+# z|0}$qHPn3_{km`uO;K|^J`!&7cuJ^14e3M)zG2$>eRl6(IV=Q#?*Vm+)|$5JIPGhz zPS)0UuC|U4cAMsGqzLXD@eCQf(A%{d=o(Q2^jpO3$9QcXpX3+> z#bYD|`GMFdFK*gRJOaLiX#9c55g<1*{K-SOcO_Q0?AiKpGPq~)=gzy3t^)GXhz?o= z^w+TSS6wH|-+#@%YFFYU`bo#^>fD?y9y@Dwm;9z|&CNG3!i38O={d6vKSKt6`4PXb zMY!Ag2K@oZDKCxK*0nQME0F#=f7%*zPXZAiLnDQiq~g=xZ9xhYl8?Xi-CL{Hy6`p9 za9y%vD>eIxH!5~=J?UaXyr(o}XPTpKR*3T#n(U=W-@gUom)L(Lx?x`!`?_69+_cTH zf-OC>WXUI)W6Gf*&kxV}@9|*KC{Abvl+YAWRq@;4XwbiM14R4}p&!GBD2&yi?21|n z$H;a_FB!CP58Zw8_n#Bj4_uf(9v3tv@!!=t5hvNE_;g!x2(|%`FCw5kk{MG5| z{5*yj;t_s<+Py%*xyVkDz^YTyfIR{_bicoSR$xtmB@&7WAdwRifa7dWLiKw1@Sw-M*4pFcn2IG;(lVfFGq^@c5>Zb z!`J)GT+yygByDMC+E%Bg$ofZmT#`98l_^hQa64zk&PPAkNB+B61;RHC-0hmsuMK?d z>!k_m6jFJJ+c@HXg#cEJ`e6i1(90w(gZo#IpXlmMi!EHS{NkdWUTfOp8!L24g@7()ma>~iX+UC3RtOCvX(;b&wTTILvQ7b$?FH?_Wey~Bw6 zrRcYJxcrVk>p7bBL8Te=O`rThZcm;v5&s5rYm002kg1d?$gb9M`PD~=Z$Hj}9)q)ETc>wfYD%HIEeYta5l8oG zX0n^hF{rjDTJ9B`fAJT8@l^sc{3iRqLETvx$N=HPO#Kdk!LjG$J zTl*5Je+%@@vB#`&_D4bfrxBIYXCtu87%sUb(+?!<>_XN@2-^=CfC}+PUi}-3!1Yg; zLiR5%#O;o;FG@h-u0nj|{wOzZOw&PIGa4G=46{lj0pb7|y zW7OmplzLR|Ne}q3Ov3#?pI)@5u>PNjmF#3m8xGD|H{g?~D6lE+h>+e14`4if>OPEyBe>-X8+KGr#Ps_$%Z|4stH zHu3FmfBOvE&rpAZx~uS5popXZ4k#cA5VhArlyB(t1_2WSN(m^>5i*pCr^!JC#GQ=* zjMJ{SAGt#r0V@12HUQx=QQV1h;E}(y|AX{b5Z$j#)TV+hW95CBw7#!r@$b)ou#UmO zPM#*GJua0AYK$l^xNo*%6X;o|kN||>{1b4&VQX@^=#)t33^{Tg++Ty8u{o2f3Am92 zptckx5fJ^8%UBb;78?ay#$lOpS?Ud2-r@b~U`YW8@)KHHu<+6qOO)ewd}G!g!|-q% zY0xBUp{x`6Yd-W>#QoR#SB4N!pr6YafmR?2%M%rAPLt|5gLpj+S0jCNbM^L>U1Nl!N_Ll@e=lUJK=uK41$R$OCaJNr;AibPbXL2{F6l%)@IW(8(}+D1Nmd% zn1IWZ-@m}%or<_T4WYQa1yH_xCRVVQ_-4Ll^B8l@XVSKKa?D!CF;q)}@N)!rPoQ^; zg5ACQnzkvFzhlSU;%wmO-dN|c%K6T1WSH%H!QZLfhvs*>PezYTbp5h3t8XT)w2*f? z|5`b1&Dk@kLsEg?f118?$e&J;i|Zi8SpG^c6OZheW&`ZI$RyEs=Wq(fsK>9=ld5}?H3m-G3T5VJ|c$ps2 zdl8iqmF@|#QwU>}6S0{6aC+4?K>U9X*SrX;T1HfOWQw?c`F3OVon2qIXBYUU8xfmn zMQw^S$T=dr-Le4C*LN=h^Fdrcg>$XgH|%Z1{#$k<8MYTrr|r^M)VA_DTRZy%R_kZz zL=e~Lbinlsfw?#hJYU3s^4gz#8f2FzF40%;N+9%d3M7SPczkL=WY@jfhv#g2rq|bT zl_bbdlN7hr%@HfiKg~Qv8j>8d`qMu`e?c5&arqlP84v)DgBf7Hx%VM*7xBl~N0+Z# z=G$Me==!{!*@)OrT*}*H8z+eV7`Nwm|5P*UkiT61gcN%zdW8c0s4BbT%i-7U8nOPD zau|L-dDYgQTeDW0ah=77yB+DzhxzU0`MSnM=H*2K3VNRt@AlX}-M@bcxPK8nB7r4+ z3OTV1FhkN3_s0F7@aWgO>j7n8J%^pu(^&nFusuthh$+&9XF&b~8~#B6gky;Pv7-?I z5N1s|Nr0rq-RI7~6^`Lc1bjLP08Ijqm;6@Ku(NXLiq0LHa@Ys}bxdamb#|ckednsf zebqp?`h_oi;XL~#Y-Vz|`6}kA*{IqpI07 zlQYdk9YLR@+|&_0msabEhrXzx%It>4cdSyeG4#$erHD;3*OL$dLjHk;w}#>N5}cJ~ zcay=8fVY8ytZIu``7dGNeLWtvEBUlt9)mC%O<8jcUH>?0H0iA4fy>Pfk(&^j&S!|S zNs^l;qUXjIC9MTa)AmaR`GEpB&C)IE9+^b$HOMjw2Mo|5vRu(Ld#s4Vr1x{^^*!g0{*?x=@ z-(Pz|{Cfb%t}PHzsQI91k0ppgrS`oZS+*6tKjiXPo5A=mi2*HQe;4IXG5!x((Kq|* zBmj;8Xv2L!euu2h4?=VNOi=puJly{b+`q*CIb!`Q-oG;b2@v?}`uS!tgOUO}%YW2o z5tt4q0qFiT;gn0@m=Ckv#yRYJJk*{H4%}-->{a>c@RY;OM)^(@SXAviR)=f!ebt~O zKl#Z|q7b!zP3>NoDQ=Ku2jId4W56WKPo)c%RG|CdcYjvqjZBh6jc9e!Sv#>m&)39eYdUir!RK*T~B?% zi=D0?@hR5+(TzomE?u?E$`aZ9LUsoCzLOY$Dy8oTvHi1>03p%p9r+9GYrzJ|eKwE+ zEs*6w5gu2@*KKVY%^$R9_~1TS?xphpexICt;ufApmG zI&f4y1Lgt`xVPVa`J*#;-2>`zAON8tT9yKi%JP34z5f_hh+lA5qW}KJnDJ`s`=v{C z#(oa|BZ=JKb@pGkaSH}YJGg)0ACLU~>=ShAgistF&T?2K02))jvO2fEW3^SMdm><) zBKz&%{_V#;^{G$2#BXm?&rx@kfa{Nl0081dN%bfZP_vc<9+u%QF+1OW^{!j@IFuwn zKB%YgV=gzNcB2uog-XWe;jC5xnimkCmJYi;fC9dd(_LzS)Jnll(*CDx&T)Ja{s%fX zKNLGVLOOp%_7ef16s}*#-v1o}`mQJ9_W9?|+44xriun;+Isb&!M$lO&;q0Z~kF%D9 zytE*97uf)i&Y8sCaK(6wuY(A$%@UuRjBIlSlHQRXnD>SWzR>OV-H$u0$HFBoGD=F< z-`FG~-kUWS_n=akv+~+=WcAI1_|IGOu^+%SP7(l!rV)%L0a~u_2G#q^+TZ2K#;am| z!BVfjWbyg8?G$z&KXo~0(}fXKKN)+jJnM2lNc)|10`T6zt!9d(L7E$z@crKnUA7CM z8@54s=hxr;w#`rD_BW19;IW$X^;ZxLC3@-;ns*&mp@h!b^`bscy1AzLrYB2c;xaD+ zew@gr`?~1!6^}08)dNCK_-i3^YS}d0{^N-J-<`frB-X(AS^>iPFG!ih>;d~j&hnp_ z|0&Y`y7jat1u9(fO>oN(vE9Zs?0e+z2>>-n)lUd*ePwt1y!H=8IgA8=I!2w=32D@+ zI@WpL$=Y@j0U8Vq&ImyoCP)(WbL@){xUFdL^)yG%iwe|)U?C%P-{)a{U!;36515AAVnu#eRBONJ6)FaCu7s-{AKMwND=ZE z2~gqVl<4Oo1i)sjU<=1rY~|Ft)ko_VKNhxFhB3a&F;rJNVoEy{iRq=L&}tq|(UYhm z2-pvN?Asu53@+)9#Q#CsUl#+w zJy37Gt^AyD3TG8?jsPj!QfH5UGzollQ?Y%_X1la!=JxTS*tyGPcVOSp*;#&HTXnLw zzWM?1$Y0wkK^mT5`(^44>b}LP0b~F|lt77tG^=D7s5j^(y%tRyRdEPO>;XnGR2hX3 z$U?bBnZW+{UY~c*t`i3%;)f8)i7kTuklZCv*s=r}&t&%>ME>ixC}ix{cIT3=KaAKP z@$Sty(f#rXTc4b;&G89qWJWOXg4>t1KT?;Vm-_rVElg49Sn0N6aKKX4sM&6e`WdA@ z-+K_3tGQ}B^kECvz6Ri=whY2wju6)$6$jC*n_)!#2}J!_V2(T_)PJa}wy{~a;pnxk z4r#G$aPf<5k>+`A-cswUHdzeW35cv2qWWcV^GmkI*{qHZtdc^GXdbnBOV(zcqLKwQegM^5r&8Vbwb1FGf?i z#^WE|>MN6byJ4M=?A+&)!%+^a1VFvh*e_z#WkM0JYKzmewn7e>>K9&(MiU$>fw3!Fj^k=A#W;AvVA_E2H-2`YBWc zATL@0zqRATx;N||ofQ^Uk{7n|^(CA6#+NN|fnF|Kd`{ zo?U&`#z^J+T;+u2aAj45KiT^CUIH1K24ju6@tw#;=K%Sg~XQNkF{?4=4$M^#9#j9$0q!fG+dlb-Nl~A(J18Tt<>E zmj4C;e(E{aP8y4KrKt6y|DIbL^r}u8@dzXUTf~3FG1gYXo3@rk3NXHD8xweRWFSP+ zxYKzFK$j;Caw>Rxd(Lb>VE6I%4}IC`KY>GqPe*JB??|CB11Wh9P&mi7Zs>)M%21L*umZ_H;xO7R6co>S10T$q- zMzkodf5+-6tp9U1)yU%d7dZZ@nVtZUMpr?7#04pX+dDB_x#0d+<5jykGiA$!qg|hv z#JCH8_3S9gY2cEi$9Fatck#{Av&vvi+$$K<>8%~y)idwnxd%B0Z7{H{P6FX8ieIZ9 zLdq0H0wBXvV*1nH&HN}<{uujZ0GU8$zX*Di2k{f6%2KEsMUZYA`3?G=G{gn03HmUM zrGKbgu$)Wi6Sk49jLj7jHeJg)oxc#jxB2MzjpC9O=~2?5c~Ji)TeP>(!fk~Mwn=*D z)+mG~njp72J$v5oOL`nLJ$87H4!D20w_>8{=6{oMX-N`rlr2zu?8|$3nb7eB`hB_m z9mnNQp?>qE`c-2XD@f!|#|ZZm}3J&EP{u~rU55D19;095JX z6?D21`!A5h<#X9L?5+3`HhL-h`uF{?t&fcn(QVAiv!@W*!?_B1$!dL24#{!&v=jAA zXminQ`I3bbY^&?o@PJI>*j6|K-nZ~R_vxi5WhssE)WiF?!x0yvrknGhT#={64lq0>UXCzj%D(@sHnXs`$#TD>^>3<){z8Ly zeaCy`ukX=d`8v_I1^8*seUW;5amYzP0%U@9bp)Mj7y_VKlbhLKf+it#u8^d_z zjKWs(=2%Gi0;IbN2mt?4w>RouoZ;;<2$S!Bal`rkE6Uq(xa}#Be~{NbKtA51TfBcU zQ~|(Oi05Ch3-J~EHhH)!Wbd0lK4Yb+(}BTX9)ej$f5QTdP67b?T*gbGwL#aG9ZeB( zqS(6y?+4e{&b^N;e#&Cl*d(IgBAnzF5&#InN)g|F85QS1_~Y*mjQxc8NrrTb>mNef z)OSdD6yzyHhR4|aWs5AnW25WiMEE;x=Sy(@1o%0|*ek^EASIZ`fl6ouB z(4t*{5CB)&cq(qWJnA;II8c^Dn;PBPs~O>Ix8M6e7krxn8C6-ob%^{Xod322;P6ht z{y+6T-Ql}XDb=S*uRe_wU@C?L05xi!Y^zeMYM%M)`e~+P^qkedY>)`}gJdlNtd~8& zKINy|x_?>!i~ILD#p4=nJ^oSCw6ASv<*T(3G zRgN7;dfW7XST(_1)cwKrK{*=dai%^J6|)v+HScK%nC< zXP6U8?To>dlWOSZ&K11-VZ%7q^Fb5-->@F3C>N3fNcvR^^VPD+@NTNZc*#Tj48cid zWl2L=Wq_AKKs8dVlW0x3Ry-Tl?@|w@n(jjK1T1%!|4t$a@Yr7}DO~YV8+UBu63%r> z06gCD+io-4%|`A!v}Ios=#aEpo#@BDvy;{Fnmc{~fOc+x^i7^x({}9BpZ@d&>VS{3 z{}0seg$W^Jz(k4=wa9H-b%FxbFj%T1vXw-D<9>-bc?IO4UeBg)T9KFld3?J+SRS`! zV(Z@^(%zdGTWz{*gx#BTpl2ms2RVeUzG0!2YnEIO+i}`=7T@ntOu*7CNfn88uMyry z!0!_2H~(VtDg*$=T_YKL=h+X~>NF}7qV-iyJOvRTLq7pV-Rp$5B-EFS&|az`<<->(|KFxzsEazISt}>Vt;H{LS*s_zxEPQ{;u0J(ue={ zLds5WoU;@4oD1?Z1`!a${zXB4`Yl?FvI&{T$A1IPe-T@d|L4S(T}hQ~4Pxec_$d}A z1kYHJ?|z$gbkoV{6-{vHr2{hP`9bDB{k{8lDVD){YZDdTqAlQNutqrMdIp<~ED5a? ziusWpz+DZepv4SKks_x~pzD86=7!AyYqE;`hyGvrR#Y^^y^p56vf4U+1^hw97SGHw zR46ua0n`lHr+gHgA-zA;>ps7wE={{DQ9??{b*$5MC5-=EVg@kD_5Lr=NI zKJkf9JOcsnMb3Sd`hIGc(v|=qrf&&=Vl3i(lf*Zczku4bjj)DBsh=Rov22(=@f70p7 z=x-i>?pIT5_Ex5dKQ~EzP8_$|Nf5t`)fDJQ+x;o)-oH!)ibU5kQY7e4IDyrAmYOQD z&%&0ZVc#{}`>Td_B~5ll_9XCWK`&MpBUZYYr1^L*oWQ?-`Z+j$xPH0xO(Xi3#6%x4 z45Z)r5fb~$_&~;gO6xrTj)iYtv^1RmlWXVfnL^e^TUiqOq#5l181@cWJ6|N@IH`p| z_{@@J#I$eb%61_~YG2edwFtztzHfwNTk&~1hqq`6sUAe}&t-e-dv5Iw`bs@koWFux zZNa5h2td_zZh%N`9N~8N?-;ag55j%&_gAo=v2fGIAp~aPn|7RlKN9=Pp2`yd{q(Zz zK)i}DknAeiPoVdg?tdRRB^>dO;EW$(>v4#-ySaZ&3*j79?fc5^j(r^;+H%-H=w2PA z&h^E2bmvxxUjyL@0Ivq{1DN}Fs_DaJ;WV&EF+0|ZGJ9=x)%G2NfD z^Q<~qlRS=iD~Bpzgqp#}HKlX>1}eLUh1Lr()N!S$k;=GIw`{3qnF@=oNoZt<6LC#G zaZ3TjFV5~J;`ikg*8ka@RWbCd%gR3?mpr~eK(GVk4&`Ii$;wHu1Vu!v3rA?LQ{l0& z#rYqWqINR#0)s#N;LAiPCtpE*lY~bNIQIlgPFG?!S&cdW{v=|5xpxNqG5y(RUuqr59z@ciG9ubFR9lPj zvMtAJR?TLJ`+!%20zfHWfe@wUh;%kuovQsVpg!BDFY5f)=k42<%d0`(>1Bd))dd^L_5srrxKs~f_3zrEbtMUa7&+#j zgXbbf-T8fI{J(7D3aIozjm)+i0pMq{W^-qCuWz68`-gUWR3rfEKo2%FdYv6E#P82} zB0z()g9spt)6*Dre1YIVf5vbB9kqJ_C<}N5@u8WD7@RfAt5#V@4ZyyjeM4-Xdu8`W z>^zHcA+3u7NXBDD`zIrBJ9WThX%b8D6Lt-eyW9h>B8Js0JMbdQe~>~L@qcc4(cbmu zf{k8Tuv2jVr%Q30ZsnQvi2F(1vIgJ3fKK;6oLMHFFILbK6SnaDKeh505&qy}n-e%z zC@Y;l5FOi4k(s!E{M7C0>nz*rmK-Al=oCPKjB)Wvz3;$#s^=Hfx0n;IBH3BU+4?`8 zB3A*T|LONz{rf%up@bw+#(kqF0)!~!FExq!ZCJ&N{Tbg7G5sUodC`S+KEGo2-ynrJ zzy5@c66EK-#p5;!=Pw%%Is9p^_ggeSR*-6y@N&5ZxAy;zU9^A5&RZ#$x2x~_DJxGL z!-$qt+k_XkO&XAb7(&)iFCq`9WBZb0jrrBw@5}ePz5^oYi?oV^mAuyt`=6KCzl`)x zT>nP6VlPjX?XU9KHsqpKm`m9v;jNpa5ODNF z`gmdkf}ji$fC`I=(*F!){DDVt1^h{jKx?DmBDhu?BmonZqojtFGr04@N>a;xCTJybnLORwi+;z<{CtOqiW`h zU;N@(wm(nZn*iWPJy8=#k-oxAmL_f~EnG>0>8cC#irz}lVD4lh%b;Zf*Om;(egeO1 zrMFzyB-cNE!M!MoZ6L!s0CWW3|54)VPi&FB5EeFpib8xLPLR%^YZ<-n0@k<}vsJr_ zVOMpO^t2QB_zUr)`)s-3KH}~udoQZs_kRDXor+S32s;$svhYY96##>Z3z<^J2L0Oa zLx+65#*Ajlx4(&|qJe>3eG8+%l|0%D8ast?PAwCDz-G(IyiogRoUXDF1&{8goFCyR+L*;ZZQw|8hvLO30RSD zU5z(vks(~n;Kh-IoR|8>8I<+givu?10ldv|`7GoVaBv(W-&w&%BmoI0_DAA3Fi_;7 zz-#&YN0@sd7xq`kA0zMm*WJ&zaRg$6?WljkA;Kq~2oTN@0?_JjLxAmlPPwA0rEtEC^*$Bl-(0w``Xw3`g_0kdq2hTC#icENdlNK;%vk1 z*wGS4wLp|D#OJq~viBo)|01t7*#szFX&zD6G(j%vh}_qxmutkhLK5I$`R*Hsc`QUB z<3FtaqZQN<^_WdGr1y^l>Z*?8S;J1@s;s#QXDn;(t+8<{W#w`UxBvh^07*naQ~`YA zc$CK1i+1hSPNd{ZuKyK`ugwEi(pXQ~(fC@*zI}jYD6JZO^sOBa~iV`A}Y?6cCfBLFM;9%{&@oeT(}~0Ut5D?sZq0i2Yr_AJ$!j>X3iu#kcQ&3f!;`j(9&m?dJYFk-zYZufgKDg$(@h?N2|XXO1EP z;McV8Yz>Ca`9aZE7+O^W=a4^JeQWGje&tu5eBp%`evAE&QQPb*dpioiNj3mXq!tER zVSsrQt|puI*K-wnbA;eE=yX?~e=pJMKxj%z zGa7LJPKPZ~_ArY>{0y7i*Fa<;0{?{G`6{{MS1odG#iFz)l4U#+^rkxWeide(v-U^q z->QbKcqwOvH$Z-s5o@H+S@W5nB&ZbJ{=^B4BQYkHo1gkh6yPw6#Qt#nl9UMfN8k90 zMV7DI8S)JL_~o=sl3(Bil89$2#|ZL6AQU&wy^op1;5Fu~4E<#7zlc((fWhDO*rt6c zcg5zF_-Qn2Z$9;uZJvhc!5gGLI>QzsKp;Gg>H}iA1qa=zKpX*9!wC%NX4q==4zqY@ zz*eM%ELj3;mj3!&1dbvZ7D4`3_~O40zh-N(mR*}ZYt{3QW6+qh*3=n@8|)i~ZM-?m z{y5~%N?{N6{dn}u$mbu<{|WZTVq~Rct_5*a`kx?z*O3@;T;Tje68jTTGpbnsA_n$n zR)p|>OSplpCX9|f5#W)(@JT0*Q3G}CXCAw*^xtrQ=Y7~7H3C3gFTVKV+28;D-@nLU|0{m`EVXNKA%Y#ZhNzSY6(vAWlK?IOc=4X8U2om< zq$CJY)Bq6(fC+*Fg_CRKT*v4|27!g+R%lNrHPnCPo(~)J2WJDY0cX96fmq3o5%zZu z!M`}3RV=x+eH$aESH>dttto(b4#MO#fKM^$W$fpWS+5-A0F4wkD*`~+LLLfB7c7)R z4S;MSl7aw0BH=Q~4e;op-NN8Fqd#=oA_S@nNh@8(FtQ4=pToz0?t4If_`Zu1K1f92 z#Qscg^%bd{!`I)iDAxXyYk7O`@*MvDNoVap*Blur$dBfray@8HRQR_V+H`Z|5=oz4 zNnVHh#~Wm1#+GNNtaSR_Zho|+=FmKmolHV%4-`s`4U8iZo6}b=IFeT7flY8ndVu~1 zvjGtQFTzLCj#cK|1)N}4fh?;d&sc5dEbf~SHFD(~hO6t)Cgjn3kV5@F0RedyI5>%I z)C}&@S^WOJ#s6Sm6u{~bVt?uV!)zm{aTNpL4&`5g6C%P5T!-$;F^vMl{UCqM=mVV9 zJpBO5Q6&I`>{WcHYrC5W@W@{*k3;@!ofP0>AN$yI5CDJ1@kOczeec4XoZ$#+fDjz2 z3lgLW1)_2p0|AcWIQlIjA!HLEl|V|i0a(DwO{zexLTKn?hFbj8tTU%eWS}XmTdP>M zI&xV7y9zEi%W!8fw6>BZRy~}5D+}l90lK&y5k&oeYVV&R#q>}sWvh}U?UK{kiP62AZ}gJT+unHKJYqdO2t*6 zEh6q}T+{B$p^T+IV7u^aj-@_UOWLj3{x#Uq4f-XxQGFA9KejJzm)G@h$?5$!h;6Zz z!Y(GACf)_>LArl&lY2Zlc>bfm-FiSXQTl#~UB}S#OW&WCTQuujT)!Bkev2Q;?a?Mc zNQh{E&V$QID7(*qj`v(-|Ife)A7CqlFV0`p69AqF(2VV@dbO|Yx}xJFRgNM7pbqvO z?N_lM2yHtDX*Us|L6s)**iZb#PfUL9bD#U??0<*4XAvJEDl!aEZzA?@RN!VRYfcs5 zQV7=wR^wi|=Ob?WK@&X*!jAz|bGY86BL(|ek_2rv;`SYa@qDg0X^T$UaNDheop8Ov zoYr>ZrbS*uR6PFQ5=K+j|0@B_E%43Y$=nl!sIbqefqsb=a>tSnIhIXj)(i5 zRAjJb-0?1F`H#*Y_qA~KrX|L%Sn_=fs9#DJpGK@J1Hk*`0?4dtAflZ78ZsfT~HA-LHbl)z-FH-oM zp^J7QL=t19O&3odv#&n?gG4k;+vfS_tUPlXVn?EXz@|6m9Jt{R-;FYQ{=USPokQoJ z$MXLJnX82RB}NK_Kny9UEdKi~GU^NT{wRFl_>=jQPW100|2gjej+5)33m5QS7Oyk> z6OPyq`TH5?w`y|dzK)MfIm!fpC+&RaYb!9I^V$meYu^(A8dOns`sV6i{^egj$Myy4 zA5(vZ+PyHrq)`k3$em4qe46nuRc*n!JF8N?xz8d|myBH^_!rlR9ebRZ*9FeqsK=p( z1J{=U9=mrdq+jQMNIv3ljkdW2B7+*jKuj{PO(Xy}GFiKs2Vr37RF|j|eXir^7f4>K9%o*8b{(r8iyI zYkz4}197(W+8*&sr!UkmJ-5vIg!ng{O@9?7P>IZ0%K;(4{C+)Fv1U5?|TfQFMWRlbl1o{>t))6pWr&4Q<$s5VkM~Fy>QZwlXTX3_gAP5KDp|134mJab*T-_3jcCa|WPMf5?HISH+c^oNvI zhJX5fpP~9s-1Hi_;KOW%8$6Ei1b}ddubNrD>aD)A>xyfMKR7Deqe=j%e|?7sEBV%d z=)4BapO*+Hm>stUSl^xg;UE6-$Nu(j|N7_I|LOKMY`PRZNwY{{d!ha#aV)!~2B^Y8 zfT*Mj(A$*yRhRZs91p_9VeXYAU=$sg++QZ){O2GB!aS>r&(xaY1E3bTt0K&WJC;*h z$g-aBx-DvzFvs)2?iNuBS4L7+AeC>Gt+V!5Y<~guyL@$D?UrGs)DvW_3$>Q$V#0vJ zDMrL}iSE)U9&~&BtWv`nRw4XWO%)eEqQKM^u=Xz#+rL5xh#qoofiw5$K6iUqj zGIZAd`d;RU)E&FOSI18J!BP{_OirRwI>mhjq-a+OltffV2tJK%D9N?`j;qGWkCpo% zj+x>buTq1&6%aH8Ip&|T8!FyG@cp_){SY90{z7ys(A5$_j7qG-w^K=C8%)_+CTeR_ z)2xRHtFsmq^eXsHO~OZ|*B(%EA97xz?u5k#zD)t=#Puu8Z<79&=)YfgKaHWr(`{i2 zoX+3r{UxbI1%PyB+vQIeb}yPW|BG+{TZzgf%JoEmaE7nJlnHQ(_B$(w+sE2Ja^6dpgCrxm*xX4zX0mKOak;_G}-x2}+h5<-*E7Vi?-=~N@9=DgV;$9|i zz`#XFLlN~5t2^#`ZNXY=*R6pkzy{pv%X3d#66^j7I^B(D--oq722Mi$;%1$glW*S* z+y`#V9yf}k)jAS!f)Sft`WB);)(WJM>lXht$VdX^3){Y-1$j|duBau-NVy8BD zmaxCvFYe#z{?*V&rPm%v1K*xR-5I3!E!lh0^Y&zF*+oUoaNa9p7`>i{U(;l}!idGN zy@@6#+T4E{IMJS$ZXI@?RLq3`@iTw$nYwTQkJAkD)pP#><{pQ%0hBvdQ+;LE6&)YR zLQfs(;yYfW><2|#4VcdP0TkITVnBncs=?N`$A0;jfBAU`fInvclhmiFdlVkWgpzxp z+)G3NG@Sllz(tSuP1)o2Jx;5U@(dWmwMuaSj$^zf>)0{g701u~n{}~YcUgpBajSDu zfHHB}39i$sti$oN>>aHAZ497}dy~zcW-G)GyX}GdUB0@v+uMC714R)kB(MqLArYS2 zv?%yBj1iX8{i~brMG*y{nL~4w#<#YFYZ%>ESt7a5H8}qehJGi{nw@w)(D@7TAEdRv z|7NvIF&soB!S#n0F5>og*}@ofRtb)91?ll_2z%xNo`RX)A=>-VY_| z(-F8Q5Wm7Xhp=5}#rY15_L_2C6lX90{e;B)GTUN?dxFrn=T2L%vXNvYe*#qrL~?VH z=*}FM@rbD+{Tkz&_}?@1_wUp_s%}-YBg-C104hi=kjgC}1Hk!^MIJ~1beqfM$Dm5o ze;pS;92u>Eq2_n!lQ+i6Y>9DW=+vl%=D-OGWlWUImI&c)1dbl~sNAs!6zy+{Fy6Cp z`!neMPvHK1JWfI{2m`rAdw(jy!Cs4>F4`*Lk7E40NPo=Zh?BrEulFayzl%%ke+2fw zpGW919{GFxpjqW{hqk`zT3^}Sv9IGJR~{4sz<0bK9KY4TX>NJsFBIaX0G&kMv!Ge5?9;TmKiU zza*g$kwTn>aENvyB9!<)1i%O(vUWyd2Z{XKvqc=gy2_>UMHnG#|5^!sH=n<2hM5&8&oyg|U8#TZg8 z0$fEPszn6oz8Wf#I!H%056hfcrxO*|zdAv`k=ojle7|B{I6{a%5y!u~4esra{_NKS z>N2JF)i91=_~+95BJ$5epe7{pr|)&mpk3?klUJ6TG+6u#4znM)ZucZ9{7J!lngDgT zL-gOt{d*!nAh!)6_S|yG(JV)u0NCB@exNjHevWCYV^0JCY8(-uZx;~|`@6sUtLN|m z{rrbM^r7G3_}8d=7N!?KmdOUtj}T-co;%^}0GhP|Zej0mpXN}1MU4&?gCYbL?0o8m z&0xeejz@ry{!I+c)`=GQRkmA-rP@ysf>rRJ`Adk6W&F2ht?`piEbD^QJoSSFtl?Oq zU2%s(4ieu64eIAjgIz0(ix0bW+M&`-aM4?&`~5bVatmb5Ejt?k7y4Jq#Di)RT_i-( zETJo>t7?mwB3uBe;JQ|eJZ<$T!F|Hx)}Y^-C!V2?KxCe962jbpCWI8TCzs?BK8Z{Ao%c%nFEk3 z(xdP$`xF0#kaYSwsFuj5^C9iu{dVnp#;nLAC!&5V7kdCIQ0CN18=5Db_db}A;u zlW%GAO%2v=G1{~O$$jdmKh}_b)pLv~zqfKoKj8kInnQ%pfla#IU-sY}CqVv>Bi>hr zzgc|zKajp*Cm`xY2pl7KL$x#AKDbpVl#!Z@i=js0r ztiJ}#|1sVyU@aV=t?F(Gfbd3VRf7j>G&df`@*ofZy9dM{YpcQ2Z198FNd#!%1!7b) zAO7%%pTUUle`Eg_sIYi@6ej`T77%e59eNbt(j@3a10boilP$Tj^;!IM)uNDJY$^ee z#4t~(Fc+%h1apbl0(Jnegy7oz*WKwIdZ?~-U(dY8THF*WR>pvG&yw4gfb#JtvCcUa zAP8Bo3+Ug=A_4_#c1b8g6{7t`ZdxpJ#ku~)(wK0emkkm7|Da0? zGHGP^H+=%c|2-gHbo{wF#QskQ2vvq};;y$j>_03$8YK*UaaV!+hy2&vHjo&cSlHN1|&amOg`1{M` z|B>25flC3ng%#&qZYMHT*E|8}D9j2vfgYZ*^Aa^sRbNAPIolMs9+T0^30J zgcBIM5tK;c|NYnV0L^m!!hPx*UaiP%4Ya3ic2SqBvi z8TH-RWVFcoX0lg+0FcpRQxYw`SE;X~Z34iF_8C9g(26s@R7pl!UOl4g)hTYP7d|Sz z_JF!92CNainF3bj2_Q8Jyvnz&{bTIQ^_kJ@^^rTS(_Pz^{SMXwZ?SukzrPp#yRqAG z*KG$s3XI2X$IejEhi-HJoe}`y302{Y&Z;I1)_86_tcBrvV2Zw_vw9>CrrUw+h43ZY zWA(cVq%c)j0IUDWpZv)SANj~f{)qkmnYw=ggS3QPVN2?$04keT!L^EezK+x#Eu%9} z-v1H1e{~a`&yYc26%poYEp4S{+!kvY`>(5y*(w2pZXgZ#ZX;!Da!cH+2)ijxyd)A! zSIz$XGiJ-z0&f4=54AjSIuH@Sct)}72ovjHj8+O4+$d|&h53~YfE&Mk(b>QM>}Nmw3m^UHM?cI*YT&UT zaYTR!0hy4h0u{E^0AdtH0CW-qS~Z=O!=qi=E8u8fg4w42@#Sf+@613t4R6|}9`lzEZA+&)W4{gQ{#p5}xX-PCTnvss0n#6R zHbC}DoPN<>T^l*@aE6-fE4vR?5#oDL zO6T0tZ197oLDX^QR{I)o5dfM9qW(k(M936)9x>51Q~^KE@mHw(lwi_R|q6f6h|yFiAu2?7SW84GtO!$5t| zZN&jXZk7?2{M2O(r7eM69P*b)^nL+9Cplq=kWz&3+a|&e{YLPgND<@@0i>o$PBYBH z=eKaJlwhVs5T`oX^6I4UZB%6CKLavB0uYvc1hx?=5Wh=ji(p8Gk)G=xW_upSXKB8v zKZ$^;`Ph;wAcaCd1XrIqNsnY;5;qwO<}Iq15Xc1Cu_FW|0cfTfr!a&oe&4M$NFQUc zAU!qXP!#~zQcyS=Y- z4@9|R&mF<9)HnGm1h0K<9fD^oqDTAM0*PD|RoJNts9+HIBIo`+^?#!7TNDAXg&Lqm zWjUd`3tckaKd&b#`n-e1#uHJtO_ zsePt<|9kg6XYYOX*=L`tt7lmrkokWOcfRAQdGnAiM7B`~!Ruf3*k@}kfW}x?-NM^4 zYjRebth^i7=J#2Tw1S8`6VfSmN2}H+|5ep<>Xl4abV7c=dVZYkA?rNu3le(^B2^~12Cjf;$E1GL`VFjoe^vB0Ob~K z4A3X-mo5jW{m}uGOI638f;7`F7&E;U!XSJ3YnqEzAazmfGiLU3DZ`Z|nYmqjBV922 zo!V}R;R*%Imk9$B&l{NC^ChaQ`Y%+k;dt{~INn^}{%MYBx z!j2Rj`)KjsLiigPJ;*247YoY)Xau_W-v1ZB`+W!sZvgtpx$2+JmV^PdziB>|!O#TI zQ7;k%%x{^%$l21tUMEF}k0=@O!wRkQqbm$ReJ&CbMjm+Jf!ja);Sc|F%D;mMM_4>4 zg(mM)Sf#@8p=E4eql3=kYFA70o}P1w-YtHI&NZ@sAJjE7Eofgfbd-ngNv?xWOmf64 z%K^vOCitakyqGn)q!*@bOu#W_vu^j3=%yK%1IGqeD)1ZHN#dEm*c|;4S7EQ(0**A z%->ERv}4#oCQ%pN(zY1Amwea3A4{q!I<3n9c3zcan!Zp2jK}KwmhFbzMRgm4ZHO&4 z?hM$?7MtCynS09C80EU%?EFC)C=yJGrSM7<%QX7~^&U)w(PVEwYC>oHYz0e}|23*a zR~?s&s=U4E=BulKnVUwG;!v8I3+x-8U=6v#)7v1-Uo~{H@R!)|<7v_PlEfwdm6Bd5 z2JDLo-{3v^XxgfWaG*h-J_&TTrL9UzTQ1{Q0PtIRefd@^MgMZI6Vn6GAyxm<8?F8K z!2EX+M=%1^+8-;ZMCq1$Z`&v8$dA;}ZBwYY%etY0~b_JZk zMesQc50Bym)z20!#1NBh{{nU#t43zlh-% zN73Bess;};@clAt(K|u)H12$7bnX=+3r-pzk7o3-OX6xu$H<{c+~g%Q|;$y~=KZRrH_4`WbXStd_O= zTJ8?u-pr;C;ap>Y#acp9?-r2uKi+@)61U!K0Ltnjmmx#zI)n{rrlnp>;CkqFO22hp!f2D-~quCd65M2e^{u0Jqe%;B3M@Y@2)4j>oGBoCZD3*#Qo~6YL5&igDm094q`hZiF{n z(E9t#iK;sKB&z-sRo}shst;b=$C1CiYq9sAFP&`1_~Vwp3s2}W7KcBR9C15xZ8dl6 z>tOt-{P#m2T>B4$zx2^I9Ja~>6%1Ta42(f%Zs?h+cEkMl!u; zbXYraKdNOt2KKhjR+H!0?<{vpetfk{S$>G+0MExsYjQ)!d5NB+f;%>`r#fLd=fgjW zjQ}pwmj46mafR3v`w4<()&DsEsqhlk+rmFMOM5N@q_zLG_ z4151?z~cPSi<$l7+{ZQlw0FGgnZ;T>S-D5Sz^1~$0Mz9m%>NKZeg`lFfTuw5u${xRc2$H%urM6`p103fvULG;L<^w{5@?Nje2jM`AffZnr=GieFy_NPwuZHhms-wLh(py8Mvt%VYbXJ24D=2@W_sN$}v*80VkQRL|%v z2raT;Lz{;D~UW--{WW9_(|NBYnSd^hkAB!($AN z_Ya<_2GImaO^hoWL0qRj6#tTwA3Qp?^!$h*pwV9s+ou=Q{$2gTtD()iKKaQH-OA(Z z;3ri7`RqTKzXUg8@PU9-&4&#^F6Ws~EDPpunH?pB03}G% zPNI81`N{XcnnNW%%y|LY1NizPqYp2r&Ajl<1&L9 z02!zcxDzA5k=|!1>8>jdkP|m9})xuJ^a;#bon$(M9KKm@x9PNnSMV;xzfgZ2i0(b z{($Ye2;T)wJ_2oifVL9UVE(41RAtH>YyERm zkgD+^9RA>_v98%&Cy{LUU&X<|Kvwhb4lj=XI|7*6?CG&p|xBdM#P4@OV^OtT19hasD zeGhu?Bef~V_G0|JcM97@1K`Ux`(J$g=m2&eqn$$-f`GlzjwFn@leMOoee7c&{65O= zCEi55WJoG4{SRRj*pK%)1pyrf=_F|U)K^#%r|-hS+$pfqpf29v-Mp zq6z55mGEht1wDz|;D^R{;WUWDgi=#q^)d&y+zny%HwIH4@O@?0Af4iL0FckM%*RrB zG6&k`rrhq=swR%^tIj@lkoEuF)yzv@SCha#U!Fu`AZ^K5FDg3c>m$-XK3e*N&W9$|GuGJERniR znz}>?x*`CN@)X}EEe1kN(tiJ30En5tv^g(~GUz7fLv zpnrY%NAYOiUX7y>4ieezZhT5CUkwdD^x%UZzL~VnewxfbX8$!|t!aA*073hOhGxDl z-Qs^`Y}+y9AKMNQ`RE)%JB_fp9AGC?7#QcUpjYB++D>*iaT$RD&~_5ki~7G8FLYYK z>NB8+Z7*sDoDQem0nt5|ad(@hql8h{4WafQL89Nw?tuLa<^$LXT-{Fu9%P^oq0V#Z zy*>1n`70}I?f}>G-XMGMF~*xkWk1Wz-KcrQYJ#^;^aD-G-1HRpBdQhA$A9>bU(FAc zYYPUp5C+^mv={nt5XOIynf^iP0$Ko_i|wFX+A++sVQ%cl5bHVw`Kk$Qz22`=v_2gD z=;TNBe=mMGTpE?;EkiiJTiPoP=3(Mgzo5;*_@&)BEf4x$KTcg2>3Gzx-)$>2>~7Y& z72fpXcd!pfv?lM#8efqp+ zElk6}S_9xu+Gm#^eCYZ`)Ck~e*L6Jxwdy>*dR@;zzluRW&N0J1%)mY1V+zi>vR~`s z`Ra$MA1WOKdm0f7XGom-H`w>Ns%HYnK$ItEKqCr2UEDKkQs168B{4hQQ%xP6sU{vf z%e%7=@YPG4+uxaV@~BiH3Dzq>kTfoNL}gObi?fe`;e%EG2p0bw!ZpB>T;Bj*{}2G`t$$q) z`v39ahadh=Z+qL@?&Xmj`U(IMot(+|14`0D17JF$2ngCvGKFS7%C{`sZc701A@dJy z2eMPx`z$wYu+vy)Fs)Q+-gXL35r;59`39T>y_>Roi0%%!WQZ*;GUqwC-9XPlwgb*o zQx^u(7Qq?PJ?O>fJQU>x{q&NzpMP*4xE~eXRRhnH>Zx|I9Iy*j-x=%zzQz{8qiheH z#U8-Xa+bHZeU2QmYZKz8LXGe|)^*n*u#J1(^PFR#Pk<@*7VqN;qU~~inakWt*vq!Q z-T|F1o#I0s<6ftEKZOef0c|U^KX5HFsR@?z1Ep=jz}CZnd;DJoV9H6Lx45CG2&h{0{e-3 z&<1#VDn;-4eI5XiS3YLbp)iaGSZI;Vxl9dLi%qPW2pn({n@vih?jm5EA<8sV~w z5*l%|bOA?S5V$z;jE^Jz*`jQ|I9M~1O;B6KwDdg78y1M;5o|9Tb5r0omvEHfp9dE* zjm2%fZ8AjZ`|VxbnnJ4VGtc$ZZ{xi`UY&+0#s|uDHqABS620MCMbq5%(cf#}jX7{m z3B2+Q%0*6PqAg;CrCe!X8RpNzV>2GAWCUTS(Zb zmazT1r61UZ(&<`=Bm7P)=}mI*l+*_SnXiAz>$d;k zDe8<7Y3)c4FhD)S>BsM zQ;(WA>{q;WPwcyx(xJowUDdx$>HUc>=?A}%z4udmV-(+CRUj&nbS#xv()aj}0J&M! z( z+&QH>EoE?QNWc)j`(rZHsVoY@)BX;LtUK8{ZS%M``4=|t=Kci~?$DZ##+iDshRi#C z1bjuUO-RB!q(#~1{Mh|A(Gnf4>_p1!gB67U&X`VG_A5ib+R?koaew}9MX5G+jI(XO z4+)I0oW=878Q5lB36MAVb>-0!&JG}Ur-zvR&h?Gon&l{-u^Ejl;{AvH$)wp<3eJJ( zbtH5%0-}#8DSR|@UUZH%UN*)(cF|4T_TJKF6_+??$cA;{-e#dguX2% zAiu!hnL@HpW|aUX{~lCVEW6xZjB&Z z!w7-NXtyeK&{7fM!s8|6%vydV_)2{BC_RiLOgcsLV06_b8FFi2HiHn!+cuq#5s$eF zACh}$`sHi!m+z#DjBzuDS3md5yhddVoDu``O>FbCq3kfDb}T&nE_3e|&)Ad6caW@1 z-S%2c{zco?Q8Rq6SvBPH$O#V;@pVTQS@0vH{&rZ6LOj-_2R4vi85~OWTVV=?%adrW zD(Or8|88(nGnB}nsFx!1dmWEN&H?6ujNLC2v!je+gvaTs<~@!R==JuxS{2=bT^L(f z_*Ze|URdu@m!H0%hl32sg71O^+4a1kvrpTt9CvO}KOE#^EL9)fuPDiP(pwWbb7uEN zQdZZ*r36IE$=U8FJPPeX_4Oj#!)^cxt}q-IM^7-_$Ld3k1LA-01g7=nf1@+jwj{7h znbH7Ia%48qD|%RMKP&8$wU*M0-e1tyh^1>`Y+QW-g*Val&39<`U!q#aVPH*b=2n`+ z;Mp4*;2#*mL4;j(@b$!IbD)*33c94blBd@`TTAIJC-abVz?{y`gyVt-my%0yT+h?; z?iP5=nP@LmIEaJ$q2vR0v0BwfSz10v`*M*Qq228#X-6Y^8PtF4ezXM^Ws9j$wm~*P z@(f{2I{s2H?7C^yZ~yco)vUwgYzvG+5bZ}jmztL`)6ZB=x4<7UD#1s>LFC+JZllTO zX%1JKGN&?b^a8^VQ$yolWRWa^6yo72veeEOPoiYoV_Fm!l2|odP~{|?^RM@f=o&4# zQ<*3|&FvF-Cbs>F1FW_SwhD84WJi3%;#-Z;-9KAz`jRK@{{vmfCBTh}48&FC=`^KfmmM8@Pib{fp_;%usF;=S?6>qJ5Ah(m#`%b`jd&xa?s zze1uV$@9LmwnB9v$0CI%|B}4osUwWlMmOl}i%s@95#4?X&=knKx2z>s|D-}Vl-~sU zzuvpBGyi>nptiiq_9$}sP>VAb+BB9NdPB`vY;CkcRdBP>=3FOq5y`wv#=mfXr;eR`B6O7GQGDP9i%=1TS zE}I2X@SVo-)Y858Cvr}OBEYshD=YuMSkT5kwP!^&clp+Lk`M54&nIM3fh zbWOsKvjIGg*QdH3TIflE46+?*_Y6-Cx!rJ*DxDTEi~~J#KfR-JSPVQm&UyFw+$HxO zzf&O{((Rp2%VTTYD1tQr22GHad6iQXrc_qKA3G2Xg?jL-u4v9NkxhzFIeIh_?z@$^J) z`3WpJ8P`^uWjgYAnXr=0>-R1(NxQ@2 zqh?zLaOVD7?vud^eLcgB6>H zRlocVZ`1&z@0M`RJq*V7SG#bi3#erP!7q=B5{w1uiK0^5+gm@!26*JnT3-jiBH!SX z^F#<=+L^u#b`*|(3z-)#u82jcGXcn0#AAa#t`-3gtibbz#i#i%6i}S$zIGxl^Wv#R-Xdb>28yECeLkm9QTPChRvrmFx?Lpxbi>(`$FY zQ6n<(etgA>FPWWIry5Ex>0RL)Otz%?#b&bAR^He9An%G<7OG^7enge{#iY@6;g7HW%;{eFVAW%RA z=7|-omS2MJc)Xj)nbjJNYW%o-LDO`8K*2EHsnY9Srm{DBaZc&<^tb->ZloRd?&_9 z<8NFF0=Itg-r{FL%{AreMO+oj=J1N{8L!SHMnJq+z}TGHknRSsFzMaM)wcHe3#A;} zN9_D)j3_gyaRbx=dfFOhB?k@hci42eONv%{6leQusZFRZooC)YyU@@;*#Yoc@?%k- zcJ8BebALLGiFj{|QJP7uW3-C%$d2Xz5OtO(0((_k%A)(IuJ?RVCMLwSEyv6C$gN7# z;R<7Za%C9>3l%k$^em$3)LMrJ+-&p0M)GUEDX9HlbAdJCO$gvmWEM+|u^EfXfT1o- z*4caVsMmBFHRxgvO&~O!pM5^mWpo~OoHHz5q578U7!g0c<~-;w{(%DIjRc05EjnDF z(8|oiTCFd*+fW^F1#e^m#hzLyV7K$(G-JOhl)58C6?{+sIy{$y^bs`Q!_xe-M@ zb2`e?;{)r3Y^k-+fu^1U;sCsW_pnH3)*(a#)yH6%`Jds_rLNb0#&NG7KW7Ngw9jp$+bnQvd-iB4G`gMOZdH<7DBAZ!4`9V7T^TBb zSQ(p?8y0kdp35m&hyC+|Hf?(ytT^vEyt2vP)Oy?8^10)X8Sy14n6Oho*fAyLC95Hz zo~KM0M@z~sGozD7!sL#FZbN{`{#2{dhYdE}c9^2aRP&Kf zWY2wvt6!Zz4w@F>1>NYB|6Db|f1-bi8oadwB>yVL7UVe}*y{%i1>{j2-(YwG736)c z(77SQBqMU79EH6!5jooer+H1Vy33pUF}DIPxC&7AC_9P@@tYRA2s=Ur`Gfna91S}S zt|=sWXi&$bHYp`{PyV78o*2|Fz)dKc;t%Bud0$wg68Vi4;O4FgK%wU11*ia=KvrO( zj@4E8Pl?sbS2Jq8bDTP5L2rn)?*3WiPmtO?jNZ`>-)YGSEBHy{;=*yuR^k zQbUy?`)0?3&$PJmHxwM@iYMc9H3;&}POdWdPX5@aJkRdOlROJToDKU9?RzPN?G)ah zuGq+f{x=wcBSA7UyHiu$^Z+`%^6t<@PT)bgfmJs%JIT^cpRe?>>+Sl?tucleqrOI`HUB-lxboT@?9`DuVxJk{_Ip*EnMW3Q zk)Ib^tYI{9FL5uu+MUy|hMwj}=54CSpT<@fWKi=q!-Du0B8gnVT_T3s- zcACL9)_?CHK3{md$BB6TO}@Qm@l(S#sF)@z6v`=0EZ>Ey*wO;Zu5Co5&iNVT!D(NJ z6LL>0W^~(M4~}MjioAFiL{937XRoplR6twV(X&}F&+^OH2|1cCjx%k0X6s$%onnr2 zQyRt`+s7GU#=6!h{KzGr zWRi$|EIa0X+Y7SMyewIto8;#ji9tNk27apD^)Y3aHRWM_1=VgwAFHvWs=xlhD>(DL z%t4f6s(ezzYiI68TAG{m`87zd!na;*Vp#1z%KDzBu-bEW6IM%}%BU4mcIOay#L}`0 z7wqV99av;sUy5KJBHW$1x;=3>fA`pnKMHgVl&6Ac*7Ms#eVt2)zm9lBl5?16eE4Yf+|orjnUQ9>eY zpz*Hgm`xrDMfb8YvW0g76*J$8624S|3TJ`GZ-d*`sVACQ)|Uk{*_;(nEFjl_L5+ka zpbsct;a8YUQo<5!i9_^Qap*d)t+7{ERQ)M4GDN}V2`xfX! z>jRJ?VXyJJ$>!xSy?3dq2jeHMq@DU^2cKIMIPUdPN(Xpq$se&ddnnwOxQSjXH00@y zjD{BIX~v}Ox6`v%nBL)5pQ75&;@{sK)lXIa*P7U5nk6ZoyqzfV>!oOn|Ce^+X59<@ z+qMd>!5a%!?K_6PuYysk?;UO}z#s7IoxK1V++H!P$KVCe0Un?%nNb7oev{EJQRQA< zAHN3b$#r}#2<>|C7Ny{JRefm;N-;jDDls7zJirjG!l_q9-p1zVFIlT3uzWggxKb92 zH~!Y>_um&F54GJB?8_$S^rQlX5pJ>-$~N7V!BO+}(vIFwh}-<{Q>0w5WX3?d9gV)| zkdd{mhp#{(l5n3}=$?kUU``q?M@6}8kEtlc$~J)TY>$)ggV##s9e z`r*?`b)y=?_@U3rEjNO~Y48kG6ZwqK;aU#*Skh&|QPKI{9mJ1*WO7;T2N%>^_tfJ> ze%F(62|fE8y^Wwx9Bs1QjG%w2=e>W0SG&0G;JE&tsDNKR_Sr9$7O&CfQT+i)lvtVy z)nTts*f||!bqu3%`Qh0=zd%9#A#o?OmSp-K+3o22%H%W4C;#V65uau3RN}%NNX6+E zy4r1UU_Z4drqKKn>};0T3A*(~hXA?rzibId-<7V*5Na|MLxU6Vod4*w`;u1SQ2QCN#oTWOIU5b0k*T-VS_Pc*TQ2#-Ufdt za6n6b%GNiGkQpvmOs{1oO?Zw%R+Tk%0!m^o+Bx>sjJ2@pz3UKhJo(b>IeQ4`N}L(O zoXO)g%?nAok!lvX)MZCD_>%O4DVX!W;}CC`7)~Ix2>y<<o( z2lGU+xP-f%D4>q%9GLF*ZB3T_gVJP02z$=wuhkFH>wODy5!lEbEKEI-pGp9kC6=X ziAQ?UN@Ng{g5<-kvVW-YVyTiAKeqD*b|Bfj1(yOUy zU7@-Nlyhi7RqMn1mp6mH2pED_xmY^A3uXx0-K|NKv#Faf(LXt9flDt}=k~B4Go|hW zCSIYWhk#|1^Af4Cfa$%{n#KtSyB0AHQH||F^{T+LRV8E^h>>BW2-wo<{#o&D)M}{o z&D*8%mGxBMbr?ZF>Z9^NhGr(kN06uwj-1w7d;H?%ZRzJ*w@Hqiv#A;5l&26N>YMT-rJG>xU7b^=2Z^3BJL)DVv&RGx z2LGvD$?Lwrm1h$t@4f3@xSjc>%I78IMx3sTd; z#mDWsmVD%A33GadXTP|tuWy++a7jUP*E{-EXfRdZQX838f& zFu5rvY|Z_kEb4Sh#9s{)Tye&4{ZWkPz}sVV9$bFlvfEv>+U=KO@l_4_C>1>Kv66pb z4%cD=+gdIY*@#7b0r8=^%EiNPY*|Xj2IeZK-+%nMb5P^H9;eSICLpK=k~y}ioE5v6 zUuGYRS)pe?Y3Hu_5blVzT$!Y|M=p-Tvd>?Xn{5AXI ztuF2ts&@Wpr@n$>1U;n?xs(V~nb<#Q254u)f{-ios?Afx>_OPS^xlp zmXBzPl-mAR_%yimkgo-qI;P(~1ia-h%t1S&{R^l3_dSinEnS{y!=KBpDfjcZ$j@2o zlu(aSx34GN;-T5ko;Y(m|1mw#AQ5YZde#51?AQz1K9_QUmaF87-~#{biDmtbuaR~1`Z%vp9c!LqZ2ZkseHx`mKDZ%01fU@^4S^`XiCVpy*LV)ZR=7V@OS)dB z6`|+OkYYZ)Q*?)K)NDGb z<`ey8#f={oLC#O>uD#5d3ojMZMG_orOJ~+>^N1N zQ;X1fm>V&{dfoB>&5RPu0DvE#DxE^L0a*o@8j1hT(&ua9AyFNW=JvW8hl_U64Aca_ zDiy`xT#d?Is|^9%y;))}2%>!S>SOL7&8Hgyc+R~-e`;2{wN_)OAZ!G%n!d-IS7#K$=SFKC!o)8?;Om zosGXDLeSwW*YH!N&Qm4367343WVHfJZpO%6fc%)j*6>OI?*jv=C+WXpg{pwy{{Xe% zhtHR~jqdvld@>ZNj|ryv&X_v8s0t;wltLZihuu|A5zB$Ib|PMuQ2wx$n+Y(6DR~bD zC)A+7_~OPHXnDvWBB;+tQ~iEOx^)KCE>y7Kmj!Ner@O^+IC^5dXIn?`9bNR!s)mab^|1U=>9wfp2iyRvqcNx6}>M+;wz85!7RW$+!lru@_?d zUHn@w3c4MQ-O_T}Un|j36m(_FHSIQ2COTrL(31WGKVf4vvql7f9@!TeZnduVu)zFh zP5bLTe7Udq(yQN3&V$3N$IN`c9VJ{9EgKVXO#6*^y$pgPg?|!cO}-EQxH!r7* zJL)M&mwnflRLD zu886|rraSQ4d}NJP=2;;k}s1|c#KLpgowXD3%$_`kK0)E0&!6Ua%yMA=_&3RZ&5i? z$p;eT14VAudON!9-q?8S&0gb;@%Frv1#c&;;~vI~u>^ar{yVb@1Pa6R&+1LJL?Cqa zrby`{@~2TRGr&^}A%`gPZlpd)*Y+tgcKF0T>AieU=30S^o|Xnmn&JIKsX~a0`9UY| z@ats~kjn~NRsWOlYdP||0vD{%bDN>-G8lDq@#!y=FOr9DMgCV9k%|r>{uBwX=6d#3 z?drg{emhR7#+*iNa39@|VKIo0)ZKSLO`{rNT>7dAX?PcB0yD5-zW z9i@;}Y7{H1Y&IYS%pyvU#Li5-b|ma$(qi8?oZs6vZ~&pG3x^Rji^whEp!z^RI^!77 zv}p)uL{12pe@!ogiq~_ITJXP~Ks}dFsP|@gTr?+u9!M_s#H4K3raYAVK_ow`U{925oS=4Xtm6@=VV+2qVQP3)p9f=n--7;_B^RkXUf=ZZBDUkZm$**k^$tSG znpbI{ig<4dt7LM8-l)y5w7$3qP<0_aaOeO^zSmrLWyd5_Ndq)%HNC@s_Fw zzzknH-(lRa@K}LpffmA~6spW>#vI-f{Yn#vfFXvQ`y8^=2Idl-euwqyM0}?|Gl<&C zvd>9jKhtIBL_QoUPxd0y6iD?ZGYHRF&0JI>ho|B?`K#^JX<UCXe|_3&8lpe>J(4Jb=5miWr&!G7?JAEF+duR`d_n zpX3CwCcBu(>*Y@R<3%{=1aqS%m$q(bcDFIs&OmGqo7W^(`OF&CXwrg9Iuoq%Mp-Qu z*!&JTFlm#NU`tt~hFoxfz{Bq@8c%tq>|M9|E$(4E9?!P#2?6G|!W*ag`Tfy82dfuL zvnf&q&!*9z96&zio!)q>OGvU{OFZ;1;;%iC%RQrwjwmQD%p*lW(f}mZAwa$!Wf4VuMev2|Yl`U+xq|SI05i8Ng-QRI%!X>G<)gO<7X1;CvBcX^xb)M zBV2v`{lxndS2gbt_nFXg-i)?#W?#|Y)Rn?48v(erey0wWIZ$0k{xgb|_qV@&4I;O< zPq@;)QAHCbXIBE&$dFg^=h}9a)vU*3{#YuLv=)2~=h-VFxv(Cft&_*nwtG68-2>-b9;5h-z+c}#lult4}5 zeHUhFHlb1!L&@>T|CNv&U6nP&y7~4}m>k1LS^?2KNgflz^b~m(gdPdYpm-&U+_4X$ z#8CtRN8c0F5{a=bLHweZ{z~lE(mGLxg%)JaOZkoZcl+^0C6oMtBv2En54fFu3|&9dz*BM;?NiB;^Qs2q^N?>% zP5|D%$=n^9kyA)`P>BsX|3hb>Ay_O)3_5|{1^L%`sl4x*1~ z1<+KIJgLtf^$*Z^gi`M%1H&ItXF@?y7ZJta)8^p-?YJoAzV}F3U`7JK5f1kR@RKHZ zGFAQT>KH^y%ccgnpik^$BzU@W0hyhhP`ShhpW4Lf|W3;sE`ifrMuu&_7!!y05M1|ag7$|=Tk13CD2gnsL*L*-$zn~1z%DC8RJUmOF&3&xdj=I6= zItg+I$kZJ!XTPcM*czWx56=j-MXs;Lp5Ur{&_(1)S^;jo72RTK+`PzNhJyX2RFK z7if*H%$&YsB=M23OFTRJO(DgYM9N6mQgw5}8Sw3j zd7fH402W=UI(sr{X>{=vcV$X^+7=ck^X>R)XKK@S94GX)ZP=-QU%}g5pS3|_bG0Fx zcHZ4a)q65HH_ICM_NRomZRd?Okswc_-#IIbPy+`K%Taec2_qc4xd~yGePvb9(e`d7 z#6`ts)gh~NLvj;zZ#kEB^Klsa5U@mxE4Al4Nr>>K0J}=577~rUVC>9o+2sFyxb~kI zW%0b)ZQ8It)KnZx8R7Qi2}(pCeAn>%7JV7Vk&yTOXc zg=+0fc3J;QS$#g>8r^Tr8uAuL5gX&V+ols=GgkQ8ISvrXoO~KO@q~<&A$xg0i-@_b zI;9Y*dro)xa~D_(#kB98;|tAom36X-j0Wum4I)#M!ZrvwVQg7ONu z+Xve=Z70OAB2E&Bc9JWvdB%CGa1L4v3?HTNBsH!-5G7X7&j`SUl=wfC-PnWJl#1S8lXNLG zDIH2aVo+mSQO_!kx!QtdA;jnczR~(A@HsHEqn!F35NAbDJlV#|BV5dW^TTQlzegX* z>cid6J^KOc_BBx>=kCYt1sUKHF+TESOR4qJImM71w(38$v(kL_2>Sfe*ER!fi>G~p z}`S=gB1_GwI$MhnhV0#c=yT-K?E7 z1N>6rj2C`_J_x@i(J^ge3Qt{OUUA6B>=*E4%(+uTsYJo@EFBvg8V z%jLjfvwGV?>guVI;Hg}(6DV*`UHcJ z#+e36pIEkq;?YzDWp-=Vx5SJG&%H>bP}1}T7?1&$7{7Xp()uWXns1)&PiiJHgzu2c zuV=E}0T|?~#mi}s0}jZAjcWaoJt5CQD&+^DfzKJ4s+WIHjBgfM3SZiq{7{Gh^N~*( zAml@N0?yHcvHc`>=Bt-<;FQmIip*vAKKxjh>1ecqBGYNT)|IXbCX-N%*K!k#SO6cz{%6WLG`ktLfu1 zGrsEk=>Y;eyEc&43~MhlkvmTr{jv+~C9@uz9MMJZ_n4L@{lR~J_<-5!vcsJ3kT6wf88eB3|Kkntf%0|l4(2GG^?so|# zydw_mrW-@*?SjQr%DITGNvwQE1Ue;z0e1V#LWgIj5&J`GO@SM^C3ws{9 zJG*FEd8v-s=ApQ_$i_Dc-xbk-7a&+@={VUBV#_`F~SYt3xc zFL89by1{cnk|{g6;cL9s2RIOE$KtYk!AQAmxD&xg`$d4CQ2$Sz{@)+MIxdA@Qv+ub z7{{i-StR|ddUmI@yaRLX{>vb0oKP!;y#ZF^GbQa;EhM#I9|cE%C(_|zJx-ws62=GV zM*aKl0?42kqZ>B*Xy6VJ{2H}Ln?!qWG%%!1e@Rj$?AG#0{hamcaQ^LBPcGZgjO^Lu zj#5Pu!=->h+*!df9!EY*RQ5ceDsi+fJ$_Qg_mcIXniuib8#)7{cQg4=i61YEmN5$9JO- z&^Xd?{1i;kV7P(x7bI2=c9MKCnP%mWT6U7WKWDtRS}t{ock+56bT;s$1Y7&~SN6^C z47(YccW}yN6W)V?rc^C`DGO^sGT#=5W8KZVAAPD$Tv9f>Gp8U9Sbd)8{l1G29m=4Y zPYzh1o6zw=F&50v`$-D+#yirm1doc#L)I6g{Kj+@`C*f>B5n9?Es^v_sL=g^_n7w0 zf}pzIpO)H{aSpAQvTPqp54TwSAszKAhHjm&FC>1*_=eX4hh4LO4*hB@uvO~kNg3vi7SONKP~Rnp59pd#n>sgn3S#JICO720lx z5>4_F5-~Q*j4%vc=ZMyu!F;YP=?#D~YkUwj<`KakzX;9hj4myUlis^F=?YJ{3^c#o z6ixZo(OZ^>@&71x?<%jsb6jUM+>1>4S-*8h4q*DSM~}tidJ6go9QpKewEOI~Cz_0! zXCeGa(=i#khC4;X+1W~7Imx=BJY_qUh)Qf2vkFGWNk2GseaD(n8wIPa zZubGTZ@ERLU#fPyEksZO6zG8JWdOePtK5+|z~q|zLycALYE>fce}2izL)R6|Oz<3(g!y$;Csl^l z;@W3?UyF*g)yZOGn2?&fFpN)HQd7~oo}Ume)jh914k%}mH|k6;Tt0htsG5|#`1Zrc zb<~pgZH19BOopY@%jU%|Uqfx(DNTQ)bMKK;;lGBFD5su8qaUR_TpH1mT7OE6uCKv0 zG9P#sqv;vLi5~R zG?e)23%G+RyQ~`ka}3)q>QFKm)#6CEP@aO2u9hvjJE~38LA@nHy!OO_CSLe#$8{A< zPk!6+OiGU`_4_P1_S;{MeadI03)}`Ju5nGNV`8VOG)y~ivW1`cc419XgK2~Btj14V zvV7@(20kw`9cD*86c1qLjauv(ZhMiYozehtxY=QIMmKXcwEVUv!?9xS86x6*x#^Kw zUKsV?UF%lgcut3D)o69v*|rxOr0botcdQ1{zzXNiX`{n<$F@#7P;psAd8 zcIc#n8P&ER)xR91E#p8OATH{3_=YNeB)B7u1zzF6M_@nx7CXmK2Fy-|2Vu!LkvspS z_$1&IfE0l~4@QP0zQQ#AW~Lv-fIpgAslWKAzUBPpj5x`ctv9NNtJd5@9L$$mJ$fi& z7LRr}&H*%1Hrho6iruARVJ)kX(2(PQTpAbjPI2H&prPi`yh(F-!otzW+n>q#)`;Ci zSco}(A|gA&;a;<71~$F2+n7g&8gNW|O#W`=a_siz%@BWf)p~4$eZj=jBc+J5;nG>v zct}02&8#?rrua=gWbkA$Y&+?xi|wpHDXrpHnc1y4Js+(>Xo5QRce%a+~jw$t%%_fBY5wP7(10d zit_rSFnXa*v%YhK?3T9mzqprMU-J2UJKs&{6{SyI!-A%;KmG>hkt7bse`-cWphNIt zKvsKB)Oo5wJw8AtFmvN~C*5*K(ma7>80%n!Wp##OvySfrwA1Ts(8+3U_^y4BB0vE9 zZV@CIW*vQe44SBleUltDG{Ge&NhZ5i|5J`dc5-vkY>PsZG%d~~02sTGwP}ow^Z#;J zaGMD$M8budKGvrfp_{xS6q*f+MkRA1LxIRi@NEnaEQ${aL-A`rq%3P6rz%t^EA>%O zsmP?Cpta?7j>u**gTHvdZc-@GkR6y;etQ1lDcy(i`VPoxP4mgL{k7R~X=5ZgGUNKf z(?2d+{CI^Ku_fvoI%E#LL{T2z%IkxX#)hu5xUQo(egJt|=CNFM=fx-of=XJ}Bzn8h9a=nxFN4m(j^1^!2GOmDOWBi+gu8Ig{R&dkG9=3A` zPOx--_Bml)~PPC~7{Oh|r* zbRuWCH^iz9YVkgG!hwOV>cn?G#vMk$tGOFwnp}mBskDHSa2Rt0xp*|f@TtpZHQ{B0 zwkoG(BLHW55JT~NZnQ>wW2&|@w%&7(ua$a=QP74glVOBkdOJExmWGn#XW53?{r0y6 zH}^^cwX}Q?dSD%1kZ^z+b0y?Io9FCRQwwYiTM3MaXTIvi>4~!gDtH{X?cke4^X0iy zm5x}s&c&mh<0li6?i`U~fPphn?-A^2HXIh=1dHS#Evgf+G9xti?>s!BHwz+cjmw+JNo$IBB^uo1!c=CCwo}x zcd5yO?CxNIKG5@a)I!wG!t~Mb)S#dUpAg_v0w>F(QL;37{zuC+{M*$o-Xc(Q%fo|T z;^J(eS7q4NW4U>efi@m+;KRz3Q-fTw(f#Gg^Jlo7fDS@fq{D-33%ufi-f%(dOf>4| z!A;4tW+tLT?1`5A*~?iY_N&2dEkLau48akux`*z?xn73S=|EF=UuSi02t9v7_i$T( z4#!UQs6qX7H~81-?$d5AlGF9?YP zm8C9IzIo-A>E>1DC9!ZqHO*^Vecsgf9+*k_^-Oa+JluTeDb&k0QJHn=mPOYsetG=& z?ix#Yhd13+!O(nII585svM{fb+%}4?fx-*xaW_=nLFC#q_Fk{RKfQDCtvpoH(=Rm1 z!cIo>jblJx?RpBg_YmT?Cnx%QJ9_rVfG=vsuIu^${aq%Uy=O81j`5J)s#1G;TYqSN3 z9es!0yD^;_IHSKe>BfZIF?A#rr17n&&H+4$wi68TK zKQei0sVhEi4H&(D>9tXs83klm(bKe3@xK`O(_n7ArL4#3SAxc>YDU>yJ=?F^QyK~` z6a1ix2~?cI6C&tDCo^T*G99j?ba_Mn?ehdL9ZOD#-}=?&x*M8oP1@FfT+3w;7Jn{@ zX#HNtD;=2g{Na?a>BAm=Ns1RnbhdT*Z3^R!ck>mAB~Qe)U<9O$d280OK1M_?M>Zb7 zSbLZ1A6Xa47gGG2&yjBnDMXd1HMKq$PeZE-BqK{!d0N%R$rp2u7TJL424+16wxyq%EGX&$p)k;#$%K%a$PsBe<)Xs5R! z^>*e!ytubw49A!TpI_Q#1dfpn%uPzPd6BoM zS|6qb^{td5;0xmexg|}{WHn8)EOO81XFCbMXCraz&;Vm1Od>0iHA{%dS>_epwwx9xvVG3?7E(St9VAsrr0aHxw^zURptS2L39qctcYbT=K@0hy z6HjwPjK5Z9T+j5C`>;i?rko{V5D(`4Tm+45^@Hq&Ww#G^#&zOz-t}Cjt>t^;VF5GP zy@QZ|NmUAP&4=d6#wkcO7VZR12H2ILq-@VxF+Pp6zAzM7I7ej(xlEXZjbn&*>S81J)u0 ze4WBw5=s#JE6;Z?A~u7$4*4jDE?z8(tS)M$G^3BxzvHfv?*XF^rG!j!sDWUaM~0pY zwjB|oZ%~nj4H`C|+n#kR6LR$cohC>7vy+{cw}9&PIR&kr@>(Jc5=?Km1nCS_I&6&P zddSy>ZG+vz8d!iQKwGl5E!I-nJE70dbgmf23=U$)-i2AvNODHF?>H!f!7_fU9_aoE1CE^7%5wKeNY&NYJJ7eTSjbNTw{!C8GYvS9aeo85{X;rg-ohU2q@Gvnn}x9>8QhwU|Ix{fDaL5crO z_s+|{c=3~{&_kphTO`GrOw=Uh4FA0^NqmfvwUapiQIKEBA)F;H?eSTU%7UF##i-%0 zNSX;+A}Q2sjM2lMvp*|*#5prw(KdxfRQBOuLNa}nmzfwOqhU|(K`IiQ7(Vo>)2@$F!5eUm1xOvsuio*aI;q6{RL#7%^}TE8;N9frSYT^3@yR>(fO({=f3sA; zi*Yf7cymmklzac3fsandV!vMG?o(DT#+iqpl(-Goyv!V89eoigW*w;Si%0In2prS` ze<~$5H{>59q&Cda;eu9$N$d|;v%6sBzRQa5kZRu0sL1stx9c$;8PaO$5{*aEDabcS zEYz%hyxZAq{Kpm{ZSG{I*UVNhKJ9JSV@WCDL2IX+K|{KcXv_DPvi8PA9#h96e@9x= zFVea@I%Fi7{(2Uh=?u0@Qa*R7elPQbUc9mUO%0_cgoX-IdQ8h!)Bh7mBTlL+L5KYd9!3JCj9s zwr}@o$uHRhl_x?;%etkcn(`4Kv>H_62FbTyK?lv7aRE|6@4oKFcB%%8yu?N!o__>A z9a;1isn?X$-RNKjg4uTDBK8n4rp2c@g+bY^*xr=(l(&M_X;s_{o<| z?y{N!XgF#X%K~K~pDVYqz>d*fqi-5YnkgGEyDaAYq~)fBnq6?4^$hZVfA;$4Z5wCB zjF6Hm+)vv})%#OVMh%|$cZ~}_Ir}^Si}zWJyy?zIJ6`O{)&2r85hpQnN!Z|<83Bx4 zguD|$3jaa+hM_<{4XMBYbD&4#Ug(4M%`7&ia1mIq5!>$11fpV z!}VK1NL5QywE-vT7piEzE&*=~)$8^5(}U?titq-Ner45uU|wamUg~Q)vyaD!k&7QO zsaEaIPo8IIG+TklbH*=X?JoWcPP4XSZSrMste^ZYZ*M=h@FVDNzD#XJ6DxdA+c$FS zFe_zM(O2(QhPYLqM^Vb7i}Kjcb0Db?Gtjztb&x&X8_IQVSTxYi;kc(shRWHdSWWzD zySMR*w~OJrFCuGYoK#eLqcC%L_hBH7Ljm_o3mh5xqi-atjVI%6aLFqnM;UR;TYgLs z7SMlqJr!7gRd&cK*CHi<|M9TzgR$Fw08GCHpA8)zwJv`hTf)654Bvt}i|H@p<#0Q^KUTiRzm$rqym z^JVvhYTCn4ZAuw$o#V7AQd+XDA5wnSS5YoXR~zG{^a)SiJ0EAtKbdu`5JSc`u6uwyA_#JOpXI`wX&kGhV2G`7#zj%OetI& z(}xqzbHX>o0%rE7E{_~@9r`v)KRZc`MIZ=7^S-6b7Hr) zY-BidPQd9p573e*Fnk?+*(e|=Oyq2eYob$g!nebiO&2}+{(c-V$=a40F-~o#wHj2d zT9D?9D8kLr-sOqivrUh9zlYUJ&-k=&PCe!gMlEjlAgJrI4bVNi{u*( zakJUKv)cGz$Nr~y-EH;|J{nyi_Ke=Jh~|iJRH;PL8RJ-T zq7QTbmMG0e{`a;A?43PQzg4k=88j5hif>1kiaYTiJMlOx|M_)aFBsw0sOZz1EVQ54 z$hnt)Dm}dH`_7>B09&ktFP60(_h&{ZoRT>VX9DCr9Sfi(q>oY71==W!BPOR z4j`n*5`Rf(wUdBRG_jCpUG)U3*ChDRr;AXo0dfx-6D$!*7NMoz2nTO^ncAMyql-NU>$tJFuh%GL(z8HdGx;v9G4Bng(3l$xDPKZgwl zq>(klYSQ^rsXpJ7ciPD4$VlhymF?4`bCxagHu>gtpr6I2Xw_SUA?h6!jGrGs!rDBq zS9Pt{AO_vIdrNn8W-RqCqkHmsTNYb@h4PeKY9S0W6BQ0QEKMQQuPwPS#}nu-B)705uQY@TaxhKD(R zJ0{gMlR%>Ra=!y^NrV0eWvC0*iG{r5JiGJ!kcW84GiALbadF0$)^KG?ibBRd0MZ$%|0Qmz z!s|TE3qev8lI3(y!f3FKED@`uf_Lm;Y7i$^G_b(|dCnIq-$wtn`&>Bx7p^rww9#F# z63`>(L6C*nZpp0L0IhF%DOcC8#>l)h7JDN$sk zHvlRu)~3nc7GjP9LK%HD*+2#B7S<<)Y|IOQQ1Z50zMX|CKLDV}YQDS;iobXZwb2=O zLC?k<4)E(vhqEV{5$Fv!pM>f>NWAJJL~{pjaX!aOT}j$YAUJ}`f!n+uE~I^M^lj;N zh1P;o-&iu64B!96=sDdjfV$i_l8rOr9&+F9>9WGWP@V z!Kg(RNY=Tt?614Sw&N$q{=vQe4+cF+Vvl@#8lgld`#**trUvB^Z(`_8d2}e#?$yFS zb#*U(bj$8&CU&dLyexNk?bQa4@3-ly+8TAhzP)o}V9rM!T_k2(hvpsJsQFhA`EQ$^ zC4ghyfc0@pK(*Ou$g?+hUfb4xtm%oM=ex1Kk?;){nf&(17QgX&S<8%GkE{I*>r9b{ zKwB&nji&crV_@>S8A5YN5j(}KJB?!x2-gY*>a1gI1oUlLTF$O8p~Q)SBS&0NY?SSh z+-tA2UnN*6>`(mxrJeBPO~hClMZAoj_WN#}hAP!=A~@C>7|1T5p+bRG5f%k{_!R4v zykd8m%@`_$!>jnFy!&OxRCQv=adEWbQF7w-qCJoySF-I4_|?ya+wTo6#Otb=>u%di z96j)wISNZI6H298ZP9l@(>4ef0suXdFh)_}+Af)NR;x{ets90qf*og)Sv9TMw}leh zJ`02Hpu-RSNmtF&Y2MmB3OLU0*v@|YNMAp%iwnT@&PZogsM`vPk!
z21w9vtvu zCZ^!zR$c`xXWw9FpT;@?AwUYrh4+6jf>Gu+8(ahJ7VJ}$SRYD~Z+%rXkY>+a+(if%$&X$Xg(mluZp#f&I&1~N zV{}aw$+_3xE#4$Jt+2&vWy~8~_SanYZ}s%_5c1D6^G7f8UNVegm}uqMkrJ3biald) z+6T6CB1d4y@v_Kd&yC`0=C!ZqZU9%2*8qsVw)2v(FaI-Ihk`#CxcI=Bq6siu`$ggW zbS-ms7mk)GDp4AC$7BpdG%lktv0=eL6s7tND^dR5$jE58bJq$ZueZ>WtDZ1)=XP5( z&OcU`Sy$PEfr*fTds##tWWfAmc5il(aGHB{brr<;)n~25Ph)FOk=1nrEae)wpL#`P^&Bklt;iKiVhc#iLdH_^r_&xm`wS-Pml*`n=!YnKH zoo1pn>X(q>YqQOG`HWZAji&7$SihH5w6fK|(2pp_-uiSsN37jf@qB;4JR+0qDR_Sa z+wx9~-BgxVJM1B#*nYEbjWZNK$|y%p3R%$h-#Kb|u=q&JdRlLQjAT|8Yq){gJflJJ z_Wwt|8B0y#G|HaiQE%=9WP}dS`;6&1brLT+L*J}JY7CWMc(q8|Ow8wby|{6x(PI%K z%j5;0Iq)XuI4gcNF}JGlG%@YehF4K1I4vM2;N1s`pD)Kxr8@y7@`t!pocNZGjxIsp zzyM>biMh|=57mlU5pn9yWq(yWa60()x#GbeDm-1$1NNqK{cUG1-#8U9%$x1a{YUA5 z;`$@GRPc{l_yC#~motKiZfaWYc@wjcIod) z4J5$KRCKDDZyw2KGz^Gl_)7c=d*$wtW9PQ|fG^yxSK9l}WsvY~b>jkw8{rz1*A8cm z2c?xTT#`;@h?zjFpZ&A>oQ} zlt?@Z1~bTujFCs?FUZTb!dt$FBit;~cS za^>2}dbBx(c&w3{v+){OOb%$ZlF*RLK*;&80}SWRO6#*zgZT3#{_%!ujLgT#mz}mV z3*zDchaCnXvYP~=N5%SAGO@cwkJ!%=rE1)wnw)BbD}p83pJ%tt`A96-`Xw`L?3^UO zbz5x_*c+FrzQ##s$T}s9K3X)>kv|YT4pgJ(%S|uW+*d*%t*w8Pk#bR!=EnSp3hX+P zAR`45(2N!b(cWcj>vHk z8k*RC>x$~>DvkLT6})xyn2eMTn0GJ2tOO7>v+8EGmQmU1>-$;T8^|MIF%K>SYZ4Y+ z)3S$ahC_SnmYTKVQc%{9!5D4h3q=A{ht!Ra>d+q4L|~i!hahs z=ye!nHvt^#&bH_NSKyaFiJ(#K7)|P`v9-H2d_R8a?Z0A8goZYV~0vd;jQk&}Z#c zlj+QbdHR$^8qw1_y|LbETtof{EGl~k8<$%8bKT%u*RyY3PayUm+Z+&y;V6AT@SbHm zCbMbEA6z@Xt~n!<%(}7tA?|A*Mf_3Npf@(^1A}S$WGKMuCn9>{KZLS^5lE~xqT`R)L9Hob z+@FTcA;pke;$TX6vEsH@{*-uHL%Xl;gcg^b^xD+j-G3A{YiCnM=wQmLeZ->ZQHg4oPFk*rln|GH;hHd*9@bvJ_`cB^`d*wiRD$O|7iCx5Lhd{ViChraQ*&8g@=fu)B5XpJ9v} zjm@mn%dtV?&pfkBcaDNm0Ke;-G8bw3duNss;AXzGmaY#(pDunvV-YQ}-%EG0Joq}N z?~2$J=~}&?T6f7W&P;S_HMWvHId6a1@()>^k@mJGC98||8ya%JEDl5ICe-Rq^csjw zdVV=-60>dGPqQC-SyMW5`zhNLjrhdDlmF|Jne1C>u-n*%QpCS8u(6vC;VkrL#Xm4s-7i+`=j2x->tCpWQT>1EA;V8j2z~py-a4qotpWu6=xFGxSF75F zyEsV5fk@)wVjt^k(NS|!1256(XsbT~fk=R-Bp^z1;Bp)=jt4H_S5LH5LDfUow}C&@ z9Zhwf>*;}R0naHx;Aj^RUryi`1R^Z}gGhlZ_}~8uNdC{OB%lJ)|NHsBH_`ym zxS;PkSJ+0m;4RrL1cchgbp(BAXX&-q%m)u9vA5Fgwe(-{v zN4NWHZ&;#M_q)Ul##M)3r(0X`z3=7&HU=adBw|=Upbmb9eU5PE%vz}Y=r-Js96nnJ zwwYtgY_x74=&!2$dW)|T?$G>lb>X5j1~-M{i?}WY`TrmP@2r3)JEgH_hU}nt7H<+S zu(?w~^o=d;#?@$OA9VT(+O!bYdl3CNdhrQA1hAKKU(BY`B#SU4c}_~bxw<-1;al7(cmQ&RkN*8S$g=YWcH+L z5@FLA6nP$a;%3$Q+bi|Jf`-v%I|O5~yKu5|zs5HWdEmFxkD0H^KRU@7hECT)wQ0KY z$dn0xX;Ji)pJWAFtXiK~od@=p-%)6>Xs#V9bTx7H*0JHzc(?AifnN7s zoZo4!$GE5W3)c_VA8jMncXuZ|*34bsj{$QAqY`ej1d%|``Oa=bCbLQBt9>U^(YfbC z-Xvd7*4-x4(d)Zz6aKp&=Nf|BEfgnwbU- zS0#!@Gk*jova9{8=EOFEO_Qhev5@d=NgUuw;e8z573k10Tkmbv7+ksg2wCD=p_r;i z7wcv)h4wHCsd8J$pUIF-nN33<+HV`UnpC#%x3a1}I?1h&wU{znG@Gi*Ik@YAFTe4` zh82BQdKBn#Ztk@3wQw%fuomy%?)I_DTTE?9Agn8u^>y|VGgk0F%1^Lf{l`9B#PyaG zgNn0kpsUhkdQIGxk=(q6etY91+LW5oOY^H5Uxj*Ey}~(}iK_Do5Lk-4WsF7Js^%CkkedOeTdCn;$)@Khqc?_B5k%NYkWJj&aGVczg8^23(;MVXc{{?7TeCNuP#63(lN3TKFI@aYwpSH zwPvuxmul4V4B3(g>?9XGiOcWB7vgy~_tXk#Ad{TKxhL!1{n=?)KO3=hthET=4uzSaUw5pry|h6z@Xi{ zYOrc-LlCstv~coO?FaA+uoVcYl2f=23g2+l6yyQoB5VviTJQxE8YbaRE>P_^jfmqEzav(j|y9pX`X=fv5xL%xYT zubu53{so?J%BiIg5-djFvZ+ax({Q|l`lM`z57s+VKx&A98-+uw*3u#Shp z?}T1TM6MN3UGkITbttqQ@{9v2%b*KoaBHk^^;7*5;q|m@5nj39e5!)oAGde{Tr>6L z|4{5MJ*p08b;kBfJc;)+Iiw|Fbg0ExtUMQi&h>@AGxk!{*j3*us}L)tS`O0tPlRhY^$!3> zWhbS8U85-$rX8XDu)Tq`FzG=0F6R@)Qa~n%mu~>Aj*E;h_n(<`-%VSPXq4Y@>f4n`U&(rLmHRc2V7%{~fWXXVteEf{P9fIJLqAP7P=&9x=)V?x5$V2^ti{cN2e$0CVL@HjV)N~r+C5$7 z6`eIxPad91sls?)jd?59-@RMnrr~meF+cez`cIm1s&?tTQ;X{IL@75OnpW=)Sm^r# zgSx8r>|2nbY8LFt?=RD2+ieD*;BH9QgkJ4B0U<4efp7C@mj$(8!Nc;Hot;-r1Sn3R z<}X*z;!VZG6k7s-A2ia{*l|)-D309LoiR+I3a^g|ujhv_k&*YRIqiLFbQj{odv`Pi zZl4&Z1G2@99?aGaNVaN0K(4%A$EV2Zjr!}K5ADt;g{U5v<@PD2Zc2`4hn%(Y1WvqwnCM2JD>F}MMo!%%diTO+1vC$*PF;7Ev zPb8eAuX>I7oxxPU<1EJ$D?{_E)@N6)aXDyc(?dY>Z9d&m^v~w~ECA3+ySG(;`q)t0 zI?I$Ap6Xlqc>DH-Rj|{Du)%yN@yZB;!~_XPtqzU^8{9Qk(k9eDTYK?cP5A;vjKm>U z;_~t1<=yWM6y>@x)plh}B)v%yVFddAh%jF+Uh?Z&!tdH|=kGkC1E$v4Qshg>=6#V0 zOJW`WIF3A!QCpIt^x=91kPff{`cFD?JXyBm_7dQPn>~1=&>e%Tii%FGKVj&$qwmie z!H#@fdhBWb_dyyk<9??ALH^L9=TGR70pZtDC-ICJ0`WybR2U3ZVLIeYj7h)s!@CIm z@4#r`cUHeFoU~n>6s`A~@^-wlcwan)C9$=BB$=FZVFSM3ZCxH)F_+0U%JoThk?v6N zK#}(%<;^jh0=t2lqkUZ<9|%yA>Y3jnDqPf3kbKH;W7cIYeI6vChil<)WvtEBgw4eEkVg+O9LEsT8v`(sk80Nq zG9Es{V$T@QFK z^-d0w`yf=^)`7A~a~v&77d9f-(7*m~-LnVdM(BiXG%w)@G}WK-U{$au@kB;LB}h5(bdfN7 zwRdYeF-zIL>!l!XQVf_1CB+C_P{}b7$GT?vh%uI5)#Lsft*KRLUNu__=yZLpmxWEL zS4SRn>$=hZsO4fzHWXRem}4*4-I$Zq;ZY{B#i`a-gEpJrA(*X*LvMoo{GIQr4AH@B zex;lAsqaB|zg_cy!il617!Q_5Nbz91FW?*n$>7{d#|Q{^V0n{uWGg*ko62`sGMF*=rW38LHe|i;i{3@6k~Cwzaq};1w|vLf<7xd z#KuIy;g>S>NtDiFkw1^ZMVp@0iE5K3;eL}SvmnITzGS}8**p5JbZC9?IV%W}=i(Om z*O?ho-{K79c^S`$R#*R=eKvM1{S&<}Gyc@|OO=vUeR+PcXvbIN`OwpvsleD%3#tii z+JO7}RW*3*wPBh0_2v6*i^I^+^mzz6AJ;={AOgVof}`7Mqxz~aMsTdq-{^;5t{k+W z{^+qg*3x%bUKjNFi_}>EYNkcesoG8rH_(M>dHP)elo<7o60OAFEVX;y0zcNoZ7~0C z90cG1HJXqo_!=1D_F)ZUjay7#bG!P*yXSFrujch@%*Gp)2?;V_*d&W&FAGV*A5+uy zQ;q2_YQIgrTFK#fjjY)z`C*m#e9BmXs~H(4&{|xON+Kc=h>6T0&XE?vPGNw)TVEM6lQYB?Dx*i~35EaR6$@rytvhHD4#W%lofCFvN zfZO8B`@+g;xWy|?{J@XW=WVXH+`8V>8#vy3PaU7;$noP*9DtYA^#f?%qOb}JY23e( zTOmI3`O+@N3)fG+%lqapBU*6n##Bh!`tw(r)7GoA*JTshzy;IX>I1&bN8u){lC60b z41}2LA&2n+HiviqcGMYMG(*8Z>gx}~FzbnrkM%+o*);2}-K5x18HL+0Hj2(tK6rB7 z@Bt4Gn`Giu$r7`N4U~?F{tfo(7eC0|(MI4jE`rw^&wAxjFRCnMd&A|W+V**!P9=C& zNF&B$>*H4bTL-R-qpP@0qb6><@Mr=g9e%`Wp<&4udkZ+6yuvgwj#Vyx(`A`E6M)6~lK?Zf<%wQUEz z#4dEI|J1oLGo=TooCPT`LAKxQgFjv+V*@7yw!It2&se(mpIsYG=!}N9T+pc++7_}K3@xj;@2>oZYHIV4QZL=uB zSOPpvnimB1Zfbxw9n`MRgm{L`$iPNCK9#h1yLMRYsb5kpm*07Lv3vs)(2M(rEIn#N zJh3_RRrqgnDrRb=fT5&0Jm8!4r7ZtJTVJhpV{;H=P_4^<3W+fxc@5sDG*Ai{UYi!? z>GfF>)fS;zTgU)Mc$pC3^^5H+kdF^KUHDlmVOSaP<9&|!KC5lzDj6tMSVm2;YhsR4 z4@sZR3T%Oy3gp2UVapk^VN@_g)OhXZ=$^y5=To`7WWcO+K{)GF3MO7GDh<$+&{5FA z2?^R{kU{g&khbUAE{3-Veji0_h5>rNXC%cg1(|%U-1t;#BGm{xZ!g;;9_`icqIyY} za}vJ-IQH7;Gr91&olElO10!uax;g8v&&pyIJlKkuS z__b-(NxPkuMq~sYomJXHM;l|Qp3T$_N>->)%~37vR7ceThzkY_^aAIss(Ew-MiaKtcILrV{wv|VHwtY}jW)k?Zw@~_E4V#r!f|yUPWGqgD z5clGetpoQ%yb?fj{$Mzv*5k$r5BKD|a7J}PqUnn~Zx6rTT;9@Hg8SXWm-VQO&$CTl zFh+hfNDoNjhznZ&vByMLy-Gf1hYkOP6ixl`)vtz(7yjYVRS=abt4m{HQC2~uIO*#Z zf^)X*mxQINr({qM>JJ|$DVic)7D6I^MyG8TM;WUW@h(s#KW67)ZO5N+Mi?B@`a^SY zy+j-j=HhR(QZNl-ACf{IbBTs1!y%7u+|yL4w_fw6CDS&lXmYAgdBs8ELAm$CSCEJ^ ziBjHd5=vkFt;^CjQj`qReqPe6=@B*dt@@cBx)8FkT?Cu1rvQW5^fG^%c$2 zdRvM*B27C+CPa#&U)f~6UH`e_K0c+j#-o9k_9@U`^a#Xr?pV658Xe`kQG;)ij=W1A z>wR9}bnieuX|?8*w#S~~3`z~!t+A12tD?~3G$+r3_;AE&@M4cp?vYlc@( zp&&9Ro*zWmML1f#2dBZau)7d^p&}o)oX?Z@{UkbUt|O;i?TN3-j8(y{!Z*2LQ;%qL z!28ZN6N@NUvQmnNH0<4}fp-6~moh$N-%A&9WqIU(?}1(@hEMSuN}W^*E3Nb@rLEO+ z{8}uI`N+Vi;!NRO+wUq0%1GXf%jj)gUhJn5h!L) zw7f1JcMThdb5g-?Dih#@MkeCj!+VE2WR#%ht0oic5}pLihMI$6q1t;Nf!pHx8viZ0 z#{Q*A4&kStfnQNexi+F>K~LJxi`rxp&Z-v}8tU_YJoj`+S%|yC6G*6R2|?4F+z@)9 zAP2L@Kw_*)5*Z6C!}55y!146IL=-+0O2t4(dX#VUYJOD93#rx*i1j2g9g0A~q)<{v zzz`=>Coqw~@#>Tr`17AqD#|ZQ7u=#!SWD693dQmuN)i(fbqp{2!dCu_9C^PZ)=h&k zgk#&^`;zK#_%&|0j*&Rqq}3C8|7EnA3o_1(pzhvP$>EE8aRCME`CRBxg4(xqD1ll1 z45rZ~Xga)26g{c^?v>FxD+&!Op33;_!SEQv0X}3fG-0S;K$5A187l{&IAtJ~LiWMP zgS%FlH$^gYargY`wJ9IW2tYhMx~KS@4Cp3gK{uH8BFt_N!Vls9 za1)Y3!j1;Gfn4Sxr4RgSNNRrbGaKM;UAF(NI_EOs9XW4JN5fBzW%Sll#Q6vjmjFW? z2EiBqG(08lehAIL-C7x<_;KOc87F_`*mT})TeEbmazMij3yjAXwa$fuK(knzAW%}r zGyL4gd-+jc#E`h5PWOYCjmj`4Q1ZANafT7a_Py;1bLRb&iHlZ`qz5sI56K_XZAqEI z3l~22D3hq@p!DDT?$gI?@wg<#l?c4e+1Vs)R{@0Ik8{*xe3@rMf?`o z(HY~llg`*C=|a&Vad~F5+GiRhp!s%I0Ay7Qf-~$?3Qd-QBNYA?K5Q>Z%tcgj zRj`@(hb|>lA5~OsThq{AYrgc+RIS1&f2eC@oP5kN9;5{aLnk16cZ6VWD=c3i5AIHg9caQ21q=BYP4T5Iy$G>E)I40~T0c1=s;#d%IpUvG2d=Nb>8K6;W8l9yVjpRcuP zc985WniiyGhAFh4x?Qr9&V|lGFJJRq+Tzv(l`5oBu(A2_rOA@dSg);mZ~t-Uv)@>PrA?cxAju!*o9tMkdeU3Qruuy z*AOb%puaa(W?5>~D*{A8@$XR2fc>RlmmXD=ms%HIi-tD%yrYI?2T?D{5kc#|Q;?te zCaLcOhM#S3W0R-@=v7kq)hm?W!R}QxT+3TN0N{ZR{-;?A60kAfCZ%79&rN6#rEEpdR`*NUsZL>SuCt(|2}5+afBd%%%6_X$!BMdU_o8|`OmlkX%EUDrojG>y6o#3zSk-RxR8MsNGpe;(P2g`g;ja7V)} zl5;a`3H-eDnF14;^_b2V?FBrE>yOG#_1q*836xMPI}3d{oHYhW)iHP(23i1{_kzQ3 z6+{b378u(?`4@D}?3W)WJaEY^j=E6UDr?~SBpTUKxu!32Ji%%LB`SNM@Hg>=NMG(A zgY0Rx2r!cCO=m0i?1YW{1p5{$3iG=Oj$~7Tt&5S^S9$RtFWG9ZVT7X%pDwYg)ffse zcfQIF4avS(Bvu$8U6%`^xm$9B%|v06OA^`IU#*R>%x9G0QrQ;}de%J(?cS`%md{CTc->e=$qO%T)X=*Ol933CKE(k4v8 z6rStF3}UP>vR*2Wdq=v^>sGy`IxwMBb@UNvP_5Rwz%#}(GcJqaWtQ_jq9><_nIgv- z!H_2ky2-k1+YA#~rmt05l9Wh_Fk~;!j8n;PC#$lDjYq?1`6=%xT>l^*HplfP1ZrQ< z*}|Sou=PzN&&z`Q-CBWD6B&H;1*IS)AaU)bq$}ZPr8TJ&4k?L zv<3p*{{3v2C1Zn#-P*#Sg%*N$(j?p-S4y6v;JdM@>;?C{2{wWwcUV<6n81-SotpP? zPCNS!4WeLEO)1;^Pf5HlR#VpZ*o1V2Zey8>IyFkbZ%*Reez+dI$%7w1v%E6;<0pI% z_PZd)K2*%i&$a}wxbsFz`vyc@s>V>Zi}}6!5-i4oMD=Y48^1UhmV$Rf88}lJ$b!l8q?A=8^%Q=th#3_!gF{>_Uhj6Ft(8WsgV82 z#jE*61#L5hOi4yi8T}v&S%w;4>3$Ms^D(eRA-HzpB|LqJb(MQc9WvSs(|%m{;3fNMWl=NXHbZ zSo1|BJjTWXRLGJ5UVTea03awN63CJuJvT^Oc;7aVd?0_Ja$SMJ6GIacJ4@7>qdxnr zadr<8TKP5E7EXShdV?AKn6}2gDbpa?eE_hFxSv#rmCI5>uBXb)H9=ntibfmj?>4MA zalbEXi&K6>AP8$#^EfFMv*UBG`hbHkHOrs~p|j6FKDWrI7k7NvbPCGLQMBxo4@o94 z*%Qh_a5w2!+^QEEyZ@Gp&#q*xG>waB+& zVCxfCWzVtLp>c}!-hp4fPgoGjvMCs*xr8|Ov}K;Pa(c*~irr9Bg&1qiv)T-S5unR4 zU4JC(@TD;o#nRsk!1Dh<%c<~?y33%;8=8%>rlsO~%w~Ukf~rrusYJz2*lFrOr-oiC&QKr zvaq$qyAK{*Qm|8Ue~%rp+krIpv?t2qz5Na(B&eV5BCP<+KU>!7Djtot99q^yb(Lw2 zCmh)YEh(Tot@^Y5;#`XS)h=UqZ3tUhN`Xv07?Qs_D~r>&XeajB+#>Ku*600^JRy(9 zij+bgoK)-z{)XKivVz4vcbnT}va+^mz_Vtz8hFl-$$C$e>}+csyH;r&jjrTf=B)Vd zY&I#5veUlVbOMfm)Hn+m7f514+;zY*+C1%78u4fRWKbOGK|f2l%s`^M0@! z#g<}$_}!Vfz-5WPP{@}~ZK5+$a)$Nz#g#2mj5h4@+Brjk6uY}F=#-aZB;#@IFWv(q zj{?TR9SG)q(x)>XfKG@ROycY-Ws|k}`zG_rjDh(gEZRe5 zX(sW)qusNEgVKlayu#i5?GM*457&W+PIqU-ZYWUx;>}oGC=DaZdhgSyv%I&U@m!B9 z3W5ePS3AAjcoak=z$rr?zysyrxyLb=R%%6r{0nNQI~G9)eh1#`=HpBHUmo-Y(nlyZ z)QN9srIUXzxvn@h)csAVcADooFQq_id6U-5V0B?AnYY)*>N7?8yW)qo#E=TsOLFvA zOF2twFoiScfKKWX>{*YvlMU>p#--|vcQV^3hN9UmPC|LsIT&G;9tzaV%pH7)HTcWfkp zy?<&<%6UX!SMQpV+-X1gXmhp0+yA>*GrGjk;hU$rvaEerSvvTyJb2vXmmQECg!QOB zTR)wmAj$1Cxz(!AdD|Zzf`$iAP3c0F)&Xq&oV6uxwy@BLm%BY4WDI{?#MmrOk7pVs z5ML#B)Ou}V@Nr{j4JS!AI{sWk?*}APhQ;NpM2FgKg90z*?JwC6fP^qgsH)Z7C~jn{CB#OI}Rm`^R)s$ zN3eh|!1iVeFOZ#Zh4y_bXb|W&h2#x(TGESyx2@!rzKMd|VeBtBy+kf`4+s|5CC1SJ zQuwb{Pah@{CNL8OPGHHs6$^!NVasy0J8Rvuulw;rm`MIa)}+}~kOH$#UH1f(NGyP# z^XtTIOLlZ&iumxzMxc^w&R8f8pRIduEq1PRuATdWpJaMc_EmN6Sr~Ubq38o~rkY`N zf_AR)db2i?vFFAK5U;_GsCy1`ku@j2(qkl$v|RmKx0^0-RVPTtoNbPrC#v$d#hBU@ z1N0e&t@BMCSjGeA^b!L#yQgZa$PZ+1i|E;V1Z>$)zJZfED#NZ$IFb|_AmbQ81@-&> z*JvMekGu_QbB*Bcf5=fMD!~~XRXlm@8cm%Oy3C^-t$J1Hzh#;N65<$1RQA@jw2+I? z_EpU~9%<4tvM9?(Zhb>U; z_p4gIuBvct(sv)1Z&ikMXtT3eP!#7X*D+2XV-6XbS9#!c>?)iuC=ki*YWFKhAHC=A za*G9NyJS)>dGk|0qRXTdTKeoplo$7&ZU_7nRP@hBm@sO0gFGIYp=hHKo zYr-)LMr0!&bZ%oh%>b{7mey5U=7$r^XwM0@6-vSBqCq=nubP^9mnOT@QFAs_-~zVq ztryR`Z$QEFV)8Sx9Q2h^%1i}slGR5b3Lq_YesHaZMt3)CZ129m<9Ppr z=Q!^Bx$Y~@^K-HAZdS^0G+h`&ep{W>9~$bCwgFPFU8Xb{V0j_0Rrfb|99o?c_x?Jp z1yynrvdehH(QpV4|NLA{eQrpuk;_!+@8>4Jr^#O^Y(toYPEts{(W6hHcht>&t2P>0 zPMZIO^i{s(Y4a>so4Kx2hFtn_d`fQrHM3ZNeyKDyUNc>={H*b#s6>-8_)y=p`S)EbaW9 zB13!*iE3|fgpXiW+Cn725TLd)AsNYI*wI2uO) z6*R_meTFatPx%0jS_k5{5zY3Bhy3n~-Qx%08?XF?aSu3_&ZO?}OC|Hial|8j2AL!U#$nMU~a{eH;^fvM&jL{_fJsJMU8n4!Hsv^ zz@=~%O3czlM&r&q(Z?%oy8gkhT5)%nGQ^to-Sl5Rcr@XqXu0fH9nX1FJpId?h6Z=n zvxJ-23bAraSTCk}ALT=*)+WVUQ=(bS3?)$v+vI#YE$l;a^RgAh>3%m39?IBQ%|(^5 z8hcfum7Ay%jbpbolMQwV+^i4(-k#|p1XFhur|y2*ug0CXYU!J|7VSoN$RBpZD@oys z*^q6$zWt9@erdGPygIFn{}`=@p8&h78A%T*K132a9qM0?+;0ltfWof(TB#(GxSBvA zC#;`NMqI?lpqjx2jVH*M@A3%#W^wpau!gKFqm zYzro$CMP_&4<*mhMA?;R#yjo2c6M#wRPR?5%#wG6W0#pjXRf*TKt7 zwo~m0ouw3I3?hfJp2@<_Uq7Tp=|ccNjZca{7*vH)76Sit!_d{-S(HT!1Z-E|?dh$8 z-HiB;4v#4O6gNq?WZE92JOyo-i0Ttqq|wqWd7c(Kxe0ETjV$|Vv~lr9EdWDKT$4@= z?u3dDB#*?5NEw8F<&?3rlrt|jF5$+xjpYYSG=O{UAz1Ob8VZGU>+3UdE*0Kv}|bdntCw|oRyAwRm0 z>H;Th(|3Ds?sOPGCE|qrjZ$AWdUuDGKv7jjA&9RrD2rIzGgy~uYFZfKmODp`){Rd- z>~=KjY;SkGJMDJ)Ii~eNSZlj@$a4KCpd0sV|4}(!1(DROg !zU|Q>DXdi@8ub0T z0aJ!T!CyMhBZ8eDhwR2&>aB;L4LY%0#~v|UvoT!8VnpzAx~OdQJ_`G85HCR_aqHxE z#}1hrzaJC}O!}#IsM>3Vb%fpJA`J$tl!OLp4{PgfM{-RTEf2)x?tRMMw+vIEMCbpu zOvH$0;)qBAO6S|To8T?{Q^HQQ3AxVE8G^IM!Y@xnZoKt#dIG0HsdrE0n|6q!f(yUb zb8~*L5bNh#b^26uFY4Iw={>2*yT3bMQwxXq`R_uBYyQf|)>1?D9nCk)9d}o~Um+_( z(@KPD>2>}6tQDuDh z_WpW5mx zd7M38dLgh_r^K^C@BE>ogoX&7vZ4clDQ&_6p<|@}gX@C%hWMbNy~A^>1?bzpT<(RR zo#G{rPABl#s|PDRp?!-@{qThg@nH)@+2T#=hB%`I{O_$k1wFWvVL=Vb z!}_X&sV`C$y6F0bSDjaN^K0s@@m`e)SHros88U(z-oV<;v>Pz@QE7?nUFQ11LV`3= zqmO)04r4cZZ#74a%mz!Jf9nB-^83JZ>n#kam^l$ZW=hg~s@DgBcHpQ*y?9+?(c#F@y|E&Nf*ZMxe_+vd^{Ecw@0 zXk3s;Eh2YrS%i?~<5bN>Gs|k*rX*E!l)HuaY#9fA3iyjxpO#u^m-xe~juT`o^8IDY zLzYFMoHrTk25Z)g*BSUn!aV1C$RYbSI_E0dZViWMTwe9RM=NZwE0fh5arl4&J-wlO z`{Tg>1z(I990H=z))%J#nPIORYJR=()nzJdkm--Ad?1@%5FjB?xp9qyV$^1+gb1hP z7O!p6RfR;ogMR@`C*?rB-5I!-v@VSD)peYoQU=fOmVzpNmmnbrz3-PGw4ns01VN5l zk7{X{)x{(`Y_-jF?=7)MPV|bm@%QY9WDD6eMd~jjljdlMb6M5+jWkUmrUYzZqx8er z>Hi=}KUJ@jReia9Rh7#KpAraCCeBG(XaCx;d`7WBiPzmGFrDUnBM1=%HY&jOC!IB} ztn{zL@i}zEVzbP@twXz%T{BQ_4Ht#h?u+pTNUPSPz@!#;L@M^rD`qWfS?GzYXs)^u zYqgT*PC%W0S{zSdt>wJe%A=`1S5m?%{ly1zSSh(ea>OG;bwFnDsrA~g;wL&`mnmk5 z=U;GmX}Si9oWW`952G|7M?6CqpK&+CF6sI>@@cBsy{6jIoXQ#+yPinP`WfHb(5OxDQW_&Dnz2RWx6Th zj_=dCt7Gxkc?v4YVI~@iGBdaNA=@b;@34ejY=R-g!okMi=2uGr%o{H`R@;*pqBImQ z-3}NKior`5XHTy)TgY=wN~2xXI97nJ#%HTck_9sLC8w}YT&(29>(0ZMSFbArm^;_z zX0r*B6`=bNNrpcnlzLjh6Z6g7MUzEFBPG8w4 z#jIc5zN0TWSH4>MJ*srlx2e;QGtaLKlx3Wq!+eEZW=~GFjp5g4`r3*roEaA^7Jiga z|6$kHx|K9Tp>av5a(OYT1y<3tOWn@uD@lE;))!PjrLFF^xr#e=!w5Jc}T9TWxQ!^ z-F04-*~8x-8}5!Q?T33);KTK_l#$hB5`k<)igzyCqwg~J?sU2Ok)FVpLM}5gJ7ze7 zf$JmFl?=pgq~5*%$=6P6!c%a)_K>-&cn2a!l+EAkIeH2^c^Te%)#PMt<^_xK* zxoZ)DX7~{fMSN;eyknq^Wj8 zNk9v--=0Qw!Mc!3lV@TOQeYve;=L&HF~7yA(a!Em>9>mY1iwEU*{Ls(G3kU?uo=@< zZzR7qlG8i#aD^YWb6E#rjz>9MaV`p!5A#kpq))t+Yh5yGl~PX25;6|}gbHv3$Ck7= zkZ=I@*cV*i{#U^S|2)&$Jvgf>f=i%X43}Iq-M-9W4tTA&)uwvIf?)q*5jUG7$#0jb z&D66sGRJnXt6jyi4$uACMLr-m))9RL)11zMTDJ~N)DdnF9G}AQ=;&go8y8go6f~kq zIP{~<33`t-O=cM6p!YLi7`#S~_h`x!Myl;}YF!;7w!le*XJKcq>Rk9Gh~m|DHuCH} zgG-jT1*OCr+@NU%M2nibjw_d(8&&>c)v{2v_Dk;lZAHD=u)8+tS)hjQpM+Z2hosNm z5ljYL{Is~{&P@3?E$+kQ+d!1cK`cZnNEl4i!L*HLEsjh{O^b3z;`O`l$w4nb)nZ4U zElqKTCdjrAW;$4R91o83@+u6&Pl7a5dN^-%6w*HqXK{nuE+-JSi3RC_Xn#GHNFAs2 zL>d&_^;q~7R zuQD03CO*xe>*N>YnX)A0kBT{7P+hdILKLeP%4#)pK)3vys zkro}Tj%@k0FS2Acpz@}LU$;;KGElZZ;con2aQ5O(Bn{rzI2uO}hAFPghGG6)Pc0rr zs-6xpwO(!Cu4!XC(^T?*7Ha0a3hFY!jGcF$FvY7Z;pK#X22@AN?j|UprvqMa+tXPV zmzm$(QNQ7wEx3nssz1vDUmI4RJEh+0up6;1oH2$D{+nsOF4<7T+ZwG%K8zUD)3Lis|p?vH4=%BX_iN$tr zpUtcs;Xw7HYY}d^d_c6MJUj`08v^FMYPU;J_F}s(L0DPKYLzIz-?sbls|5c3M6345 z4263BHO3E4y5sY3dVu|9!yu)lg*#5=6;_@yP3>v;M=V|>qHc`s z7IL$)BQFRa&QQ+f*k9xVZECTu-+)Sbr5*7h$Rx%5&fG1dQrGmK5h>b*{G*%JjP%OL zn|3gl((To1LThGoK3tm;S?ycp;0aJ`oaDxLU5HoK|Kyx3B(}Q6bi@ zavx1`L=YSiNiaSdl`OyHTmMW|DB!Txs(iKi`;w6`Q&wMZY~O)CCXysBZ!Y@t?rpw-Hp2)I!C{?u2n@ zH|rCjfRub71}dc|tPn#6`@t2~c5>9~kLXoN1=Z(KBu2D}8nQf4OBu1&H+b`>EC~>p z-Z{xVMyfjKM4VpyaPtX-u%by}gSLHxy;(-lyJ-w$4^%w#qedQ1QE%fVU#xk#dGZ+?r5L zn@wo0$TD!FZU-RxzT;1}Z$0>ar`ul;?gdKgDLFgfy0sbSB4?BnJ4b|;a#G~R6GKlrlG+K0{T1NL1F&bbsFxDpv^prm#2WL2yYtF45t zJK7T%KDa=ppIi>a|Gs}BCkIc1Kz=dyF)>~g>~fJwY!AC082ONiYpp<|@UHlfZ{#8T zW0{4@6PaUl1`=mo5pQbmL#Xmt(}`zBSJbvHvPmsSCEDHYzHofzjdeNSUr`9{`t#x- zb)^U6_;lJ#?q%aZo(3mhVOLGLZo3Hh_cbHM=_11EoWyGeuFZLr?O{u^C9Sv~p40%8Hp z1qWZ?=!T}G{sNhdy0cy*vu)W9d^dI}J}DS3oQ;XS^Y-E?d{Jeuu2aaqTC?)Et}Nx8 z^AcUIWJ%z(HY-T8G@H&>ILV(;)@4*gtyiU%%#2qpZhi=Z^aamBa}~aRUQQ*pdq}rp z*oRWz%S94iH+;W6%*X!ja);9^YKCCaHhc1Y;J$9cq9d6hfU$l<0-oSbrN0wyY(GLo zJSS(aU$65gqMzCcinG(fZmhpHE55wiZ9n`iD!N+eX01v-(oC#|x9-`KSjdw23>~R_ zz_y42I;R2i!%ZOYG@}n93#6)Y@T4Ul8^ z^01ZYJoq=rZ$_w19>giW_LknP;i}}c-RqLo3!J(2Ls9KdgmF@_v5;EKqFFq>UA1`B zV>LBlk*HzyT%}LLX?FQfe{;i00cG=?7uP@k9ZtMIpO|f(=js;crtA*$O4s?Y)- zLt15>>6uMV%nmB_aU7->#d#>6c^vzEXH(x}3N0pN$@F2BCYRy;!F(K5+xjbfsT>>} z<@m9EdAAbIXm8;VWbiDbap{0`f_eKwCg&cN%Uh-DVTk{d;Z9liOTNJnQRv@Y&Ajc@ zwy(qk6;yv5p>=yVHWDiR2f=FsOY8g3oVne1EzS7}2e|7RT2mzOE|Pmt{M&pF@KeXr z_ilznFTP-!E+4wai>}eB4bAH_RRR18*GZ?B*_G|2{AN|3Tm5cJPZQn;D!034gGH|9 zILW+<3t8+8PZ8wu!717WvdyIts`*`{5G>0;w{eR*h88?aw3dj6XjHR7mz3gDRqYv# z2@H6@&*_-*Lk#f{;vD4Wch|sO4|X1y^`E@&5~M19OC^4WcR=Ai z_d6%ym+w@rh?`p|L{8VYf@@ubSJJAb?_{NB!nu&QIlcFa-x)xr&W{9$zE{G1gOqqM zZ#=k%9%mwwMLAD+*M|#F^U5zC$+Be{$80^?R6h}5jE|HbH+g;r_uPQ_FpgLcV(C&g zYtGUpmg1!M2v$;1d#mo~|Ah*Q5LR+^uDGx=MZ$RQn?vpvrn)wBbZ^K09`liCh#6&8 zkCBm1C}p7AH=B+s^MH1rAV6iP`ju(D;02X`ilhKXKI;~n!o!#l=)1{f-!Z$$-*Sq% z{WHMJL^HGH1HeB(zpc^Ci$n=g8k?8+3pu?3E_(m|;I2O4{slVq*!jOvs=!IwE)$aG z+C%4}|Ds*R(4;~9WK$vJn4BipyEU>ed;0m;V63MBJ@_=Bv7HqYQgV$Yi0W5m?MVu z)e)v})%XaUU>{DD7+#VHa9pn{wO-?zD-o&-n!0`)sTSEL9?{0*;ZtG!+5u4FE`FKl zZUy$Rx?G5Tw`o<5t1qBx18+hJKEobQ$4D%@8Pxznu`-r z7MjUg|LXodxAK^{$(*zouL}S0u87A$JVK3ltmtU#nQ&)c0IOqh>O}A(glhCHM>7F_ z>NnRDba)wbNPk@gK|Qh%s9iddI?Bkg$>5?Rw#1DOIq?DZjvX}arPf}cIBAynTwn1O znzag@p$$joIqyJ0;-Ocqcj0o`OR^DE$D-t6WfOO4K)cO8$dv#7yI5|?xVS?{=Q|X( zifey5Tsbp)UL-0KZFI6-WaU#GhU~F#EoX)(+y~8(!LI%Z`L&=sXYsTKI{@qPZb>miC)>MXCQR!}Y3_oW z&~Jc&u|_3p&b$p1d2aZBh1-KY2^#3S0>KG9`m6zAriQJxDb<-mB5pIFfi$=i(0u@9 z7RDzKZ8sx+_iADQb=zJ7Ik$e!Y72*p1+WRIZXPe^h+-OWwJUX}sQ-SkUGfl?I6#hd zMFeZ|joNoks;4)4=F9bqLVG~*AIcD=fqQRo7uG4-#WT-LcQhJ}TM+m26Mp55DZ+w# z8$o4MiBx*}JNyZr-!W4aS@7uH$}&x@v;w>rns8U^rn0lROmmkq)kNjln(8-5A7PuY zsDg(R^o1)@#)}8XSN!nRH=-_!Q8!fYf6ZYpScjl=*l$-JX_01(EqWX#EnS=?G)J8d-_bckMmIMm6`!+E|fQ{C4F*uVmH8 z`(WW6)kY5rAoz%rnE_rcQ_1-6!WU#tV081*qII4-xJ0ceU8$9ogJ@Y1z^iWlU7fJ; z4YH5*#=`?_)=)TNGV>QWeobEDHCfX9&cjhNm(GSok_caZOIgR09%tMcv0jsy z%1Kl`tvaV)$J+{p-1ghTO?B%f{j+_4bYU_n2Jvr2=$j7FUNQK7x9h&uWJ|sXO1=wI zT*9c^acGE&cTnxZZed!HwOlo-V9Z#jU{^2_|AN7v;J3Ond`6$U`ComngmxOORLP~IGyt#Oe8yRZ&3tMHyx{~3XRH)XOG zYhPvTGE4%0R(+mxAgKTXbqZFk{F&t8^_@C=jHCcW$ZJFxgE_OVIGq;wE=_+%eMwp1 zU%}q`$(f5gR6*IOftMXX?%W56;%M^1HkY$*h=B@A2Odfrz0tWQI+ez{SM@EDX=Yz0 zI(+QjE3#g7au@mcz|JiNpA6@O!&O!RnN`=>IIl+!32%f}R>R>c8U=0l_<%T(wASIT zH}|NhKas#bKGw^w$g0x%eG+xyCtt{=qEa4UTeT?zgssyg76&`A+EfUOq?UC^a^tMn zZ$Dm>K1%%v~P0e^Bp+Y+C$ zyG}0IGh0)!oD1LdQA6id1bqS9vubMgVpGDPWONRT7=&qa!E6Tm(g})ugM2#wmT^;e z&T0Xj{#mTY-2#1V_U9{CF{uye+|4=l^t7CpC}gZP=gUCQ+17We)CS$WtOmC#w<$2v zG_=n(9>LimNUNuxSDr%HQR?8vP4Ur^;@p>tTIc1sKM)m6egk=7pWzxt&|)v=$lBV( z$tb)>_{!1|)L=CkPUixwgx+wqF;`dJrz7Sj+bIR75dPI`pbvn4W4SXj2K133(*2$I z5TRFFca>ExM^4tPPt)x8;EL9HM_IwR(|ByKaV3^Mi_xj6W@@i(S4a$>qR|r4cIlh? zE0}ZoZkRL;KhfG5Z~hihGjx6V({o+BzS@Wbi%37Ho2SVQ$M^D#wvLUsL~%?GquQXh zZVArSIk(<7v4f(BpOhR|!CQGdaPJeJzt=gvCpe)-oZAjlB846RpP|7PpimwP6@LP&KGhZv=@Iz4;6KTX_Y&_?_kWAI3puU%dDQxI#m2?5 zLs!w|QLYhdT~&Q@CYH+bx@Wq3v&t6N59tO1D`)UdEG$#*4i0u9n2EDVZyP)0L*pFO zu_N(Hbd?l?^DC@sYRA~S9yVUIU9kI4v(X8N3OH9WOyzIR&!?L@u!lyAcCOr+KPLL81}x?vB4T42Zt}CbjMR)knTCN zWL+bb?G5kGX=46-jHti516%_q6M{B5}ZqN8NDs_=w_jUyzZeZbJnh{h>gfR)i^FWuoMyu4?BMa z=O7LHhPodr{PJkSvG% zhxUmQD&ZeudvbQ?)avx(W0UH|M9wEE7e}Z^0D9FR-`X#SairH7WHJT%hFaJ{kIZ+s zwA-#UhXP)dJ59{{l1dSEaJroZ-k<`8wxHHGo zu4iitZ%n^1v8|-kfL*HF|K(@AF`||Xlwx!dGA^BvVaP#e`C16l{tv$typbBSAqE|K{y9II-JImLDR}i^it)d>*70~lFt$L z`6B1U{_@Qh;mBfmM^RXpl(Z&wwY;B+^V^JYSNHQg?||-7O{Mw4-CKBR*Gpn zsaQa}8ft3=?OF3b!gu(HU$g5moNw_;+WZ;ME?W+5G3NNC_c;8pLzO)0dfbFN)1R|Y zh9o zr}6iFhQ*1?fX0&hEH~AZa+9hw#Kyya-S!nFr@1D?U!n7N?_qCDOlKH!IZHs=W``0_ z0S9DTY)*$%h^~migV)Oh5I}1rpIU+1@6Z^F8J0G+j~QP9_G_Na?-%c`_xITN8b&!Q z4S4fcOl)1Q50$tND1z|rcs#TKKDiC)AiW;wc*4`y`9JYE0EJF~59QJ6HKL@S&b9Roy%`8GV)3;k;f3%*C$0>VK5fnJ z{`(duG00WK!($uGM+*FizBAHOy9okcWd?}v<)o8Fy+n5`EJLDVDAXt@@XRe51hDyl zJAK~p3$HIMrvaiPk0c*fJY!K~*BDZvKuHtkO?({O_|qq_dbrD3n3f2D6+>I2Z_mOt zA=lgMX?SVv>1lQ@LqI-oQuVCGSbBoyw+bTK$RWSYdQnl!RaHUpSKmo!!T`EHZML?|t zTQLh-H>1~9R^MYKbB2TOsbIA+I+s`94t4j|DGoWSMxzLq&;gN0}UkiNUC=-2VFXn&+a{^LBma z*P_hazLuz1G#%Oo^c0-#oK(8Jcax{HrCv7{?(6cjSd*wz^CR)9w|2#vV%24$m{siP z=IcH4^hQ_ICii3&V2&*OnM6J|FSdQbvX8Nm7N=P%&)x zYFnu`A*&PQ+I|rJx+8EC#S(m$Mv}hFw&`m_0OD5B@6h*;-Exe(l>BHHd>W@0 ztakT--k6p%2MIcW6ZFbI<1j9o#D>o*6!S$pkBbXe&{%HoNr7^;7T6}?@jiPw7&{^L zuI*N0q&^F?b!-@0^p5ayTihns!)qD#X#E05U=Sn@-C)x@OAkq93Uo~T6QAD-{8D@*wll=vk?%Djp0LsmI2Y3-QG#LhII?5bK zPKcBYA~y6Wu(eq$8}mk=!meX&A$F}dYRc~D^T3@O-#b4Oxtp63Q$3#0BsX>i?dUPo z@;e?k)dl&?g)x(ghc=4GM|OLl3Z(Mk{A}ewtyD#hOazZL$Elz(%^kZEUW;xxKqs-q@v;u;@2IreleiiTkn=k3bCE*B-3w>P0!g(4L5C;RjZ z^Xai!Jt)G?hdYzfP7i2L!nhHP$(D}?%0^;!7R^e>q#>) zJNE9}?cE#2UMt+8#NMh_YfwGTwDYboa6g~I-~9tqPByNR6sQxS_kfTiN%h3-{A5)W zLrci?zz_r67J5Tyk{4gCzaU5M@f2K2Ha*sspF|u^3y7&5Z3QH`fePU&XA~+?>Nl}a z`}*%3PQkhAwx0PiV>1r0XYcuaat^1Es$ClF0r+7&W;3wfMHDe}sG>q|COC$j)&t0e7v%Pq>ztsCp9X7X5U zb~SbWnjXQe3W>EAih4XP`NEX@-K(A060=@%czQ67i`=AwXqrVV6qCe9Zv`^VAh2IJ zF$g*1wbjTvTzxjgdclObUrc`fMlPB%((4oYt){Kd+M=YHDujyjIms!xo-s2xo!v#= zh9hDubU(v@H&?X#F@GpNE5Y zO}3g-cP<|ZKbec=9;Rts2oT0I|6Yc&&&FUsQdRHZt=t&V?HpcYg3k+tf+*vp;Dy5v zXH3a-Yd3aEZj8ZO>a0En!v?c^Kl}pJZfJMq%^DA9{k9=fxcVGt@QR|)5cit1dQ; zLz3_&0Pvx-`}-d9#Hd z4_uOa*b#^XEh#Fu$K&ZDKl9)p$aHnD6dDl=o%SLWKRzB()k`d@m{9AcNgfgOb1g?O z9A|@&SKAfbfbL3tw5ftLE=O;*6~ngqQNcK(2yQ&t%hrDbC3&UUzgu= zBS8$&KJiG(u@6b3GXn=KcN=A8P-&hHE;Bf6b|igSmqci0t;)3627icrBjA=VBM%oG zI$$GJZCp)=h;85`|K91{M#ia5Lp(ub3n?PVvhiBZei!?7Q}W3Fc=tIPPVE=6$#L5` z=CLWq^QPi9;c?U=Z>|hPS4rJVAPK&ySR^fDrBQH)C*1$LcwFQF(PCc6JAxf5>XGP? z(EJ7^YsWD4LjGoL?8Wk>$cry>O#7VWTi4Wa@locZ79^b>vCj{uItLxVnyP&txVA&e z%m^-@O(z^LC=aVcf;j$KQ%C(d`ZhP!X1LbMxZ>Tzln=MWtXx+)2nSpqkuTfdYNR)1 z{XW>HMkgF82Y6Hdj?p6th9%LRgfz>Y-&;FG(84N#FoMgQTJPgxZWx})XA#XT_zd{}!B$flvWaII|T@mFb|A2Li z>RSfN3|5oZofZAwKkutv;;APWue*D@_$9@{#3Ql>^QNBYZhu`*5%52aYS9A}TL0tn z|1QYAG~_)^&ifJTSEHni>y`*2X53T4$ZhEPnQN`Eh~ zHSQhY%V*KGbVx|pM&|*RADQ~7xOb{6ywn$OYe>0%_DB9BL@!L#{Z{md2ktqt`aES< zOQ#0wfg)pIJOM&*mJ)Rx%CKDU%g$xbWzMeQuw|arZAEDQPnXYZt{hYj@krsg1#gMe zHE<0O`j()2@Dz{vk zVpvvr?~2;LX-G{}67AeJXxr|XsejX}Hrw{_LA34nLy=0W8(H_;A*7=Tuwr4LM2oS%-t8~^rLKNH)%cN$bBP`p~%fq>!r*)6!g?9fiNybT3TTBq`p<2)usKgb`W@0TZj-0 z)+T7b0UQ!(J=OH2wuY}nkIwf`ww=BcP^V~Xq@Ohfe&t~Z7E1O1F`P~A{}Hg2sq6$r z91Y|7U=~m4uLo}>YO`)JY$pv632I|ZuiU3WvrQJU+Xq75=A=I$+t#x_R2h>O`&;X7 zi{AXle#>5wHOTZHl|ZO|JULKao5c$!L2SYPIlO)|Lt5-nuPfbbH)voZ>2T$l(){CkdwQxn6Ht{=x`l;IM0p(KJTK< z%6!fq%wr&}*W97RgOlf@BA2^pA83_Ee8vF|ClbPPROCig5VrM~+9HSF4dT9IOGRXI zzC^tCC;H|kzx>AZoE^0k@OT9?;_w`mJ^HP>*g!u>3(Y_htnleG@TLUZ_9l=@qVyr4-#a4ux#%M$XoWXY>Mf45I;xT_C}7qeZc}y(OJf&b-bb!308S{ z+x9ExaLpmsAm#abd0@=MHH-R*=|6F|^<=>n#SfKQ2oj=>ehW!H1U!QP zKYo#{8DqL()}8Qqnb|#NMAgFONtHpstX962p&;3|o25-Tu zgKe$3O>MFyzj^xse5Bh$HiksyE4hs^Mw93Y>(;18RL=1f<|U>6}*6V zV8q1l0oY7XF63+*{st?FKnetaHCs_%n#3|K*t?2cDgVGZzM>XArp+NXcfW6aXN5x!}y~eF{OF)rj}@#o0=L z`}6)vWpS{Rz+o7@s|#d%b-+<7?6}fjV|Ox5N+zB5X5^6F0~t$8+`X7A5q?9SL-~&! z71^0dt?8Xb6*{js#gwn)3TXOehckTJQ}*xTz!79s(zSCbTQ^Z z;jJnhsY%`tVMl)1xvg(+obb&0X_X_YR4RwP)$ONxm;7jzH`PSzgQsGfH@zCC3@+UB z35Dy-4j}ek5vU^9o&pc%g7?|TQuGmw<*ufv#IybSf9(&Mk*%^6i{Ew%X|Su*Sd-Gx zYF^tF==<

dO`%b7p(zrClpe@Ie%KPz>W9eF?BZ+cutk`p}^s+*eAn364E(|@J%zng~XlM@y8f%2^zq*!&&cR zDel0*jfg0`AMxf8zbEeW5(QV49zF1bPl3S>%Uz&jRfTWsMGqM1MYHpI3J8NU+rjVd zcNvpMsfHQ2P;s&^59OZ%{`|DYBWGM%n{FwoLi+N0LV6{`0?iI9KDUGeu*>o@ z{D0+H-mhJkbcP(0&UaEpq=ghDEcsh*N_pR-);9jh)_3vKgD~ekG_kwUZAi?X^6aF5 zw`KWET?d-KP-M&e4OrjbbZ+>^hee9)A*$CK`fQ^|<2B|5)!B7{(cEY@n%iQEbE-}v z**VuZg@wb7o6Dk{+^1-x{YdBJo#o|)epLICUsaA}LS6lzni{)yMnu%RMQ zQ0DvL-0?1;j?OT0apt<(^*!JGJvUMI9@*Zkw(I&yHD<^5W4i_q=DLUNo4l`q7d(12 zNO-KxBKVz(UR%>HyjYrRLvqb|Uvt16z}S)Vj>MCkL@Dy@K`}>8&SL;XKwLkvH{t)tbX}~zr#?qP?mY_m2lgT0L{DP(5cHu z(;|dwzJeJNx?r^!9=PqR57E-`$`{ji&rick5bHsLtjuw4YCP{_BZFXuF{-9OE#rJb zfL-}uR`;zl4nLV%I$qNKJAi6wmf5-)ZEyGenqv?&jRCJ#Mz9#Nwy>;_ghoC#-_y;EnlAdsEQa&F%7JkyUfwdHC&7 zMoey5<%4Uh`O}NY&Y`J-wri5L z&xxEHhem80;$+SqHyPk~T0jGK_yqlU8RSUC7R;D`Bi#23v|`rEHIrcgeZOIhIXjlM zXWn|>Bu~=W=}S(YNiR2%rY=*WBG)~?WaF-h_ zR|;pYFC73{O7Iiz{+f|{2%{3MJvUFK*=sW-W?iC{bsLZ($&+dd%2hVv?T~mcmI%L& zc+%o2WO%Vb;U5AJ#5Lkq80e4!{Z> zs=n=o1lh-3=lZ6Ibl=7sVin|vv|Z88cQ84eQe?73#O$7nocsH`^L{t%;3H96#XofM zya&C7K#`!m^O9iUR7}+LCx6)kUocN5IKLOE(U5S(3Z>VBk&|~SND4RNieO}?k5`FE zs$qa*oNbUbyNIchwi{T3{`aZkj#(ZK>9@7s9KopgzyOf*hlS5T?~X3gni}kH91=$n zg+BOoZ;y>dn4Q?x+K5xd%#S0Qwf8kq)%T1{)qa3s{g3{b@o^ioBwl7}rz zGOkPX=3AhSI=c#Zcp8I}0=WIeuSTSC+ddwYPl;e4u^%LBMOK)8u3!9w=lG_|?|lg# z*SY$zankRL{Ew#ft>w?7no%-&UOv)iD7X{_lKtT03sY?jJI8S$OZq|UNLgQLsF|8K z&r@h-`9m|MqtXX^QJ(SROmDvG9%jE{TjkR|K*H|NUk~XoC;k?A*$_Tee-Kx#GCR*z zyKxAfEI0kIXySNg#x1rYk%$|CH-1a%fipoDN1lpDx>;P->&R)tR0)Ig;bu+yk>iIY z3MDwIL{-h)=(E+KGkGcx7j*zdgt;Mmm*FxJwg-`v4+z!_Tbgzge5!8QBt(`=`F+cT zNZ@VkpwFl9{5=k(NQKaXa7)5#nh01;VO78q%5ERqP_aBpWBouZc}sdNClOi3k&^cJ z!^fQr+4()f;LdvycR!eX)rl)J=}adHR;kBiq47+kj<*m_elOB^Kgaii<6H9rFKS`G8|JCzlF| zEIfCr+!jO!wb}csuc93O512q_zx+xwOkkKd4x*pJl6$!i#INQ5S||Sbo)RV=5(MI` z;y3>PXYWm8EX~ftymObjxAwL7?wRQsa)um|B14g~rHGO#N(x}We~d(lO|2JCH0xax5T`iz=l} z-&J5#^YmxAT?`vF@)=Z0*ag6lj+cRtL9ax@eTX*;Ys{5Q9e|{janck;RY06GHe_e{ zJ#hGW+yd`Y5o6IoSrvVz>TFBIfA|T5Ntt~f*F2NuS!Mu+2Xptn$JX7%-<7}Oq7Dqe zBHRC&irn+zqCbBJjx#w_0HW zwa~|!XIRk}!wj+E&(!{W4Blh<*Nd#YBt)+Avv_fta9`2CdwaoSS~aes`B(h^_Cz)O zKd+n%*T$zp?c$4JoX~($;qo4y=T!kGva-c|!b7w?Y|f z|G4tx)h9~qKLjm)7AosdARa-k1+lz?{Q@eC_?a?21U)KX5P1ID+hOjHzZqsXw!)9r zUkpE8|DkY>m^M}=`QI+DhOeFZv+%8n8zFxY zH_$WKhiLf^rr&n!dr~c-?=oye{~_TSe-+*Q3o@+z@MqWGA<`lF42)OujZK0X;Q=u< z6+Zc~m&27yuuY^A9>G2!GZIWsd33{~trg!XAJC}W#EsQ_0T@(HU5Ysaa&S4j5(kO9 ze+yjx*I@wMf36DH)y2;;1CTyd=t?zVLATc7RllNtYw2(Ot-tj>IL9Ai|F2Q^F5tc% zh}uYhJ%aqiL>4i~xZ!wY0S*S#yC2?V<==w%SFy@oNAG_fq;74&O*i@NIpN>kW2gK$ z%1QugT6T|`7d@6uL8Cb z{RynhlU2EZoxol|e}Jmv!Hz#kcdYT)CTU)mr_13!B5{rXx?@mBjsGmscP!h@{>Di# z2==qYYH&4-oT+m;zWx(!R{xMf_0C6|3d1jYU-u=9aaGEiP;2vO;SWiTTh$v#^+u~( zVG56m+4WkuKy3b(dJEw^a+XZ5uTJ03d?4z7njbArKnV$H>_o%Adt;knabguQc|M#k zmma8IGC+7=`qFVOpfS&35%Fi$ zAQdF7071ln6$A3@s%p3adpu;vsR&^ZcVqlF@zq{6n;)Wow_C*ZSM;yD-!N3}c);_6 zlivf8&}Sk{fCV%JVc}e!6|^Z|b6C(95%HJT5cRX4Co(t+tbMtJXcSQP-(iZds_5UaR`*X7Un@96vu^}82h^?R&JE{NO~ zYDB#oCFCz|bf(?SV|^a|%il+$bC~bk_gW^ZpQjW#cAdeyw6o9#fbo#{o1(XjVc%ps zk1-{T7JV<%WzA$PhnemBw&ch^5IYaapwa(G;7jnI4yu=qDV1Ts`Y}|qA9>`*Kl;Y> zTwmcn{g|V#x_SoyABH5}GO-Y=^AhRF*Q%AUx?YK?gctG{mX!;;#zU8ka{jLP@}`@+ENknLqr)KfF)Yzy*FwssJw(ty)FHLaY134e`9ib7?=G zcozOVs|-LIo8f_UKUD`hO?mquiT=A^_`(-%bNpLW_}SeBJr{u1!Ocm+uT^S?AQgSY z{~D=8gt+^b#~ce$y81OC_=N00>^~F!fRw)XF#5ZP$p0Ra0JLcl@}4>9draRv6F+ae z$U#i7){lC93Cqf@=)O0;v>0X=uZPiEJ1({|l^^BOR*4 z$lSZZ_rU;YxNz=;7!Ke9(e6IdzeEVoR=9|jg-lmwPa#S^a|Y-l*vILyZL~@Db4Bbg#?NA|qQpuRzg-04-vqb+ z0t~==Q3Y&2@LAb;78!tH7;@h#G^Fir;_u4eTEbfN`-qD^#s1GxA1ax@Kb$QAeqx3{ z(pH+{SC_wx`0r*OA9}G6q9oiY!!&Mm zq({!nkRh2n*Pq3wzXSWF{3T<$PQVu!vI!=x9x6F}|4YPyfW(#05cN;jKfW!l%%5UI zePvuh3*I@=l2KvdxKtJmMZxgHkHMVBwJ7iM`R{SgnkZ26l9VP`HGQ&7;>JS;eZHh1t239NE4o-;4N_Np&F2E|95 zEL?)&Wsi3~=qup(b4US}zw(u@7}=GZV@*tebU{e)6=}=v_VMn0k56@Z));^^7!Kez zoUre}rs{MbCjN^5!!P{8FWh4D_oxEKj-tN52cmP^Va3xW+EovL%ToNxNFKiE>X*6u z6~YFqyKilsC%tbeyg|(H+o%IpSowom2}yvKTDHUI91fQOkA=;-qAN06_)v2N*SQ zhzU^q|KEb^e`&w~i2G#%5(8j&rpoTNWFR47e|x41!}H9PG)R7s`@8FY3_zJ!|JMi_ zafN%n=*>F|S~ga7Jq)wd`y1cCRU_b!;eLe`SA0h(a;qK1`?z(jq3{1@^%DO6<#3DR z+l2b9$RP0Cqdoly4SIgdd+&kB03bwCgltUwo8JoIjXw-|^q*(ebK#SB3M7Te$CSID z?30Lxwd7p?9HRdZLGH6W@5yCP6qo>5P|l9tdlS&Li~;)`tNApgOubJxe;N|rz?z8PZdDMn4J^`KpZ3^XW*tgxn-ESi~%Ul z(?azBPu%tIkOQZ8KyfAmgg(NsD*rZT@N6ML(l@{TR+y-ag^P0wr~(L0Jx`!y@So~{ z$dn!ET`bN}+sFp>khpb6VZOndd7=eoZh;TQV)!Ds{ukSDeYl9!A@Y62 zOo;mxF-7sGs~{dJ6b!%c;Rif?#(O#tcr*N&+{g6374(c17=k+IUG@9)=jF8Z0JuY| zczxrkqohV1!N%JX< z$C~_A1<)E93GGot{_6bqiuXVKiou*<*%jwTE{_2g;`4kIp${%R?4%fe{?pvIoe7n* zZ-SXTu4TOuLKw^RGmaw+=?D^<5$2~6{`9zb(hS+*KUwoXNgZk&q&PJ!?YBlq08}LV zs1f(X>?Z-c+ouT@#Jsxgk(#&%PHm8^$oLS|K5fS^b_*#>i@Ils|DB|BC4hKRCudKZ2!)9xP#%}HxVyx;3k7MH8lAB zc{znWAn_+NT<*<33?tQA_~9Fk@E_j19Oi46NWwE3K8%sy1R$s`e-6^G^}hc5YWFi^ zz684O|F@g$=QcrOR}sbDCgNZ1(u>6WM@Bonz|6q?FHWI-+96Vn;eYi6FvFid;Cu~Y z-eXVlvrm&Bd3rG2^a3a%_$bpAr8NlA?MfJXi&V)AbpkSan44kQ(Z;h^ouP=NrT%Wodx|e{#`Fb?M^LwIn6s zR&X87SMvluLxuEi2shrnN7BiO@MAyni7-Dm6B$yK+ zC<_JHX;cAl6EGSH{m1)X=kL#g`~TP9{LSC|IQzR*0WtuhYiUQ?dd}jpMW{*p@x*ET z^QoguPv8B=|M(v}`2RdTAZ@cmKbiPH=A~|JM4i8> zLN%XCCA}yeKW;0;z@HQ7hhQu1>2Q~5e|L}q+))a^3Iki2D3f~JbDsZx0(-#0Q}n;O z7z$g}aA|ci{NUzvxIl>BIa0u0LWG=o>}#Hsts;e=2jb+zLetUvK;u6%#;xUQWc?ct zok=YIXNi_NF++pYn?B~*tgcLpn?n*NktvWjKq-Jk=hPOyInR2qNEhT-@sF}Xo!ZzS z;$kOEA?+~G(m3QlOXhQYUzy<$Gyiqs>fg}6w+Z}nV{$o+KwRg>U@A$}6UXpz^^<9m0%_O;(R&okhhcBlgEW~&e_@lQSJ z*7MIqInC2G4Z!fg4Db7G9=o+BCLoFayFdNYKYEw*|75ZHY&HM@KmbWZK~(TNo1p^0 zX!vKm=^i4b=)Y~6P{m7%Ko42Gqlb83oxfuL3UvvczjduM!g;d)agk8?yqvNg5FTQV z_%^|Onqhov3!||Lgrgf4NWXgqDbH-rjBw?s_fOH{B_!EOQZP-R`*glt8vq%A4eZA& zSdO;|%Ni~JOHe@EvL4+YzE>%LYB0C@Z>8DwbejLZy+vk53wCYCMmd`drh^Kn9a=?HIpge2az+D2RWS+cJ@!dY@d7|RNhOp9^a&Q! zo9Ko%ZLSu`U(l-%{ghY+WL&Il)xs9BG1_g#_*okVn|&MX3`%O+Xs=~}AksQVuPqqX z=rr))ZhPpT3}}EWI{jUx4GEG{52nePCTKe5(x*IWed7}@u7*!@NrU1yq=6aUra^R2 z{Z^}kJn~aN^;2)*67o^@760!j5_r@5b}{tR+P~A>BwTwHd>SqAtAEB)hYzM|u-Y@!0VmcJWr<~PGVya2XH(h_En02uaHvFW2q6jMQHK&~du z$%9$V^k;UsNO*>4<)fZ+(te}e+C3KdmQr~noEe!4ujgLCMNQGaX?`;Af04>@7PbE} zaI3IzW^b&H5l`Y0vG^BYC(ogdVJNpH<|lP5=)~eIXj#KiYyvjx#G=F?wT>;r_wT$* zw7{(}GcgffCUo%J%w$vtJdWJjF9u|bk^otw#yb2d&o826Beiu7mB5e$z#;ruXu#k5 z{onun8(;d;mp;s~w81r)()vwzk@}H~!80+7$7B+@oxyK`Rozm*RMS9Ss z)@-OC{=eRw4&QA}VDUd1pVoe^_utiHr{plM{vn2l{__O-nW$`qm+q{G83OxULV~nF zT!%Rr01=NX$Kx&{NlO*q{hL^gzf)KZD+K?kjf49pP=FUf3F=F?DaalzcGa&`3_Ad# zSP(}aB#Xtl48Wsq+v7Ev0`@5X23qjp52``naWk`fjK_gb z4MRc(NkUUrcN2dZ9jhE(kw{QC+5Tnf%hX*3;1R)T=m+q`8a)6w7sZ|;(BW6_x_#H7 zgx>@|TKzY%^f#m5G7P{v!G6r}SA+0t^ygEbms8pU>ciUv_(A+%YPG{O!F;B%_8-Tn zv&0x@V&epo$M=oGm@)tp$F#BBuQ3}c81U60b{z@-2$av&|09rW)_UiNb)W*k`uY%4 z;`ln?0B`n_;M>q8BL!gmrqTLav*14`gZRtDWx;=1F#u2teRqykw263>#6&xcgb5Gu z&Bt;H?ThLbc}-Fl_lOwS9W#$XJ5(?VTx+5Zz^A{8cR+(V)gU9INrWQYJ*L4Kb_PDh z;o5A)%AiKC0HyuTgzfS&dw+RA6Sipt=iHa;u=>a}f!$A)-B>(6mBo)d?Im@78kDqk zz|sJ^b>(k0;-3)kFQ`L>X$64jM&h=`>c3sPAN~Ei7?UVkN-r9^>5;pN{oAbiYoz$C zLGW)Q^8dHhb1(p-G0wlPf6vP)?*R#64d3IH+o7T!9j5Z=9TA>731uX^E9s819BYJ`=R#6Q{qJfaoO9z7ncxS)wpy)6=+ zN8EOzf8v`Y{>^3j=o+34E0Fx9(eOggoPU!@0rcMxr5u0BJOEnZ9m4-81z0Q*m}~(z z#j`LdIB=NT;4~F;2b2t5JPGqs?}qPh-V8;OU!ASZhM7APWD+C`Cf)(&4LCDDeW3Xy zzV6|%B{!$tRvRgRfq`-uxE4l`$f*u^!07%9Xu>p1z%u=Y7%Zv*G<^>%FP z+;r^r)RxoA0Hi^%FSZ;r9`1#;AV;I_X5q ze}hb5x9{rz0l@6MZ=WL}Bl`P8@T)KZE4cc73(Nm|i2XJAt3PJ|_UXCPbee%Q+;4Rq z%m2+VUME=$G2<5?it3Iv^m~9aj`zDv(hUJ;@(43nmfC?^vW{!(x zczW&CX6Ax10IaP3qx|Y|x9s(plX5PhaJKC&`UoaqbcGdl1v`M=Gz@^T|4vT$Uz=+T z2lF?q;>x~0f_>5?L5xV@Z1~>@awny4573V2MKXzjCCp2gbQyQ^E3Ed(9l*T0L-_1T z(qDHms2v|GM-l%J;okS@!lYgRT^R8k3%UX}T;_1eV|*Qh1nKFrP0J%K_#(97@BhS4 z`~-fm@p#x4Ac+m^`UEWr;)jpZ{=V%xX+N9{miFkqk_KUT>%QM5=1tYn9{I5!`>{Kp z|NQ6icM5-(y0fs7(|Dwd*vL#%R=9y|S>P(~ki_4IEB-gyUsV@BBmfl>{+Qag)>9oo zJnWq$jW*i?U&Hl30e*(?p{Wyug|C9od&MJ^)I&={EcZuBB zHTaJzfVhl5XnXl?zny39CLHG=>25u?Z8KaA@UP}MOG0IvpSqB=kj#Dk$j5TqLA-^nbkVbGO(hIhU zez=vU2;B+7cW?RW^p(>n0Z1KhZ>IrC+qCi@W&j*aSNq+c{K=oZ$M%1rK2+3=b}>L{ z8|GK{zcy)p;T(@r;+hDZe;wB$)B1jM>q1zL0e?zi3%z0+*n0^4j`E`C_Z(jjh=G(D zYYd0qf4KH1A-}pF#@8mpB~$=L^jB12sUES<#(46Z%+=NB{r5vi|MY z@c8W@R+;1+eGsK%Ts%B8_q+F`oo5((g#6WIJXgzyON$F(^cpe$S7*a(1aMmDO~#xI zdH@`^@t@<@f_bYEMQ5qB8NRXbR=8VQ58ZPR#+i1^!WiY9lB-i%3>`f7asdX6Q0Vne z_}1-f;o9Q;aCU44hM*m0reLjcS)CZeB$H@?2ayIu;!oJ>cKse|Dk5=|Cov3!B;fLq z-M>9Ye+wG%SHAkyub!j(q!~&9Bm(xRETR_@D;>FLUl^s6%Bio*=bI_!0Yen`_{9f>em$k5JV8>+|1c^}j)s zzjqq5;f>mSxY3-!;I9Bg@q29Y5gz{hmJ`wgz>S1YB3L1I{Qc`8ckdbz{~xfmetTpDP8Gg;_~U4P4}Dy>PVXSZnOmC* zSMQ$>FE3pP7c27w02+mjGd>6%1?u9?S_fGiMo$KM4%W zja59l)|j$Qqye}KqQc5zx@Ze0i+>`o+SF>Hqjk+PcJg}<4#iBW87$I>xc{ddXN zKu|<-H;|O3IYrW@DJ(d~7(-<^;{W3>N&t-D==f>*U!Q=H8zue(2AzE}H^#(2rxkUi zX+ry1q=R}{B!M@ZBw}ciW_k;^)k>olHa5v7INBw75CNG>j*Ds$(PnzU-s2<_kmYe9 z+A0Gca|Xmqk?fFsXsG;4XvLpLGH{V|BIP6na5dGVM6R(JXXU?)ulVyPw z$0p|BG4Ff+^D*>*D_?{EVEv!RP3hcLH(aiahqIM#_z)@|llUgR@iDY+-&d+THg#;4 zH@*x50Q?#Fr*v2bfLY-xQy7kL%Dyn2>b@;Fc|XLVtn@FQ*7u}9`VO#jZH z#L@BZBoxVzvQ4rhF)Y#gS(c~j{TV!N_r97ZnzMw<{ z7L3*UYG)(7@y@L}{l?Wrn)&1osaL!3H(_ck#Ai3yN{tN!9I z{vv)_;a@-ep`b*>L7i45uKW%B)5ZT(ztQ-z;Ws{f^PXok{99{{hwIgaa37-o=1MKR zar519znU=>-K`Bk2xbyDlwj&qw~AsF!Akhe!5$5=PSeor*%i<3NvQ^_{!k&ANuwUF zY;?m9qx-+GQ4Fu(H9m=@u|Z?R2}b~-_o?491Hi2q{+9qU`N?Pi*dHZ$yvcte1v%iW zEy50XfHvi@OfGf$#EKt* z@Q;L13_p{__+jAZX?%{WNdGBHRvplfQYdhmQm8`}zAVkWc;6HLQsF;ND7FlBbjAT3 z;`DUrt?y-y3_qV?%r_yTSVfjLMob-P425C*&lM(H39YHi&EpVuJJ5aA;j{<-RJgZQ^F{%Umd z;oD2y@VjuU_sDO()x61bzZND5xtb%|Rp|nljM(X&3iqs{k7^={?OrAT2~vO&46>$( zLs7yfJ8>Z*>1Vwpg04=Tc>19^Aox|xHa70l7xcl{6#WA>P-H!gx?~1J-LzDAn*Afh zN&IUtZg<{9Z(I#?8`bbiXFgovC&k7mC1A|%Zjtz_KaL4xNZ`}AFZKUd>ZI!Fpv8Vy zZRLHCO5wkcdMgd%K_9d4b>QS~gZT-s=X$Hx1j%cq?`sWpTV}<}Ot)@hgMAf2v!O}0IWQ50dmZNylUC3{3{lZSC9m3aR{()s{w$>XGaQfh*_WY$}#^< zP`;b+JMxM6Ck9}I$WCu@{_|7~I%07m#S)(c=coz*(SM&n5j{ix!eytIWEVdEuLz}! z;a9yoMl9=mSlp_I?=IECT>``8`?rDJZ-;XJewJa(I8(H=jr1Y6f?lds2AVctLOvIL zd4ujLaJP}z#aG+j!?x)0Z9Y*~B<|acdQB{`jI8H&koVFT{x*27w% z5^^NcDH8lAu8{4AlhM>2?S4-Of|+TJ`LHhdvPROQM!AXsB&v|cW>_QDwqB^CW2G1@ z=wRaVrc*?(6+mRYu^zxJ z147Em0*pdunKpqy$sOOXLhKZQt6$YXDj%@@nDP*V|a>(I^83XII?lI-4Ov*l@S)42AJ3!XH+40<`@>RTqc7upa z{hLSpU#wO_83tgqIZ5!J2}nO8Wa>#08}HRKG6H$(vTMx-5g?-0%fFEyVhH6A&SQ*mik4X#0I1sM{&u z!}7lmh8QL2&s<|FOf@Gk2~+r=+5Vr5adb)IcwwlRYlltJ=B|xk1X!Zs1kEvVQCzeh z^!pDxKF4{z-;}_@~8@%LR{BRG2Q z{Q%4KF7@~lXlvB7xz9QE_Y!)mQVx&ZF5QR(KSw_BV*Xt$ds$ic8*Dd1eg=abNGqv! zxSVejsxLAE!#m4VJKpgnhj>_aX=aQES~e&Tk@y;m^Pz=LJ`wIizc7uP8>>D1 z-#d-(gaV;r3!|M-##g*_fq6w!w&D2zpQE~>vyMLf28;y4rZXEe;iCj^nql34mcJ>2 z;{hIZ=wZ*~{97(>hBqefgtsSeht3>woJrcxf+9u$JpRTW?$Zu=wPRca zcN!m{(8`6|E6d=6emFZd8z#m}VS%iH1r|tg^?u;KKpM~{RcJ|sX;Ni`$5_Cb+$ zd>&fz@BhI+_y-?lU)mz_k#5QW2<;%H2z|cQ$|Ts{vU{@2NoN3thcb2W@Yc?^iUO>W z__M7JbpOB2{>}m+>cIeXu=ekv1nd%OGBN@f0>+m`BD(XI{g1c<;@@HQUuhM?_cq4D z28Mrkmt+9G5sJ+_p*YbB<#Vl2L{}F@m}cwZHWPLf@Ml%m*&&cjclGz!FR<#l!2UJp zN7enE_*1yRSH0&w(fvU|&YS8V$MzUF320Rr`O!ll~_#=;Ptc8oWZidN?N;pS=r@2lU(lH4T#&yKgZru^yH-M1{ zA8G%9kBJNbus2Wv^gFEBA>6Le&A)z_lCBn9TEyV*RhbX0{3~yr35|Q_A^tGIvq)p- zF4NLlXjc~rx4Z;H&3wi3eT1MfVt@lp+ri5;ChV;BL;YGelq&tOur><=@M5(3KMxzH z`QJ%k;%u%AfHoUVk}fU50K7SWD|~nQU3CAsurP_F0v)+S7^nJSI{uVhEAA}Lf;)-+ zS3q)e>)LWyyz<-rr=fV74LyzzRO@!-xg+ad1m~?=r1kg^RyOzb)}u z9r}*GFxW@O%v}&(m~PiZk+H~H^c4U4ZOnHVm>iM|ga1sCpk$iBKNAp?68Z^!|1-jo z`uZt0@4&CJZPYl1{u!mbja(S5mI>Z87H0Y>?eEDT{;B0kY?J_C^BzOt*2bElMgX85!GA(g>Bj)p2Ag!> zGq>gYTr}lfpaVD69%0*ATa2?9sxuecFz0QgP$Rem(lcCqkPeYyl@{F#zdFT;q5>xbz@Vb0zOxwC zYXn;9t%N-Bxy$)3D-@sun!K&696a3PJQ>*{E@ss7dt&8eF36-2i8A*XiT42`V+pWi1Z_7A% zETfPxr`rVh@jSn~@=e6u{V3k|BY=BX#F4nO)q3A!2_#8zA`_5@h>sHY0Ah}ughxxn zGdr4mpM8vZa^+UYU%C!MP@&1yP(q(qWM!i$FGft{yP~u@iJbkeDD|)nPqFyzFpQy! zS^~ZQM57n3K#XQs`Oo#H=y@Z?(N_MQL1B^d~O^imMq>Ae{ zUxScibeLa91iZq%tIQAP4B6zA2<+SaHcg|#7PdDVg)qB387|(N2s1U}H&o}t3`U$; z&cCC?{2w0kL-gaL`f2c+u7AdEsKW*{%h;W;9vCHcZfTD173+OKiXi9r=1p}B*wx2~ zf`}Ao90R~gZ!1)4EF^&8i3u$FSvU-j$bMZE=>c41geUHhE_A?OKo{yqo{?}Qv;>;+ zDhvQCmTfvCB69?oJQ3=BWqNJeK3QPk1y8zwO;2n|ow$1|(NEO@u=*Vme=YxSvi&6W zL)1Zm_(S+JZV%mAa}z{!A4DSqkokkAm!vx$w>8%PCh2|e;xe=hz5D+C`{9rO^cye$ zl`ww!oiP6KEeKhbprb&vE@3H_!Hd+}6>#0rpm_v>SDMR)q6atItKXt+5I|P^-K{?b zN3##Oby%@PoDH&Vuk%gnOF^Qodw{IWYX_Za{W9PP(v--LqtnueP@+GBIzb|;i{TU* zFI6MBiqn1|5q_a4F@!#(TQ%>92q9dM45*jdG|gF+(wW z9BGA-%Zo@iFz&;Er!d9D^0lfz$o*XygIw~8(u+u7aP?7IQW)1b5~6}ZWg9Pv)_ul} z_T`BB6(F|JOTzX&?c(>=QCqCs4#llnIJ4dipKiPu7Fz9a70s~*fG5@cFLjm7iKsCK zw^dZHD#fv5oHDAMu6)c^U^a+V9sxB;uDW%MU(Xlk1B$Z*|6x&4urq{79nkK zVuXc+s}?>>7;WIUOfuycKZ|nyWndQg6jt?)!STzLJ@J``qAD}ADOHC#d3pan;!z}fF94?XsMJ>inY zw7++W9a1F}?&kDXDA6TT7l}17O-sdiAC$t7c_vRJ z{vso#004EYKz6*zV{abba(J=|==a1IJ28!B+IK4xVCP%?4r?2$O-#tc|3Q6F90E!- zQW6u$47gg2Vrs`LjZwVpk$=*aZrd;cTgLmxsHg@wH1P><)wYNQ55YsfpBraYq|V1dHOW;1MtGp>cZL9l87kZqJi!m-y3~LU9d=CPz zWucVT)m@jZ)`wbH+eN0XMP(7s({+7S3rPx~OPAd$qabBQ+7JnUw7R$7Xq!5G`_R7g zS^gGP6?A*FXsjV3Uu7Q#z!iQ#8luY$ZHYMbXXA0MppM zCN_NP^?L{Dk;UuSsR-y|xPh6cQYI0JqI@gKUi$ z-A)s_IobWAa7uR`VC%y*ABK^MF9yEp3mL5a*^mP~cGo4z2EgDyZ6s+yMjGBLY5I8C z2cx9#9N^0yi-m5v8#*A$Hn^w-Bi>{`dXhW@2zz%?8YjKNa&ZpO+iZK-bOD*WZ~CXu zmOl>zAmJBLS{aZCG=hOQ*gC7gky<l-`pU~Aw zMMEq>kjR34?F68veQXdUT0&ZMsK>ji|3^E5y#vGm%c@(Wtk53=uT)n}($dkxdL}N&Zd|a{7ggnxK zDBANaJ`Tx72mkEm;&|Bl{y0S8d}yD0IrJ7@gD4=qm_!cxG}Qopx2xsKN(i^V8wyAO z##aiY{heX$Um$Ay1b+`P$b9E<6k`-B=GLNo5~5wem@(8D5SuP@bI@YnD@j5U)2mLi zl3xhDd*>kR8nre;QDze+Ho`JfD-!(}*oT?e$c5?~BcZbiifvD#M*C1`PrnF!PKEyL zj|1?C`b*fi%$x^ihL}^^rsQYt64wxX2(?$M`mIpKaIk=DSOGXI!W--^&Yd{Tky4Dj zO@QVb`7n)l!ArLV zK5pOZB>ob9gZ~)+|Nh8&=*^&3MEswJVUF{8-@BjT9{__9jjFMMU>y|JG3dU2>wcIU zt>X=)Z&OQ;T|^RKMSAO@~GF!5cM1*6Yh4)Fphxs~{yHB#HhHj$1OM zDWT@8a_YaK+X<8+V)al$9~;A#;$l3zhWpTy+GWwekZ3P)%e4vvyvAcWTt7TA6S&j> z`x%lR&;Sv3>=?JP_d(`y%OO1<5j&5_vl5jpt`K(_WLn|fpb#*wNN8Zc?sIrj_6Bq1elc_lcz0a1U*a!3G#9?>b>7Dr5_ThmFfFfPUkuq2YpjalNr*45e%dbLXeipdC!f9!aSXHbk@s}n6 z>G8$BJZnInWF$$N;2{vn$em>QJ}NRI43sbs$DQ_qm^v_`3%9PpLy?FlAY- z_A&A>4P?X$UIAiBFBrPvk-NtGZ$kWIs$W*x>+G*XxvCP|XapxLP-)?|=>IS;;o5ll z;GP|~Y5=oG(e^5qNV$2p$AF@UFA?`V;ZzeX%PTn$RH=OswMa5f6uk_%C_c{L+~HJ0 zG|`YzH3Snd;(nuaF#>Vl2yK3|)x6|}CiQ=On9s?M+1tO^T&9zD4XzZsh-Z7BjCm}AL64^%~cJyLRrzwS5MFzk=;VHXbw*R3L0Cn@a=hgUI z;jfnZM(P{Pp8an=&@b6jl9XWsCs4->oz;N-Tk~ z2J>>0d0D_Xw1vG=4^e1T_a5ehgq_GOswW!kN5m+Jv9DuiOIvUOj~hFs=s?<^O#&qB-CBlH7qI(VLBGGqWZDT~1ZbX`c^KqM6 z;xh*|O5W*x=Y!&WWo>CcG6?=AgD`xr``ahd4-an@*LLxy&@#M(p0<}qw0!=fp+9;q z6Z`AQpbda4!KYE=fMT#BtgjK5&k*J5!g@E%lJ@r^M8yO^Nq;PHJ?RCKkFo;HNg2ns zq<{r|PCE?LI(=O-BY-%tkNXy{aiAFogH+93z~T18p+A97b?r{bvm(olpcWGTxUAPK z;?qBkgiQB7BoI>{3q4l){St0|XI~wN`)QYwhzLykyg$MwKpO3Lz_$YIfY1xC@#px* zFGPw2@o$;w?{+tow?@Lnl{4XT^;|gHmjme;h( zHSJsYmp#Sj48i`6I}duGFk0ikZe%dFijA;1vmEZ0){FMkl&>`smG~n|Mz(G4QAw zz!4tIi@yP_`A0AS0DYuAVnL+<3`(p*q%TZWh;-lWi7Ph#q?XiyX`4FOtrWm&`(@wP zFwn4r{~mRyFqN=&jtl?@u1jRT==U#X5ZU?ULln&VSm}?3n~if}6$7N3?U}HM5#SPI z+b5D#Z<-(yh{gMa>D0AEYv+hsp4QN(?{Q1-L^>JY%?a^-+8_F6Y1}qw9-y6(HVnUK z=vi@h_iyQV_jP+5Yf_-)e-nh=Wp&pYc`5W?{V~EGp!1)9A-E=R>gIrfNmu}d>xcNvC*I0~Jka(@qzqOx1~5z$Zn?Zn zo(jAG@+89QUj0-yC;XBqx_Zo0<0_qN%*}B5BRm|>jlyzht$z#g{2Gs7wlF*86FRkW z*t&5(H11wvZeZy5iN6&3b5}AWzX^2ys&xdcqSM*wyWkg5_RVIP+A4(CZoL$Kc=e;J$5)vCGW%eBZ%FP~yA^>Ay`>epmi7 z0vXvKW+V>wti8U{@4%ET>i(KPDnT0Njg!%_f;(p%Cf4TC7BPeysvY&(t? zrp_APrcO-T-Ne7hVBDdxf062M4+@xoH6^QYs#1Vh)e&L!xh{r55nQL+u%gCk;wsph z37w9?edb~4Ao^oSP{&~G%1F%|TUY=4jja^js_UXbra;a)+_!Q>$BUk;1HnP;XfO3s zjt%@V79_ z-(5x;yrhF#02Ag65gMKsu01jWM)~t*arg7`$R3E6+VoYgfq~`L1Y%p% zDfxMVAF?tWXUS870eI?qe+Ev2gc_a{8$>5u-w5Lbc{8Vqk%2gnyH)+7IWZ_VCLkPwKlRRCB~xc(IZPVUow9)D3sGswA+&$dQ#! zWV(_8-ouaCc}CyO379mEB$*qn#;Y(BlaV;*h}Ng2dXLt3=a3SVuYfLDG#Q6t4CXG{ za~uE#De4z7OZ-=El7$gV?dEM(ct|m>7*B$pnP9#-<+!Y~2@$Bm*(x;zu6 zi7t4#afYBxlhJ7Nut}R-`CA>IRo4DDu*}~;0+2~nCg{~7l9fyvw6lW_cjVYB0oa1M zsN`x<@1G;>Zvj4ulnDGe-1DCGt0Vfww zVpIVTVKwJs5mBo2BpS75kNGWV&SjVY#DffdMvIsLku`IK#QN!_ZmkETI9&M@%K>KJ zQ)^A?Fkd*l4;I>`R<;W2clD=1nM6RQfOIEdnFS2i-W&Fp@GJHf7rj&) z3qQVC46k4ha;M%7zxT?$P#Nbpnb>pa_3i7SWzU|i_jm0w&b&yxevJ8W$Ev=wiGkiK zuK?f4O!yp(H+wI`0L;9=?B$$Nouu#2l(c(3KA!YB8t!U~0W+5S{?{0f@4*i)h0%{* z57VD!43Gen7Wg_|<;uVDZZ|Y;x zh_aUcuKeE&cf#+6KSdQ#3m*$FgdYtb$NHF5!u*xJdM`yLqt58x!}5PEw;7hkNL2G7 zT>s#Mv6rOps0VNOduhtay_fG#U7*KN|12!i%Y*_Z?#M>J9#(MEZQ~YQL=8|PFpwzt zPz9vag@eb=k3Fo2PD@i=|5`Eu zNC4_e0WkimApURoTYM?a6&Y$3jZt7`dEzHLFZ=dDnhI>Aa0Yt`B>-JQEB7I;J&v)%ZB`9gp%u!_uQ# zVt1gZib7=>fCfasDg)4F^)F#~??r0`3o-D4-C3B`I!3K^_?&XR9twP`guCl%9yM1) zc&y;Pe%~Tebc}?3`mR?%ydR|p^rP~5sd5pfVw6??1XRr9sLsh+vhQ=#xM=Vv@izis zvx+JPg4iLrRACJ_E!wQm%?NQw^(6knQh`*$CE^T>ZD8wAg)oz>X_}ZF+H07t(bf84 zial@agk88ySi$59E9I2Fav97%uX*8oKC4o^O{QGwYv0#U9gbhxx8k zd+lHww>0Z^!c4DVy`w}Hri8AP(h%D)PrF*PGtq&H_UlD&WX z-1D7B_W*7@t$RfD!mzGg9U;2c<?Ap07-@QuKxG~my8jvMWee@?DWvSzR%wjF&EViuoT^T*ccwr2z{s zWFmeW?s=;Wf*CC%L-3eB^Jm{3{Xu!C zAdFceP4Wi;AXR695FMdJv4ptO2B z2K&ho>?geOb<8=c1dXYNsR|LsQ2Cs}@b7HrW01`$kc#5}_lE2r40I+*(wqD`s9)c5 z1((UJOlCu=z>_SlhF>Pj-dWUQ<;F(1bp5;G?($M-T(}w5!ijwOH*-7i^C$(Y@FGlaMQ2oTr^V^`k@<(Wl< z3Jt8{nVm=g%*|^sUW1C~)rSDz{AH6|bK2&wDwJ(R)x-YQuFUHlsI{U*Gr7ugY z`ENjymj~NBV1dj~uN&<_<|7+mE&h@CQQb1Sj;Vl^^r{?BobA0UIqXOKn!tr z)aO4N_eJy$Xs9+c36(Y7kap2!%n#vKg_6z*?WXFH(IRB zU%_mvxCKTj0I;5mYODCfpMeJbD=NC*ZMvkW*$E(^Ngli~RneaN!&?rIuRLOAA6uhR zXSuZ#)7E`!B>rq`7-Fz?3BN(j%7F0OzpnO8{*#mNE5eC&hapG0YtL;OAuazE|8HOe zumK}bC3e2d=R@e&8?+ctE0;Z=`uyZ}572>1+q(oG>eYw`Ph__)OPt;emgJL&k#QGe zxyR@;Bd&r8e^4< zF<@tuu~3Sppz>^Bx^eB5&1V~b*aaiep_KikZ+C#XtfuqTN5Uh9bbao-J1Qbrdy z@qynYc~%XPI8h8SGVH^Y^@(O#*o45Z7Q#3d|MTlJ;r!-8I8VT#1yo5gJC4|))qk}PIYM!amGo%UzL~FuwF2WY!n+LqLvXDa z{6`G0AnB3uGZ9t4ML;N4``yA+*uqG69YfCoDbwrN19ZsCA`VwY zbl|QNj)6&OMox7YFLq=AHpZN%*e(Yj+5-*xXD|S82yyTQ0AG`;SGk|=@Ob#EI6U5R z(iniOTeCiKKXss;xMTG{F#f}`2nKwpNc6L;e{gRQe_j7H{EJqcL)SfSS8(a7`$wm* z<^Lk9{}t*o`&|Lbl3FVQlkl5K%4(7v$2opMx+vc9{Et1u1UBA(tW4xi?;@!T$|Qq% z0b~a=t&y1V;B~7^#N~?>D2WtQ794#QCf!+swOKA9q;*MO3O z#56l5CU}?li*&1uO>+yeewYv#%-XISEc`?r2o)6=9 z#==x}90SL5;c{;dx$F$B-P3&4=aD3pk_9p$;ezp|wW3b|QG@NHI<#r4bmb!}g$X5ZwXE zC6hDpfMZ-Jr;(QSeB=PefWxnK-tXcr8)5wXJLr@dM-r~&uC(xvFNTkV zOX1^dR|y`2I5}K~1;D2q#D8>DzjNS4`f8FZpnfgC{~&xf>Y2?l@QLs;By2qXE(`D^ zi;@K;0Ic&v8JEDnwDs}uIo@}T6?dcgrEt4Uj`ed_!o5%bWT;+zB~!<tSyVosG$1 zt-x6o>&flN=os!rxyd$ zB21zUD^BqZJp8cTez>nbVOKLvHR_DX&mjJ-MZz!NMO6sVufBaQv^S9!8cp)W9}NAg zuZI@#LcTrsI`$#+;ViK78lQ6x*w&_AVNHQ>)20i$zhx-`bv zhN)kI7X6oa1H8o5(o<=aKUxzwxJ}iG?EdhU!{aF@fdNQgo;qlFYbT}-b!&UAYd`Zd zKZ8;+{8j3MLYErwCrJU~N^gKT4>vW{#Svu+LT{Ll22H3U38+TPe}MAA8z1bslFy4u}WcA70^XK75yr(m+HkBvJv_bGt zAR_8p$H->`RdoZfVc@u=z$70%z zhY5%WSauaElkntAX2GDOOQ*Q0o<@yKEEwo1;vGz)_w0^WL#Yl~q8d@N3vrH#exh+7 z(=ah-50K&B&9uK=?Z*{ADmf5pXe;8U|JyJCQOC-vpF9H5^FsgY77~Cq%rv$Dd1NAa zR{y5ME})Lfp^nKBkf}&sfe~UEliAGJP@LPcUKcWl%A=@kkpND8fLrD*y(XWdhrbHp56MA0~mpZQcK2 zKIKS6w(Cs*06+jqL_t(7Ii{OZxAS_zB^E)3z+j5{`x^U^M!HK*lU@^PVUySr)P7Ee zbPkE3YD2P1MoY;O9u$y$JY0<3q7--Zp+(!^9go>4IgSekjRJ)u@y5>bSD{6Jol^iW zptq9=kY+h~{US#$Rd(Y!x5ru}rYEVS4ocg^NhLRdt-?GM_)kn?{ZDphD`|aY=0Ug27J9w#c$FpK)Zk|gxCEG_1D5GtMHZO(eVB6+zrdOiAXSt zB<#v!*q9*`pT>bR7eKf)SPTC$Oq=Q&@mov~#8#B&Ksz^F)hiv_lF{12MenNw3%buR zH!#?0;vA6aS@ZKS1|nGFv9scGjB-Up{4>mHY%vO3*kQcIx}Fu_D0U-fZqJ2rV)ntUZV9Ggtmr)9~KQt%W}c*TNc^gqEh)LZ7t5Wtg3r>R7n6 z1x$42NhCZ;?I04k}?aU%?Io>C|})|8RsUP~)c@?a`<1t~mTi2etC= zk*d0JX9`?_8!Y&^ZSp7xeUC*#_tn>s3?LdYNZ7fn7z`sSi4i4%L&m5B+^uxR!!2Au zTZU;z{6AA<&PTvJOt%0HNRhiRsyV#D3aTb;r14)Y8Ls*XXwuid_{A^o=M5keAdsZ$ z>^KqSxEX*nb5h5oPD#gZcMyM$JHPmgzlahs{93wrd&{63^{?B`7yz^X?ZL5aU%uat zqf@~j{XQ-w_lfwogjjK1|9`khe{(c<7S1Zdtb@Q5X@bB4$tb|5I|V^IZ~EXK(N$d% z>a^~&w#_raE}e(?UxoOC?Tjt|e(Ft>&|uvkni!NJbT5s;0Q6TvdA=V;FENg+wmM`K ztF6NE6F+_&{r|<@0*U}N%7)?*9G_fqg{jtmnFx|ASb49%_-fdIATHfs36rfmVFD-p z3%z+(GIW~2_k@em480B1mD2-Z3}e?4#MMl9_i9_=?Apz68^pOb0sODbhRp@C_)RlT zFMJ~N>z5gbk^PveN&=J)M5IV#BcfyrGoc$_xOWX(thG?e|6k~3-vybn!kuI#KT9jT zmHYvAuhG|(rbSyG2!XKD+2kC${;@yCpa0%?SZGXzAKZF1e7gQ&k}{RU)y{dM{7pqB zCNsz5L5D7qVprlBW2P(KALZVHIje@{S!_ejqAme8=kJe)EA@qNxpM{^fXVny5!F$P z!>XNuZiXxQ%}{{>=wBqE4bwuQ7=kA{<)}|TUH1v*ttA)$ME;$Pe5ibXHZ+%s36du( z=%r7AD}Xyh@Vys4lo5Zd{iFM-%&2gu+a*-D*V)#KbtHMU@S>8vL-u1dCU;TU z#D1UvlMKV5U0GfguRxnU@YkS8pMU|N^^skZu8REu=y-u|9e#5UUi$QooQQ(U--foP!vYL%a5_$F41=r#F420K;A|V69FBeZ(X!BqVZpu6&RNP z*aEoncXanG4qvPwDc+em^Dwe}O~i$J-t@sfDUOfRgGq^Cm+3-1u)Cj~Jt#xFamAU& z+d;Hi;>*~NOd1SY6|sM7E#!NM{71H!%p`OvBi=6oVhmUwsYC(svH@jANtHVRfpLYb zM)^q=TbD(bYlJOU!@Lf|J5uGMziiYv$LqReHmk8J@0j=|eupGGO_wLrnv4m^o~bVT zY?pZcu(>(<>mtc6x&)*t(T;_+t+1J6HH0TjcWMK50FX|6de-Qfp&$scrx!rxCmo4+ z9D`aVGq~JD3II{fkKad}PvyCJuFVs%En@(f?#>xHCOTOX%*Ff=-8Pva>6{Vj?CNBg z!~krbjDF{vb7b{9!^o7PbVh6c%;4|n{o;5;eLUZ}NgCc|j6&B(2>ml=DqdFQG;{<* z$cfx&w4pd`Na4L(mPLUyv!JSmMiJaK#;m~RGLLX2(wV()Jl$sp)6*4I!UyJW=#o6D zTP5!b2A!sk?l8{%5p?~yt%i}y5PV>4l6@Bo+jv7#@t~-YRc*U2LkqDseY*kO;v5pj z5}tT)%bt7AitXsJa3}7^#?oL_0+~%gPFge%ZCd`ySH5zVeQA|6E732vVm!BgwKYDP z?Xeacdfdg1u(;j5pE}Uav=)E-$A4V@@V^+I=$Vy2XC0s@`bSrZ*v8`njx&$;(hMv_ zXqzCpyAXdR0P9-*$FYl-J^aU3yYi9yL?qgG1uM5HVEYBn%g!F4Pjcus^Aqea6>=?B zS6bxb(iKdpJmy>(fP)*S%XZ;FQNH?QiNpwuDOS;!qqZ2k}mqTNObkmJ8?x!Fzj9GoZZFw+NVlO zphcso!*ZcsA;=B@-6UC4rMrgF74nNxA*@W@B8)J1AU$c$BBs^n-$6_EFvJ|6E|ghb z#iN)Q?i?;YJ=z)QVX#E3gH2Yeh&5t?7qwemRD!PhO#;^3yo9wsu`jUa z=+2rB9Q{6){o(9OnY1a1`Xi$$f_=DywD(_z0T>}xK!aG(ms!L$km6>{r7L)`{XvSO zgIq|w0wWQP%aJm>;518M4#U7f`H!JZzYPO$k>fyoByhMj)Hg2Oa2aMC1}p@N);9 z)3?zd-EEJBdjL{fg1&FzHyHpUq4iEq?n^zwbj8JL_&HQy_Dp zYDTxRwOb)~{|yLGJ(P%lKlYIpR>O#)RqgTELX~*=_a?)c@0}w6&_sB#b(R1?GXwp9 z=Khy`#C!j%xLIQJHtuD&3%Ht%UkaV8p9uX4T=7`tG$5RLeDYu3m=4R0Zdk{7PU0*h z;tKiwD49I~Oe_!A=+X4Su8Jkj|G^?Q3Hdg)5w49~$0)8DRuQlM30CXZM>lZ8B0<)R zuOS7%PQWLiN{QowN-nqd$BgsaNLnzfy?|NmC=v$!_!+WJ9eD%8R9QsSkFl5f{qwgb z!}*oDFvUE4wR^}lHlMPL7?vBR>E?5jpRwh z|3AZ5fl8t+(a|4&GVcUDgfWZ8z>V8@!)W0TzOAf(nrVA3TKM;_ekSy%E`eKJ7*I#4 z;slvYaqd2)3BG<453U=eIXw?#oW&mChlt~%Z~u4!+Y>o~?H26wkaz{}V!7No40KGFmJ)m1QGF2WDi<8%yx?p%eyW%PRJx&H7 zeWD+qiXD|Y$F0Y4<# zaFtL)ywe0Xid>u~PC&ZDPBm74WB@!jATm-At;ea6t1un|dVZw%Kg5HlJxzR&)yu~&$U0=N2S1T>iIB=<_~mwdv_T+t z!yK(J2A*v(7;d3Z4GZ098O9W^Jqm8`G6! z^JJ$f;h@#nl{SC{3@^)wfG3tF!t~N4;arL3-=D<@^GqBIjWNx{C<~-3WA+qZcJv~8 z_n#K{TQD~o;w_gp!p1luf99K^S>$_Ip%%akBjAD&76ihCDxr)OJ1R^hI3UZQ!GCh( z7-02ZBMv~n1YD}t*7x6zdIn1zdjQ2iPCe{94DQn<(`vV~fB+8$Acr)49EsR8H5r;7 zFb;+AS7W?t;O#Q7R;B6@&}Pw)sRHQR0}NZdgg@D(j2DeIzl<*BJz@*wdEVeT(xgk! zsFmOQz2Bq3Vw6a`96fJO)#HpfW#{5l;oPy5<7NP|etpn6c0%eX3BR3XwVlP!eC9LD zZ2v3jgCYQdRH6hxe}BcpM<|X$O!|Y)Nd14EiM}Nx001F4mj8RWY!4kxR{S3=*ui92 zmG@0Vf%qwM@7vcs{D=?a8D>nL#3luNn{zM##nok20jvgD*>^XlqLED&Hy#j>%Xg(8 zMg5KfD@O=RbP#r*3}87XqLd`pBS(D9ETkO<`z4qF7=s+*{yt*d9ByZMLaXL+vC5a) ztgt}ps;rH&#yA^Sybl2yfj}Ab#|&@!l4k@lf$Do5F_FGH-z?|5M1PgOSVDxpF-~9} znMkWy`6dy2@+BRt&Z~T*$!Ba&pO!tHlD;{Ue8>!#mdI7N#&7x!s2JI#kISgauoMXA zwx&W8B;JGbjZq$D%wz%@NOe%fU?mX7mm!;|6dc+d_7-?QMtg$h2FSTVq9R29A8KD@ z<)-{$3?;;D6!oj?m*i%xNo{*?J>ggwd`E_+flb2F=z3TjTM0{(>tSP>35z^I z9*}W7GiIu!6K-M;f=F57pO~e?w<3cBT|Bj-Fyh}z8Dr2%atw~wfdeHZC}f_|(7#US z?iPI@^H;&f3bjs$ReBd@uRnnlJqHaP1!mOui(6e(9fV@T;a4dE731$nM6MUt=rUqwB^*(FUQ3I zq>k{5Q)jrJI?S!-?Ks=$w*KqC{_9}=@OP*~#o#|UQ#EkYVXKHHGnN{<yKpx+z`Z?~tz_YglWv7(pkxH#Om7%ElK^_7o+4MqsNza#HC%i5X2=sLN4GOQ5+pxQqa?WXeG>gX^9!En&pM&rZ= z>4aN|@w-s+)d~TP*(x#6sLkktMmcC3?GZvN(#(H9p9zqE-oEChk8ge+=%^c!%D{yQ7VvUv=|`L!*wqpJ;x)kNih4zpVasEiI{11=c10 zM`8eApn<97_EdPQc9CE}u&I-6yaG`D(f@}lKs<|xZjA*Vu84U>H02%4_}_s>{rYeG z#&4*m9;RI)E=SSo(EDP6#_F+Uct1Py6#hOPEVBQH_|d5(Fi#!hv7Hz@av=V{%<+yM zxBrs(U;U08+Jio2_Yg&&^cI|blbWUf%`*NS=n-r&swz&di0?)~@Bje#5sx`hhVmti#Ej~};o`uqd@xmEVRf{WYWiKh^vR5C4 z$i|oK^C!c)vNEVQ2o)={qWFKagb^SCkT$8KFo%;!V`M@`!3h%tpqXU#pJf)X^#W1$ zE&IIYF{fGm`VZr>7V!>h2agOQb-H#929wcegP6Quk%_c*( zA=r_9#20+5!!D8BhaX;(dblt(W zYK^Nzdb)`?%FKW38l%K!9N_-6`ZrcOj7XQf0d2&bJw(*PM)^|uv;#crgK!C>8;v8~ z0)eAf5X0;9jRD@+)f#F6#t?=q>;7z;Gq4if=)}Vs3*LY&56R&}E|U=Fp55#<+~S{X zKC&Cn51wQHdORo*ghWisy#E^atd4}S)v<7)I|l!*1#+%_UqDvn|O{H`~5-ABi z&XT=dHh{3T^q1f0m+GSDzDFKE_#1cQ@Mdg)1LkD+YvSOspY3H=KH0yjE{JW2z5iy+ zxcC3gen0%q**}V_e%uX0;dR9R+GAi3(!($j@c?lLrXd^`Fh!h2DKt&r+t#BOd&PJI zwxNpgUwx_>ikGo}IEzGNo@bA|m!}`SUGM9i%(KoGj3E8m#h#*e?-jyv%n}LoO6Xnu zBx~nSWeX`{`frQ}k9avTgm`mA9H zPbk@~HFcWX;^#mAdCa)61p-Y{v%)Gr{&NeGj4OXli6b|bE_(FVo=%N0a72?;=Ng>i z1_nQML`ILb{NH{&PjTg@iwZ675k0O0hig25|DV10h>>*L5BpB#&T(?S>4p0;!=pq| z2K7wQpe@1nLgGSN7+wiBV0)neP#bLo2;kb@cqs$k8PLM8VG;B*K#8PfK0ZG3r5oN& zGj~Ey=dS9?<=^joeY$J<_ViR$SM|)?J7?zW@2fAK_|KuZz%_@we^}E;51;=69;7~? zzvTYoNC0cQvy7#p{$u@>7a%$t*kuSlJI+Qhy=;hn^!+lVZm13lbvUnGEQT>inj*Hm zE@pZFWY+&9y#Fax@w1A3HR#&~1=Na*#M}qq&9Mpi64j!qyfBSe|Y~={OOO(S$GuQwuJ`TI2 z8D3l}BY1(ZLT%J)W4j>7ibi(|q#;3LG{{UUbkxpK+LYC!3-_M|foc=|v4BTPNf3hY zCrSXuH|<8L;@F>2FdJ=jA*i}FR6>OEZ4*tgM?8m60<_N{@zTma>HNo3gDBl)UXptZ z6$AM;ke;=W3Md&UV6T#p&oe(KQz5`m<)w|%fy$W~0uA9{xw>=Ws7v6ijqiW|`!p;r zh=kMnk-z8sZAlMjzs~XRz-^yUooslT=IPjd>M#kEf}P3!x7iK~%SX|F90)})S%fA9 zjoBci`<}hm@?ZT>3;j@)iSdYmeR$vjFt7x`8f&bEA9N3^Rg>FvktB3$q^YbERgLtO zdIV_k`l>vm2hzw3U;DQ-OP=xgFqfqj^+6Vw&Jb*8mGQbzL&Qr6(IWF96Goqn(>tn< zAYV{n%GXQU-0tD4BTo1LSmGFqHW)Dyz zY(YY(PVk-C%z8Dyj{5ufksPD#Fz+^3F89oI#ivWr;d_tMSo z^~LPs_NU0-q(5#(|8oqEzr6psCyz7tkQNhR8yAre(f|M7&AG5a00{&C70D2 zTh!qqqHW!MGqfLkE##qayTz?Av-1f$YV=0vq4P?12Yl^7-~K$@l=_2i6z7q+yMHkq z4QLwNbpKh}4k6#EVS$W@w^+-CH$J@_UcY-IT-aI)U+vu_uKaA207&zX<8xMB9k@tH z{r~?PeoFMeTKH&YHPkL3>c5PAt8vZcek`g14x|CiOLxN7cm8&$Zf}Ibqpk4$kN+er z6D#4%;YRptAfyZMrWvg?p1Nig_E9E#0P63TTVeVe z5P>rlJV%fQ&FGy1(!lqB^L;!V_KIP8b0%DaTfGu}L-Y%=$44(pfkgg)89oe~NFweN zOetK(of7XDU1W`u@p&u8W~+aM^yLGHRtekNzl_xDs}KUX`z>8%{zCyB%=vM)9XgI& zF2r?V+XheH!^7*kgg4>{69gF!yf~;DAXQ9t0D-w$WE0J?Zj0n6$Wwn6a+Kc#XZrNY~N_((lvu_Oj+5hWVA-H}PndNm7ke;b~8va7~L{{Z*w5i4)%Ig6Waj zW`qe60IC{We{Ms2LLFc9Q~iV2f1K)l(z$eP*gfOG8qTD6#1g6?;+=y4oMX(iKUc5k zzpR{n(6YIfK?IS}9uf8A{u|8jo?=gdpK7H3k|;&&0=lRPI^+XrRSCd@#dscFW)(f8 zDT7%7Of6g(<8tYL!K>q}-<1s-Y^N1fCsnNdw*mT(r*}ew5Wh3CBz+<>We)EUjYtoN zT~8h?)pLYCE)bqLb5YF97SBp*Suf{74bK-15gUxDXd>$VVH6^)_?!)&DgY&+O5G5) zB915Gq*AY_>Jrpb#<|9`H^#q$UpLH$qxj#r04=z8oPs$!%11MKp3>(W!2Ou(`B%hQ z1Pda%8Pxd^E=%~$y~KeZP8)}j0C0b9ABbUp zwfc8M5|H)h(LIA48Tn69&@Q1xl>pQ*{)@Tb2YL9Udj!~0u(PD8ym$wij|o1Fm}&Pz zxPJ6RTB#H8C5s$+(hFXlJFgyy`baa5ZK4B2#5=QJ375Ky7f-8v%YAtN)+K(zb&#{*`Ub{? zNS$T~je9B9972L}Rs?md1~27LRU`ZKxmNc2+W*De`{9$yV-Wv#_~h23P<$PX1mZ7U zqPGye>q#OAj_#l!{@Gmu{ydr|B=k&Jsm+rViZsMng`CAML~>1~jrG~ao%O@TM=|PP zZE+{GNjDt1e?3-Cm1;vjia)8=TgF`w4Y`>wXtF zzX74|8lOVcvoHbyAo}kSmn1Vfcj;1R-re`AUj}#mn9XQj;v)S$DpH%gg1^VKO&2en7ArXib1kn;RbG17qB}qlb=R`B7d#uzvx9oy9L>0ke_Yr zCjPJGAB4YH`bF4T+zaiuaX0-AMwA%)6-Y;{=wA@s)peIGPgvT8$K-_g;35RT99aif z$U#6R!sx09u`ojaIu8u~qaDI_z7`%5b?`?wJ_rw|x5DgY2#!T#R8R?rPH6Z!D-u{D zf5Yf@8c3|(`x)KT+MfO+CJWK3uVIr#C9-hTV-f5<-JG53yY+Kx*A68SJZBIBi_mh&V4`XQ3X zPuuLE)LB(@|8~gl9&ca_{$rFexqk-3myObMEe!r@OoS?%#v#McgyS`%CWfz^GmIso zAv0Q$S~k}JETblfs(@5cEB&gRZx5utS01Rx=q@9!^*>q2=DX7oz>7#lqT?(I8|6l8 zSn$_~VNji)$FHAnOfy#mej1TJtw>l#gFs@XbN|*dJPU|xZD%t)n%X3H0oE$GQSM;_ zGf(b-Ons3N0@-}F(c^8;)2jM>&)ZI|{57`BeEs+G)v%u54x5PlAIxoF?Y|cGmT;q7 z&4(GbD3w#^Zuk2*U|G##-kcBwrCO>H5_&(g2QjWe=6E@JE0szp4Qdhva-W1UJF_)5 z0%6UR!VFpN4nzNb9*2wIUok@G9F4;oKi?xGC;i-O;c`hN*Ra2hoF0{c;XETK_C5yY zB%*l4A#jMz?P9DK-2fY?e8t4W7wWC(AH#+o@5^EVJn@#_{d<4!?@0jcvDq4Dn7GZ6 zecERAEM8B?@x-M5oF@U0+F;{SNyqLJWt0ej6#VBp*V26l&p}IT0Ei)AO#936C=vkO zL+T9PHj_c$e**!HHW^ZL4r;0|x0$QZ?R6ml+GLgMp=O9j? zC3Uc|_Q@{~&|SmtA5rft@%Cqs2AN!T+|mF1BzY>KHEI}sA(F-bsyhppGY3r2-#=PD z4$@{Oi^PJK)0MffM|$47m#U#jo`YJm5Uy_Rl2oTf8;sRIAKT%wGKlWyy<~n6>iV)aZTbJTNelDv22Ur${~ura>8mSk(G|^jE(W!)yD@yFt)T&|!~w2b(bZkj5N$ z_TLSi2as+>yr?dJ$xg}Ux{@*Hy!wMNbdap#ww_+t({%Iga0~daRKWAb1Q>J(B8jOR zpg0KXF?s_;M$}P`Z}HE~-}sH++WMnE`hzRBn5`ejrB9_jm*a!J;M~gdAOLKfjZO`> zQ#?+cV@Ji#`qf|kRmK1RCEJq)aev2{%yp8yX#L;DQFjE?t+-!{{|_4T;UNZK47U{_|GALf98lCzrlH6$l)~<6OWNf?9A+jnOo#Q zAPK0fgxZ!EOy>QI!e3+bAWvOUa0?+L_nqG(E0M;fjGu5 zQ#g9zW@b~RfozlpoDDu>vPYWW=?Lqu5clQUbS1ov6kr;-pTiSiV0i$OC8_|h1IWRE z7D^;BGk=G{g}?y^L4khz@BZDt{l7v0$iyDvHI8kB3(|eRD&Sm^Ki`g`3HRq!jzgjJ z+kM*X6gw;YtAF*cunr0TgU9{Fg+%Ye^+Pd6?w^i#^$uC2`s&d&q=ZN)OZz+gTTb|B zq*&qXNJZPtLBS$I>{jtDui|oK+FJ-mi?l}Sfb7hxzZ35PmYalo4$)(&Mtt{e2!L%8 z&%pgpVdSL_UE?76fwPxvHaTDQ*N^F5Q331~kO<8%FHHS==>I(6*93$!*bFe=_p4i^ ztDOratlGP9ANMQuP%2ijR-caQ0AuVc&CnizrzoT8t_Q5yx!)Gy0AEf0tIl7}e>;zb ze|`%iO9K4NJPsc&KMbw8W>~&Z3DcJ_;UlQhA@|=u%z_o>hAx0TRCZ+~082O^EgfWq z$P7dK9~i#Ls)DousA2?IM+G1eQX=+1K{bSfbhg(IU!n7S0(cj_ENmuiEiRI9iG*Aj zNa1Bc9+2&IyaGrDRDB2rurq-1E#m65Ae4pgND88-m32;3o5w>G1HSEn_**=0A}Z6q z8w)_jFCzZ|`#;`Bogfz>05TPT5`+v7vCrP~-~ZEp`cMDofA-J*87Cr66SsLKZPq-y z)1$2T+xyR@WN=~fpXzU9YJA$;DQQbol6#TAtkJjFVu@mYjW66()JXuiV(qUXx=qBd zwSODrzt6yL83B-E)Bk#HEJaCx6srJ!mPw4zFHBX5gZ%&i!&g}FIG>K?Q?Fh!SPuw8 zq8pM%UZfv3y4!LW!!Cflk^jbr__O+mm|V$lCfp@lJM!iaU_;$El#SxY2W`FI-+lhD|+kN_8Y=B>;4SFPBO5Sg_b=G$4j zUWC8)tjN^O{*A$OK&-meeLDX*+z0VLo*~lyrF~-TgIwkMLHrTPCNO+LLkuR`GFT1K z>PS%uXIPGXrwnEEzOtW%Qdt}bGXP@3Ni;$z4Tey$cy#}JIfo*)ZRkI=H4y^^Y+*{P zh~)Pn;ZWP;%J=Ch#B}W?vIUkP#!#c98i1mJ;MQr8`j=o1QTWGo zmQlLZKewft{A!~%IIA8u}54&QBjJuJ27m}u9druVD? zUXJP^f)b2%a3ybr4=P*X59U7(pUmLEb$~Vk79r8gT15KW2Z&UJ z`o{!T`Y1dMJ5#mr{x?1e58ikj8cXPBuXe-IYxHjk13o$ben0=z_=7d?{HU!Fpyvag zTPG;cqe{5hy&Q8wEJ8|Y061##6V}=2k3S9{hfnkCVG}Qa+|^E~AQsPvlV`)PQNRD9 zJ*UxSnIvFzN$6phF?9`i-XNDtgYZZn{%ceN=;leiTzlthp;^65lth@Q+uvaOI%CQF zU1I%IV6G$vhA57MabE1{3V7f#u>Vm*BDxV~i?y&yNM=<5!xRa-=#AFg#)uR9uhJ|8 z-3;G|E9@Emf2B*CpVoyD>|DE6Y z9rgeJfGrk#Lq^{9BBPqwUj}Sf4q@Dk_s{Sk4AueR?gpTtVI!3qEyvoA^Hua zEhGR)8JJ*s0%F8=#O@gDmtVc?sXaiSGhJdJ5{9FU+GigA&KU2>eeS7`j&LE907URW z5E>8*fq%9z{Av^5zpJ}b@_Qb24#ellIf1uH8$-6;rFo_tdhRWZoB(Efxt%bbBhCfJ zsCpo{Mmnyc1Nbr+$vi^CC-_LJJ3Sb=f88tVtSzD;MC7`o)&J~v*wC+jiO70OaPf<9 zWV+tE#1qsxsg5qm0~LU30Hs7_LPBS1l(Vaaczq-Y&Errb9I^ElC0MuUg<##jC`Isi zfPLKeNO#SDi~-xBh#Jd<+Up{Qsb9$K=;h4nFw&?Bf<~LdedYP81%_NdvfLJfzbOT7 z8x)9vR}GMv0s79ti^C>v>LQiSvCe%XHg35m9e}n+I&20(Cc}1Kj@_L#CfJ>7v z=Scu$-Eq{W?D7bOCW4mg9=OF@2c10y5OVP%}3p*^EDVaQ6nx;^!PFr!^Xcm4VF-i@#Ra;WYiM8lPBc6&B_*zAN^165G-MM_zC9zJl%nWGVM1XMeH}DfBNF1>nKib@F^>NGi}%8#>CLb| zO=i$H$kcWfZh!tDw!fhEY0VK*Ft?6+l?t;0a6LWgnwZRO_u<2%@78TfB@A>k0$|vY za1t>;kxb_#uvJ$aVb=c^JofwGGiO+0bj5T1<#?t2ZFfw(99462pXzU%$7%D63E?N? zpZ2>@RLUuDds8fSEEbpTrec2v3L;<>462U58iW4KhfVf12H%806DdweZ2%S#^)}IE z;kBUnxr-UPIqZ8K=7Yf7axTN2ed-JO*EI@v*CY{1^+R-hyKsjam2kDQ8ZEq)0%UsL z@$?R}6=N@S{-CT~e7+wql*7*LxA8$|9xPo6T>(}!bYlDuroc#FjzEujMu4Dj@dk4W zBQt^qeRAO%94tr@mB2fnd=RE~x5C0+J^WJr*J3!gwn?}YWzZuqNwXEb{UsQLDaeG& zh}8-1(YN&*2&SxAS^Li5?xRJM1CWd#!G$Tz!C4 z;BkzlvVZ>_atRQvHMbC&JO2eC1GsS-BH$AH6%6fVws5gM8f*?vDSClbjSASBCoBOG z9w7iCGe{MND$yp5XYowS;p3=FU`A2epm2*#Tn5X*M9NxeCEdKisqW@i)0VJ-ztb^? z<1gny0Hj*?cWY{B|FzU1h2Q+m-&FtqTDq9_nFIjj4*`(%S-LXZUar5+z$*pN2xMYC z93=pBv4MdA06;2S7iqe#Xo|ElC^uZ?U)?=i52V3$FHix<_qO2m_lWJjPyB!A%vsiF zX8qqkMTh&$@w@$;5`YYO!Lg#ZY%MH=_5!eAZkeUeycj3M*WgqlfYQb|ux%^~0nz4z zu-55jvZ zcZsRc4RhCvp?no2P4|`#68d1#b@cM59a#-Nt8r)!_1tu=5*Bx6!!ofuMEuG{l4Rs* zuXxsZB^NFJHK~8CR1aHo)v&p+N2m~@4Z^`5a{mKV_gUY1DX-h^)ON5yk%+0Wh(`<9 zOJTIz*+G)>7`0DBN$MhQyq|;|F5F;jj07P9+K6u~sJx}*BU>gKT9njb;|36a~nktYl zGO;i^i~%D+Ksqp(8Eb^!JTw9S~Bp@u&#f@eAast;ptxDb6zhL^qm9@+Pz*2xw+j?#Q62Y z`c&8?g5Wg3bG!P8WJt0qr30V$tXDJ~OvFIO1!p~_(^Mi3GVQp_TDB(J#~*!vvXz?s zm8*9>Gb#s&KKrc?zeiq=fpQ?A8gOMBQ`=#E3Ze!3hWpd&*ijHtd6sa#R|up-Xl(*G z#xUE_l@9oS7)`J5`%gWj8i$@CsF$ZZnd_fMf2xI$AMohOZF=fE`!3i{B>>uBxV1`z z1cy#59t8h6!>jwg@;N=E+Z{_YBj&;NMFTip1YSe1bx7x&%TEJCnKSj}(A`CpqH&-R zSoMx^?mweA0~_FiU2K7-FhtNLe5A1!kVkx^C1)J&SZ&(r!xqK; z8*t+H8Vg|!@&8t9f+_$fp}Jme03-sch^`(2Krt{XF;8I;v!S;U&*~xXc~yq*0hUr5 zw=P{T%j@NE<>QOt#?P*WrTw|^_4b``30EV<|01)eA+O;-s<5FKgVFp&_(fR9HSL3$ zuZG6eJ9vdK@Dc!%jQSGioN$Ih7QwK39ikI^1Q7j?zP%n*1BI=%Q2zMmp|H0Vid&Du z^n3pyl-E9q7Vp2*c_XG35((ZuNHHYx&x|FrNQp{Kvb=cYx9B4hJm*4oLibPU%vn#a zUSEB+`g%wZ4i}`T@4oJQs!P14-NbuDYk!Eaze;R_ySLWD$0YCRPGh_AI!0DYpw(Hn zm2OyGA#8IV;;!G1-VgVGJl5yrKf>`oAWm{r^N_AYYj9T((R+b8>M8Kk<^2Z#&!B^CAGOWm=YL z-`^4a$HxEn_pcmpS|$O&_a8lHt{}0T8jT835~8 zD|Z#k%cY2*ox77Psst?V{T`)@-3$V#Ok7INfG`jC=|cD*R-G>HgkpY;b}L@-;LfL5%YFqINt{Z^m#Z#kQkCDO)nKJf0z$5uoZIJr>$TZp>l$XSjR0+Bo%wtuv2(AqxE>=(H$El|eUVg2cQk ztvvYzH0sVbH_@=-G{)G4He##+;i|Xk8&l)Orh#wpu0fxTmFoK=K8i7Eh$#~p(3zJ|p-KT_lbwC_ z_l!N@H0hFg%n+|#mfs9k@fUkb(fG{>?`PxhK3lmA!J$tC*l$+4;T{&=kH|K*J_ol_ z0qUy;&{$~z5#?v!e#SFNA|*7n9#~K3kgDZ-J0X7!RL&{mqwkb<*b}b+U$`8SgE^uk z76Fhm7|oUdvPFznD|P(j;hgdSyb>bR0_So7&|)LoN9cw@mL6Ns7`Q2d^l^Wc2xzc| zJ7C=oYodWPq){dWH+5T|nG2*eAUM}__=GHLk0II`*eujns2}cpMCAzuqvjdLm#%yw ztLBJnN5aL}|1EUPBn%9tI%%00U z7`_=V&J%VSYJnp2!Rg%6ZE$T3wch)v26iCieg$G5qiZi3FT=V1l%n&8wlLd3fin9& zh}s5Q1)z~#2eF(zH!_yd-@Ehe@TaS} zaBsR8nwO_TeF+gIfqNowO03QCmrU}v^Ux$!5$nMzt=@zpLjAGa3B@a*I}G94h}=KE z@CiZ#`2IGUei9C890vm%dSp$+k}c?-twEN)@-!I2it8LJWyx=NkMkLzIz?2%5(GBD zv_XKC7Tm9ptlN|-wvJ8L7S{4aIJ|Z* za?DfLkl4WWYuO)R`&riv96<}uko`}n{4U%-ap|vgR>BozAI_1p5Qw%_NykG_%sb&O z;fZ&`gXs<0j0ApoF^dy0MF{-fomqMu0>Uv1@uRx$Dg zhARLTd;)#`%Pew z8xVy=Cjg@Zas0rO_sQ3v{g*_5#fW8PAgLB~7)|A8GDS#l3OB+lgvUasu2{TFyozYB zDzHVOLGCRKut4Z_IC#|>^eIAuXqXk-bg+~P%=c;Zp(VJmE`W5O07$J;rYeYFPO(6V zoCZ_Zh+hE3P{BQNh5F30Hk6L_AXM=6FAzF;evZ_wM)9K`tye^x!u2tfL<@EGIcF=h z3ehn1$gW}3k0jVlUqK~F6z*a1piv_j=AaD+oi*wwzG%-KbXVl5$et+j=s`^8^ScnK zPD0`7KKp|S>EI^de?nh*sRitJUjylD1gJ{btuzEq$fQJmi|_hAq+3>%8O8pP!uwA- z^?f$0?dAn<^Ej0>A+pEQ*$M8?g8)d4vKb!tZ=OpX;=T)oRL2J3A9^7c2hkzY^fN{Q z1Y^dImRK6RbQoMCJ?R3d&S#f_a?=jaFHF2RYX$zMawYOt2Y}dtb82m2)P$Hg52ut# zil|9{k4?N{pTiII4=B?mN7&!oVbf!w3dylH8n33BSEjh@H)qbXp2kd{8$ zy03zpOU&5<#DE^T9aJmQvppmOja_(N;GoL9_B4PHv3(apA-{mw8)707^4Pz`fGJ1@ zu*XIG&;6>&lupcLiH@RM7X(U=inKcz&pt-YP{xpxxc*wvKe1?sT`x2tffd_U*<~KA zlNf4`#89;2!J&f_@^AN zbFBDZcs02~{h}cjEQ{U%x4((FbTf3ONknw-{m@=VhlNN}y=GqMNUubs^z3F$uF9W- zHyho}DPmT){9VGi{uE{tvGT(De7M|Qg#ge9FiQY5uI4K4)q?#K?Adpb0BkNJ&c2Pr zk03zd(rcOZzkumQDEdwBZ5aF>Y`#I%JZu4Ey5X|TPA8}B`s&WJECFZ{VJfWx9BDMy zMLH0T=j>ydE(n9pdM~U!0P!i}FR^A<#v`4z002M$Nklmkr%|#D`B$&DR9KU4^}lkC-O%vLC9id)IEsbVwAe& zR>W<&904t$IoVR>+^6I86)WxLRGMg+Bmt0mKJ9HtYFIkwK6QY5J4YjlqY|OGP(~oc zaK$a5?DU$W+fO=*69(>IBA|`F#|(f~M37a*H77kViE~y}5ilH~;?8b&Att=Q>LgAY zg&GpCksOs2dR5NW0}iaKn|>|qApzJ#w7XdfQ~OwWW7KB!yCavivwbQ(%?t%}U_^%m zUcFp(Frw4BUUHS3yD;`w_uRq%Y?mxl=e)u~R`%6_;&l<-tBJ zJ^Hxg9OiW`IQ+si>rAMkv;eWalKdP7Z^ae72ri>hXKv?_3b^X?d%PdBs2nbMJrH_y zk2Kp`jOfN%nFfebuMQG`9#I>+s3&^+oNN2hldE;CmM8vnYWTcsE)Tm`AtdzN7J+{V z0Hk}P#(zg10I8uTzUsu2zCSYtHTX{}>>vSnys#72=C{M*Y>DMhY=xrWjxzk~v**6Z zf9YVISfaGQju%&Z2INmH0LV5bF@5SJqhkl8t{gAD2|7_F4BBUIv^5~)+|c6_UnahC zg1IRRI(!XOEt()^He14bX$H7Y8;7y@J3a1x?B!qs^sTlALk9zCH5y$?wRIvSZOVU<@S7-?Z8R0_WTFB8&i9oO``uq z095h)MiyYwA1vHsobssqAJ_NJP;H}7;YJ(9|M)E{jS6Nl15xGW%oY0&QO&fD;<|(# z?^PglrXhM}FNW^iZ3v*ZFf(`)!ste5)h~x8$z3`GW6~A28xi>)-$nw_qaIonDw#0M zx5f2hzm*rUoQJ!c;+;tEx=I|d+&6&FsKvlgT|&*m6@)2_zZOXet%`p1DV8h_PQK zY&Pb@79Id~LO+f=z|Z{H({6~!AMWNhNi5oUJAVLY^WLX$K^M?#VE9dw%*Jpm+2 za7#wCd{sv50oGiXq(99KV#4nf!q*<%4tLhBhf6!l;TzpMxOwU0ou>XtQ**fQy1b?H zHTHTynA(4r|9RLbw!{1L*F*gxfN2Gx)?w`b;od#gyVd*4^}FBxBosdUcOkd^ekiW) zhSHZen1{e5{yz~r|7jJl(OJWVoKXURgL~-R#tjQqS9b%B!w~dhL54OPC{x2vcbr+8A!GbM3G54Y)i41J$el zdk7y==h^*GzN}OMqGi}2lm=pcwD4poZs)_T>ZS0_?pqK5bKw>q$OeYah=8Xx{`B*z zg0utq7*)_F25S44YGLk6*dHy!{o}I1-1^`Y$i=LTQB`mS9m&pBXfS2)d|3`fXT8%1zUATXe(MAbCPfPnUigh{J zkrdWP??3yI9phpEn#yV8QXBROpn}i65&%Q4M$k0m(ufil8n3NQs375*LKHir@#76t z0Ix+|e%R)l*kg40NEg>E7%l3+Ie=}Je|;+ClmN*6M?&AaaFgl)+y%olM3j=dHpIKP zp<9(B9Hm65BD{n;WSSi+NC4(~GtoO_JUJmU34jElfsMM@L*%0bfabgi(_oZNdl8;- zjxk=^^|W@%p@n;mNws=;)ofQX>1vF!$-EhoDs&Dj0g(G|BDRmIfk&8L+0tQd0?0F! z^%F1oT?_$#kFNB#w21>P>37;^XS4H9yd+&1$9~cTfOYI|P&#&>kiVe7V_1{8f1Uk7 zIp|0Y0Nqg9aVA|Hc&{;r(f{g*{~H+o=@H<$=Te-QA_9}aXslvnILxU{2$GCfpG&S|k!aT~dL z2ws0LT+XhMe!1Pa8Ab2C#vYtFR`GiT$3Zn?zKl$NOC=Hjk3=&>#r#E(KQTKn_zLai zP^uA-XdYv&RqBnqWwf@o?t=_1T@i!-Y=fwwfyxAjQvCm<3SiVu5RowVFd#Gd&pHyJ z8hxD8J_4JF7_#^*eLQ-#UcM(q_!4>SyChL-tyPHUfkcQXo}KA8LhrKnR3QFEHgjwU zONZqAQ>P>xQDqL6NDO4Ym{D+q_$g)sgpiH7U!qG)`bu~W;uBl%oQ$rsK-}kyO*6ND z_Quu3H9BB&g%x*hB{j$orsLFb_eM#A)bA@aU9o=`k-3{hfDaDaBg~(e_-C8!QQL@l z32+Ctf|uoRPWhh3${=$lvK; z-8~;}b}q*hxGPMtvxs+(cdzrvc=kKke6JHc8fme@x>Li~>?zV!1jbLSzn3Aq3kuy|gEe;-o+|JkO{#v&la;44NNoJA6_ zAm`4v^?+%yj_ccD|HmI=l!?B!wi$Zs_hNla;?nB^#8r~_v&l*Tbe)yc!(L(k2XBPN zgDUaXH&`#5B!}68h@tL0I&k+=9ka_d?hzac0&!+%DqQX?M*?vi(IHg>?c$DE#QnG^xg-opL?hobB!W0|P*T zNVKRN0d?~THqPj1OEJ`=;+=z0ee!dY{uO(GKM@%SDB%pDT669h|9E-Qb@;r$pRtzN zjR9%^?p-X+%T27jV|dpr?eDmI+Q2^&0ml8WGL*X{dEcFd$eadgIkpmgBLJnb43(YX z+L051hz`~D5OyAf{Ng$sbS;z#!c&;j1AsM=R1_mmL>?3iyJH+l(C^CD_=Tm=qtO~`t(T+}Yfk=eFPB^Si9XCOcgRWP3nixF~ z2C2JUf(C?i1K4C|`5|Vp3&~6X@!dY-O4I|u)W6$!d~M|k0aQZrf(xUef1{dZkUEZK z@L%GWI7V)CU0ln!YqobPp}C3Lvl@XTH5SmI;og-=94B2!(g_IaO0EmDJ zqSzE5Xvo)Ow~MD(Z%?|bAHM0vZ~Vq@ZT-<7{Q;GJ0{J^D(#%MEAM)7hrM>6IRwhLN z^jFY|rv|0tv}eTPwfwLB+OJ6fe7FC>cuZ%?y<{nX?T6uu^p{=$bt3PX0@&jxXtLp7 zIocDc`r03e7;p{i5tqJKu0!eCB^V_E@NBZbUX>wwz`kXRhBxR5%lkz9!}V`rZzjy5 z0+>eiV{|uN|Hj$3lBl}=>HoinLK(?)=*)toW;u`x?nh=rH0R8>I*BYTFkKBfx5j^@ z{4MrS0Te%F`fVVR*7rZ-o(D#r*;}9f*Un8qI1&_`h#_1hf>`cKzUD5W%LQW>2}A5T z?FN(oK`dAhrygHWS~HGg4>_w(peOPU|tU?Q#} z12s)Hx#=oyf2aT|_<*bbH#GF9^Fze1_}?gywPKT85PL|1Fan%n45(X-e?T=y{=ick z_c^-Y8dmJj|0wo1;~#FkE!J_TiyCO|Ch!uNIYUkrC2OjgBsAlE8Fl31=c3rZYHkY% zc6?$O%@I5StimAyz-&nC@Mws>_FKR88~+vp;1Kt5$*1}^?@qs+xf3hrK>%2J8)He0 z>fhTD`AVfyW&a!Al#0eWUDEz`+Eo~seU9N^hU$(C&HKn6x}693i*6b3nd1ZSm_BvB zdnc>$0PcJP`7vVR?z^G-3z#3c2Cak(^O&i{KrH85t(W<0kz0Tp?BSDM0BBtLcrLv4 z!(|A7x$p*ke6_WLh<6V3FMvA|3Lpjl$$}!E z@PboLISq(KMpg(2WEDR9J5PRxl^m(5OadT>e5^B{y!|P^e98ef?!TL&9;v(MR{XRgEA^tY zP_kG#caVRyci|y0UVFaO$#d(Kvwc{g4^yeMJEr~JFNK9o47;{xi331rR{}s0euaPI zWx@Pxk^oc*sIy;W(HqQ$SP#MMf6oKjM`|crJJH{N53&FD!;q^!r1k3kAB5u67D0Om zR|--sn3c|MIcqs>NqNn_5LnMc{7M{&@UOfP!nH56f0I6=-z1oh19YDg5K9QmVg#ts z*Zd_s3Z_{z=!aGHfZU&100hnt1}v125KSXeo+kOvG!lR*m;&cVhWt-!$kV^V$Ri8t zApR!}G-ChF*=pFFCj)>I01XwvRnq>?6ZAa2_Akg4r>(RrT^1z(5CP3ci2gT_02m`~ z}0)4ho-ZG?|sDKXfmKx zbpIN9m<8&&7gD7v4(&m4_CQeGDs_TtG{{K=QmL&kKvkc6Uky?L23aIvLKj%EP-&GS z$FFa_BHe0Iw4=z$ac5Q)>UVX(ON`U5#pcxjp&P^e zk{dm@_bHO4`?%=e2Uc!|!Xlxk(f1o~LSwYCPOmg)2X2^OXN%(70UwIC1rP~H@_M8o zjyVXFEV#%|E8JpoBVGSs(!(^axU1cHyhAkm(=$X+GqoEH%kZRQ!{*!-`M1{Lyn%x)j5E9C%Mgng_?030=GaHCngfyl7-z4a7ca<# zIvWfPtmhaZoH#O)%(Es~*3lWgFXs;&h=wVjQ8tU?ocQ8AXN8-;)86A$Ja)5s6DgA> z0QxJP8q?oU&-ojW4V*rqL<&lS3dMy2xDmQT?td2w|1K7ussKFB@-?0C!E-r9Bg!BM zt(&KqV5%q>`-2R$tq*~p~hfCYb;k(^0 z$KWnkNi8uR|L)X18R92ARTTTaUtSOYuJS>+JBRi6;!|;51n#joU8)M zv_0isx%pHOyB@-~XAw(6R|5p04(RoWw6G7TeyDpLQUHR)B=C@4-M^3Bv(t?dgVK5- zT-&)2e!2CPut@Cpo4pGFpA`8&HlqL0fsTdHTK<#tH#{zEh3$pCF!e@0EUc1W{vt@^ zJR$8sHGY9^qVu{3;iTIn?%MrhEb&R*-6>oR&1=6M+Be^hwjW{nMg}vZCzaxq(Z=ee zmMa+A15Y$z5cd$>Z-OWGVa}R_s4kMhv5;>L1cqf;(E$*52I-m!g*cWtJXXYY3Fp~} zw58QJzJ?w9@bRCMoR3%c zr(()Sj)!>7XJ35QGf|`o;8Wa5V3QuuxPz5z4k>^^P6i}4&svMm*YgZ^3=(39So*Mx z1VEjxzTH_|_q4Xg(`@HfBm>|+wf^5I?6Yx91i%>nH^z4uFOWL5=1%AX;6uD!bpDUo z*5E=B`!8YqH}xor`ipagn0)FG`Rtdlq?!Zfi|7BA`lt};vtjCFU%*6i&{xSTosgH{gCNcak#8&L@ z6Q6r^GQwg(J4C#?|K=7hv}AwmqC)H5LF~T>;-5kFGlQY1M0G^`XBn%L`&=SmAKXxe z^9SX_BtnF6e54jSZGvU*v}&2*AFv#%)8i9rDy|dK!v#kC=Pk!?>;LWXvp>#F!xo|9 zxJ!S5aHd3YCeWdTd(_NT^qV(`kVa-J^pov9s7S=w(IWO4ulhn?c0RBP+`Djr z?JfFj3)%`R?>TbaE8tbPJ5CjVpH$adLyA{rt4)_fZRtYTC**HqZkYr&veyuJ=cVvX zh#x=u&?Kr~2Q#Judj1mD{?lu4{22R@fv&K?iVztkTIl$yJo7|Ki}U#Y%r8EAf$Ju! z3_$)8@{YTZJALx#&L@w!u9Sf2!_jk~L?*%okpDa|I3p0BynWbTetw_1ut_+R4Yq0# zkcK^D4E|$$g-Jl#VJrC}-EW7b4b`3Nw)qeV-eV-7Wi0*Y-weIQ*Rb}70MMSs2&%f2 zo`_Dy)38(>Bls#c7I&mH^3R-KhgCqW<`m@ttq5#n#9>MTj*!=l1DxjybW1Dp@GS@D zz1Clj|L(sw((xoE09L5K!l{vIpBkPol}Zu-U-?W6yaTajkGRUwUlACduZo2|y+IyBF<2*eC{Qi2GaxfD7#{w5G)BeZ5eViEihYxa87(;DwQ zS~fq|%D$i6M z-Tf#sJGEaBI@`cq-PzE*_#cPPm0PSM!bxBG8tSwwz)7U$ih2e`0B7hfYtn6u zm=VeYhH(%|Re!EXI+VfdQaWL*O zDFUFsuTDBnjZJ&SA>aH=rZ;lg1zdOB;Q7V*EXDux@(pl>k7{3o7Ne4nKRsSFM`vWi2?( z4icgg_BM+Dl>nFl@T}&LwpfYKIz+%4xgd9oRk&BC0?7aD5f)Eq(C6WloyOQ{^VE7w zWX8L!T?psS+i#Fb63-BGN)R(5v-{9il0H~vU9)l!@DdC}A zNrPlN^arL1QAd7AH`|bL%%8M?+)H?&s#5);D{D++sf(-i7!q(=y;F;Ix19jx%%@IU zDk2Cn&dvk5{5T)DB{efv)%n5o3S$3IEri+HRG7v_#Gp`_cOUo+A=V>xcCUDue#6gSPZ~x3aSo-? zJg)i-2+f6M8Um5|gaU%l2*n zdl&Jcsa>b>6@K&Hjd1;@PkY98f*1-6Jkj7f`PU%qzk?0H9^Cys z^vK&G-^6jtSV9CgiV%Z(%3Yf zF$!cgUk~qJ_%!_R%KPEL(ncu0)2oC ze;q1qC3LU;3UnR1e~HLQNS<%!Id5770;-dss?MjU&@Xy!&=RFl-poT0Z%KWE$Fj`} z;k)8I_HH)L6`3{;WAV2oogbzO*^>kOJugUQBW!3I$I+f)FL&oQ{(_wWYj+Q!?+(0Qoggn- zEJxq}Lo4O+fA!Qi#(BgNg6lMRLhUKf5;-W|6Q> zcgxW@Gz$&w{YTFnK0LsI-f2gLqzK)EnIY7KZl~kI7yEW5&D4j_)LxA{{44AlJb^ZS)7M0 z0G3N};`vB=%thno3Y&PD6akPLV*`#Kr^ebyj{#LMYKMicVs>aT*^NGw^nJw0kiHu{LG7VAW(C%+rY9O0R+5&ujp2G;BGbn;-m{!Js`|`k?Q@N>tc6x z@E;b4^l+h^h5%S5-K@b~FbDG+3Tv>+CW4qkx?Z| zTN5MJ65(3&t5|OvryuT3mo2%sN%e*6#cvQzuvgp$i9DcAETetI?idIfci&H2XQON4 zr5WZ41-{x@L^8AxX7Lco`2JCN|7>Om)Kvwk`>!!8T2uIaF9NF;=_FhLUvd3Ut{}QA zjz=WQ8qA;SQfTe6C(LhmR$V`v$X^3mjXa+d@~4^+U+4;GT3~I+JU4WaAdZb?PAbhl z%rF?=B+e7}0YxIh7qq91!&v;CipL{WBfa3H{iFzhlfISCrAE4!2tdA#EzUs^sK?A@ z`u1qq99{p8h=9QXia{NUp$cc<=JDXqrrMm-UPz$`S9QPwiBfKUE%f%6LU-jpUGNYw z>u#1K#gMJ`*sBtIz_r!f%q+WSF@Rqp?e81iYhg7k5Hxft0{C%tmD92bs1n$36BOj5 znRfUS;MLkxKI~nd3H2q2HdB&1hW&wV##Mo5y~l4Vaz}64o4*seiz~fhE~o!=Uyr0gfbF>f|qm=KQaR&hl3x;nBVJ>i}|8 zA*7&&pU9YW% zH`}+u#qMIbN)oQjIwZkV!O?Id#Q*I*VDtSqLUVmSbf<2G_JwbS-t})VX5dAQqMs}EWZ3v(*uzc)rB;~5U3*w5 zKx{S0%&dTI@?J;_NVEE;gMy($#C8a8S-GJxN znM@D4yROMY*rr-#-2P@j|1 z+yED?bq>Xef>?a|I@oU}bW5hqEl0_PqH)FKhYMkl4oY*5eN3SX&(f^{Ac>~eTE}7= zH`dPVb);2qMd?*<7Tv#yUuc)+^!SG1=uN(xtczjg3iW~zxldjIqR8dp^bdn+sqaI` z8uM$^b78ifBt)6*|2TsGDE_Yj!m2sEcPfOA0jx(U%PV62Xspr^!=bt^u33zA+jS%W z`^L?{-LHt~-@GVFjhs8riTk&zPI>W#QsbC6W<=?+FvGXW{pY2AqBMY0*}9{#5%>8k zt;DqFR4nPYdtWy8GH!k{RX9~N{q{Q^r|s}J0TCnskQt_uJ!0pH__J20$Fghb&S&i< z8M0swh;RgqFMOenT5>}H_Y8c2HIu1J&2Wb-DryK`_$Excg4vpKg@WLK7r0E8Hc0im zMPe5a-As21wiU|Ju;Ulav4)uS|c%({XNQhNR@=13P~6IDTjDe{g36 zb;#@t$MMz)zQbNI!nmNowDx|0xObBz9~-l9zc=0rJ@#RR>1&{p=S=`O zZZ_GhdRN~B>yb)(hbV=gd=m22c@onQ31jBnP$EvfA!>`OaLjV5K6b*?GI>sG(}N@%S9DnXB++qK%h@MY#K5(hcAX!#E;n&IrMS^XfCwjNQ3M%aJY343=D=MXlRB6L0nlIh{^Qgz&$&g4 zr$yoTh8M?OvN!;U&=I4*G!g(sU@;~DbP)z^U5sVandL}IF&Y&*?p}S)?-NnU{VU4G z*L|9Zf8`IS!Xn(Qng0y$stO=8@H#&IMz6aDfVzAM@HfDg)v3kMT?OgQgZK&m8LQAgV~WoX}Nr(Q<1Y z^yiA#Yac9x`loPh7vTD@{~F)8iMSt`_W~ST()Ujq@u!}$(h?i0%y72v6mCNR)Icm7 z7$>sT9y3n}ExUz?o)EKTIL|2vg=i#-48Q=uXC(kKqHrG@fb|#xc&C8MuFP7cPh-%! zRM%Jg*aNDcOxV?Wgv%)L9D3IQ`!f)#5Rox8dJLLy!bE%y{g=f6(0JS}qN<^5aiqEy zXr=A&H8&4%pAAkQ@c4KK^#AtQ7mckpB!uhnW20I#Ko;tf&sFYT1Ib<|d? z0#JOD>Hqsboxb)0?ggNV!q|Ekq8QLcRb~#l;7JM63t0Das8U=;;4keW3b;sC@YkIs z>(+zilH4YTZbWI?({U^l;Lqp#+{>mVa!iKoX~K)#ifu{ z-%c5_oc_oi-UgR$f*B#|E?vxp z`EPO^(||8@0e5w_LB{LE4%^O$xAv}wFLiEXM6%2zx*R#X%(r_yy_A7^6TLJ^^|}`R zefV)$2k3u1ZSWsBm<0?rXBIP}Z9Jbm`&%MH2Ju@~Z-wwn{|Rx&_6WGL8Fn7M7IF{B z40!jWQ2fE4BAR@RsYxf4uMsnWpfw_f?jGxpeY?4eb^SMa4iPO}TI)-HJ@kI*cE%OzNkJ z!?1t%O4$3UuFh9N_e(cfKg=VgNKu7$mJf}uXQ?W|X$Tt+1Ge8OVt&Wu^{O+bpq=W^iQpgx8bqqy?0h89nuOtBW0kcC(;s&FOMY@*V zE4}%!5~Kc)Kk8pL_Rd7OJ%Bz@-Vyg2QI_an`u=OI>3Ah%bbgcN^e-iLUJ1nl`c;V( z0^qbC0C1bkt15DgO%x?;Su-x{uF&$!!)X8 z`e9GgF(|D_TGd6Fn;6fW_xj8@itmZv2Nv%W>2wcZ1`*cFK|m_GaXv{%zCb0D08n4X zEeS|Qsh%)9b>lHycIN>1`PwuQ`zK{Om#(MRj8cuKJ~K%IAbqsIA^qn(-~0Q2|LEtitIrtiL@H+4sNe8NgEJ7P?j#38R`63hv5IM*x+1q`@%EZthJ^>1%Fhzv971q#l zXAa+xGVFlD|Irly_79%jNC7Y~#2chhfkT|f1ED+z%$n!Ts30l?U&^hKeQ=BZC7id$ zmWh*2Yc}mC*?+7V)er*E?mhu+wjlg)zr$c6v@ikTEvWj znav$avQvkI*TsE2;t6j}TmM@o-YJg4Bui>Qf8+X(MgIN7q=Tx*xqi=414Z$Pps_`cJ>aTEI zrN;c^+*fcd z!}kyWzvZ3T@D+moERouE8A8#x|7v)%GW=X|PUsEt5LwV;q(D3K5P~58jS#aK!d;WT$o*&*n_+8A_Y;J(|AbWouAC& z)q!NOycjww-^O4OFAC;vFD6gmkhJT$d!OJuK~9CK{jm7PPeNg;MqC4`Pg?QL>n5$85#K#hg-(CSs@6eERT#%TqW3i-?ocM+m802n`dhrp{aXLy zOWTc77214MD&jthM1ZBg13XT@(>~rb?mw>dahKC7e7s>v2Xa&g`%DF-9T)fU#L@LZ zk9aKkavIDbQgNJn;fshwC0vOEIP~ z3NTY70*r}Z0-6>?K)VLq#Yk-l&TA3$Z{nY0dbYv8al)PUG~r!h^uIlV|7^{a!lO$U zBLNVWja_~qzC7XC7wS~9L=*U0XA49?xBfb;4jMSP)J|;+)xbVei}@Etvdk^xu@g%m zL;Cy{V0-;VD@g(n;VW~ba+TNww+RZg7v?Z9yOOIgKX3zNhG+nI1Y3u1hy*|bnb0nz z;Wn^)e+pyJRXi?cS+hz>*m@=>daxVn@1bmHV_$KlfTW6VL7zmhZWo@z(v|7#5E|LF z(|U{-$9okB0mhU%cHe?XnqzF86UI`oK6OND50Ikmu7T{g(ek{DyQl;N;AZ6j?r_`C z#Yf}gd?XUfd^6^9NF8wwoiSvk4FMdJ$FXlcApsb?AEMOqfCvzu$~q$dn}Vp5(%ea8KXG%)O=bj;; zGgq6WF6ecSGP-56W*pVEit2im0@NV@2soDo{h5-30pOdO_GK&1D~p7tz~3TZvOP99 zo(GdgLV$Kg$$`t2lAg_ey|{mE4^lIgw?(2KRuDNG8Y;8>KiimrPUD=28336Z4WuMJ z?JVH_vs@6)3np$E=}-lU3CCR|ne8fsRvxiBx5hXDsTyfNiQc3edh|ggo&~d!l?T}) z0qEhz8m2f_-Dv(1>w&}|;N@ZW^~!isG&tWQhJrCku(^q_hx;N8I8430H$r?w;RSM1 z6d^R(dc0d#&A2)5UZD9!7aW>Qcsx?E-E?NpHeysE@#w$4u5$s31MQuIMHVmj-NKa# zmZu`$F@5u-hNN@u>6xb!0B5TM$bvpKqm#azPjvg)UVJ`JD;hH<_N7}aR00{zk`n-z zCKoA!0Yr1~x=%=y&Zk=A{)&h`Ci9WI2OhK$>&N`^a7@H>fpcLEp{wjPu!kU$TNxLk zi}&H`*j8He;l}PN241s~|2MkZ=-S=Swv3uYzyDA0^L|k1gmvOGbT8e8D~2dr6u3)? zy=>)R`RTgo{2`=qG{jPe9(}{OE-)4j***hP9k%n}*%!IVVlN~bp}7|d%{oS+GvNw$ z0E;wM-~Y4B4-tW`e;ee0`~^NCpAr!20om)?i?~J3vnVx;G#&y5hrRaKLhI&#hB$pK z)SEvHx%Yn>3gx{}zKD{_d<=@y{Vx$YscvOx4U23>$Szq%I~Tr+eFD;oIqW`ef0I4+ z7U}ASXR+TFkqR`3r_gv5YWMC@|3`RJ?1j>WH4H^j5ilhR7(EW0P%5>N&dV3up-_2% z2k8a`NEOa{lQoUh!RaOeDlzf`6vtUwNX}n7fKhD#BJy`WMl^R|2jI`6BK~ERB1`Al zlV-w6=e&0;Wl{uymF}suTC) zk8M=IT#+_K)6|!&O(%6XgQQWPu1F&O_C_Y+?;_rB+(Rn)p-c#bT%(K)z-*X<2$(16 z&udtAoAvJ^`rQS>yJmr1PWr&;=cL*9;Q!aq_dcSlccu`XE`#_NP>RkGyyOruj{c43 z_GIGlQw1ILG;j_P;9Q3SM{k8*FQ$HsohHyU9Yso63CqErD?*fanftz?j! zuGhrbcb-wuVsk;@*CM4j-7EZ-g2r&wd^2m-261ufBYvQY+{Vu zT@N!mxHK+cF9IBjVK0V&+Nq5>2!MQf9RdQ00!D_p&Mx(XLQ&_sI2$0;8NUd8kUFaZ(C7+|0_QB+haTcb^%&lbiTn&jwM01Y!qI;zfU0darWPH=!zJ? zpc8WK7D0d7p|alzD{S*vxK{}0YHoy1*8aL^cvp$_V%U^XH# z=Y-JB`C+!}hK*Cs7}L!v-{YJ1m$oM_NU_Qp@(1RQs&0*Kr>`Nzq8ETK zeX_sAeT+^#>#VW#-_d`ZT^;k^2_oO8*0jG-qOs%D&r=^9_CiE7A{#nBF$lxHb)5%WZs?-3ReKaZxiBmu~Wu7 zof!9HgPJx;V6UE+5VH7r|6*!0{Gjq_xW7;g4;F8S))H=X^XN}M4+Ox|NATskBIk+) zyCUq;?smBIXfIs7yC1IZw8I+^nF}#NlyM?Q^AT}6?=vHe1F?bo z>|aI&FvlFlPUp}_Qbej@-K9I|4AB2WKz8v{A$K*o6y6W@PyUjcY~oze3A0~EEIy4| zZ!RB7yzfx0*AFE}91XekG6BT8BoynmABED+_d}QTy8+|R*4DR}>fBIdi-D}zTkpt; zLybtheEC<27`cl_)=xwI!Ouebev`mPz#!aU^GSszRsx^_Nn-}>~>3c3G81ndCtAC_z3VWkvyDhPn55WhGk>MLIeU^UK` zzr^oqvmhV<3T%t}?Qm(Y8!j==V6d4Z1%Qmm-$m6Af(CD|@gVS(z!;Qx5Qy*B7b zs%CNfOA-L*Lwr4dj1Pg{9n6c==muOgln6#G-F@77@4ttnVw?N~Oz&GP5Y|SX90D>d zqt)(&c32gW4^p&(@5Sh@0Fjj6N2Ff{>^F6jWL*h<`?(_-4=bTf$kLTa2=w+gLYs)B zgvH}tq;W_EMk$(>NH`QAB1C(+jzk;vV1%MK$|x_L&@*<4jN=jWIKs%-O}xl|ao^w1 zS-ll`2p#)h-hZ6kHNn5Ka)Ot{G8`s)IwcdF#;ESn0rNXyQ9s_ z^>hgY5y2J55S}h7>B#eLnseIGb912_L_CXg99W!PgNi0auOxJj;pJSV0{w;TK z5AAfAB`NNo3uLrKA^_JL#1O!GgEUG+NSv7qtr@_lwi6QS$B97^sUm&PSKzu$c?%2N zt6jqo?G9$B<0b(58<39E{-oO39ip!Z6=qyqMXsjPsxhI@pXIeK0(EnG0>Eu58gI`alIz_J zt^68Uwch9QZl*q4g}WK|NItFZ2NO8D=HX*(#yF)B%}rGk8HcZ{UZ)P&Bq>XC1Ggf= zqax=dKnvpi(ky^y8l+ETIchgwUBW=;N?W9taXb;q%|Q zcngC$<^p*;qS*Yzx!@dO9?ygP)o)9rEMiD%7D@6l^tzj2_u&umCas3)=EE>kxCe5q zgRDW2WNM5a0%sgb0}n}{mlyM4`c1+hU%<|Wpkl52f5y7J2ba&9G@z9p0gC@+IBbi@ zGptYgwo9&!R{2*57KIlKF-aPaf64;ipq_xItMo2NeUM^Zic7SsgbIOZgN1i~9`c*0 z0cNp}(EC7%gKNvaI3&Qh_nf8gj1LT#YuQ%m|-+IyqN zS(Tpp*x(ne!1E|J!cFRD!gc8HyXVo=Gki0t09=#}#N^X&v+%AkW8Q;;zXz9K#4Z*U zf!fZ!m5iK7UOOJe`b~3uW5pk(dTSlj6%YUz@73=EH0oMMgWzv{8HFsBok7%p>9s6T zjctpGW#FzOyFyD`{E8B!GT@GK5CE0+yJ70%pM^Ohn=REA!YY!3S@{1-v;Y`i>*e+g z^kUjy1HEi5%!lnOOJR2z;zVGn?q9;}Re5oGKpTMl9c)A-0QSQQhN3sRs}KNrWM=cM z4H<#a=ZJGczyB;1beEJ07szFQ83I6W5ax4a*PqfI&gEI=zA3&H2W!)F`Ag{GNgcfL zX=wjBe(}w1-hpaw<{{iRoH`tGVHTqPtgI2API$CHqNnNGNZ&4?d*9d(d++=hOU6&I zQ+O?e*S?)``*x9b0j@*aWSu?Lyc*i2uR#=GqtjW#e&A#3Y!WGG_6v~TNCDD!;sa0l zBa>o+p#n?2jazMg`-70Xe?R2ri28c_Tbx8q;)|ksjqg9lB8JrtAQA$TtA~JuM#sr% z@1J`aCnS4T1Jd=hPmOhTzAC5o09_V|0RWD=PEyf!>R8KjE?TI9CnG79dN%D(edmA| z`)JL`^@HrAqz>1-4#{N<(4&!22N8dAnNgzG1+Vvrz}A~4l3_st0APZSKa|-j9GBoa zVoF({oC`i$A|IOy26MrxJ5RK_X}&Q>4D&fu4O3)y)bP)LfSv&xGT3c4H^%;FUG75w zv@lHU65h3^fs!FizsRL;F31@k6~-y)H=~c(!IeRR)c^oM z07*naRD9Ge^`G~*;$x!zg?%Jq^?J;kVbUMfLz(UWu~(1qv&pQG2-w3Or-4$vXDC}^ zBn)H=!W@l#LH+F?iC%*1#HfsAA_t0Sx~TZbme*xXtGic6ZgUUI8K-%a?z_zRbd2+l zT}z>YJ8=OcKkWhPitU6gEZ#_n^W`*to+H;ms6fb+Ot*~MPNE*5)5R#+CiTc4F_0I7 zOI+N}EA!YzSf5a;F{BUy8gkm`C;{Nc^nK2LPK&*9(kMS`w7uT{+{oR-Fg(BVFaE{9 zVD(N?1z;cf3AeHI7w>rv#b6;?6~FasU?&9B>r-Kebf*Qli1KPTlrHT_3jq!j2&=MTiBXaCg8_XayBMsDN4qzvfVBPA$7 zDgu^!Q*69|NL&Ob!RlCxc?K>0h~4*zko*>gebEq9qC-w!QM$((hk9HGalH5chVba) zfQ@KaS$iwoXkQ^Y^mMcp8I?#>^shaLsi5BppN2mR?}kS-=Y1^X>q-DF(AKCwACOyh zt}Eg;wWl#Y3J?(A`7PQ3Y4HHH!VgK)4B;|$9in%>7D`3h$Rlx0588)Mxi5!Wp|}LX zX9?zJ>S5_y?~s)bbwGP9?EGStS&#UAo;JOSn$cJQ7RS?~l;h1`X3W2WgzsV4eQz)1 zwy%?VfqtL*F|_iLL^q=eE--ABgkZ%ztT3=dX&I{J+`sFbeNYNjPNjzjO|`~)G`Ew$R7CO{iTas zjAR{C0?^%B3auT|YVHuX8z5m?&q(8>9vx=~3HT3as2HgaU4LtXc#v%+lK#%|^ zy~Q`!%h?kfeHPtev|Ru&mRQJg5F&(_{DZa#2wmKX!aos7@KF%}h^Bz?-(ss2F12RD z1tbk~Ab<6`o5u{*wr(LIxNC5KnqiL1P4GDrjw0lnSMJJV*nb>oNKt zeN>^H%d8)W`tI5?qIGOzT1CYFd=*#UC7fY>)Ww3o3lY&peUW2}p@L5v@H7|L=L&>r zUL>)ZMvshNo&-dpwn>}$?bs(`@T9hUe$LV1v80|k_m)kX07wlxzCWjiI$hItPM@6A zX9OHt#uI*25qfV5U1DR0#aBn)4giFPH@cW&xM&b)kEdQArA~GmMR9-IjA9u0wIDd! zaQ>YhoP7?z{fh2QH>ellKt%m93~G#v4!0a#<$zvZ6Zs1y3(ofeE2U@`W2I2T&Y`v! zW>GmTAtqhI4Jix$bJhmN<{kc#+tUD02|yM7U;MHh zB%o`*%hg9wJA*HxjmVhe#OV`6Cf@@Q(_8U6)msJmF+W1h=(KonSMa0Ays{^5T6`Yxgwb zaeV%N_TKA9vMfF9JmDkKoASQRO!qiahLWh20d}#k!oCUmEA${hfL0Vh36KB*S_sgS z_G$M;`#`GR>=>Hf2GdSm$f?2R#AoiqY)l&Z4gPbN9G_F_7pOewD*R~w<3 zj++G&H=DnP(#+q2g@;3r(u1)1`90RjCK0=sydOeA$cE$fVx%-)u6{if{kA^?EP@1d zIt$3f|3>J*D$GhKLQVfF3-ug}6jDO=xD=q9nuv;LJ3gM%0=6MXOfJ&(Cn4PbG*nhv z;S~G-rQSSj-3o49C&op0M>tXxz_n{0$ z2p2+j@mo;1%nyNN^q$DPaN|XE70Z%)&|1$~_+BsF&5?}WCh!4vKDHRx$c6Gm8=Qi= zL1mUPmn(pr8N(pMQB%fqEZo9X6#wSeYhiJFB3#1T-3+F)B8s^VzzFlMKWJUZZ@EA> z!=tcPZii1VOoz|Ud=Q>a*TUu%wBo0j53a{F&qp0>*M>+@%mcv7n(kfttMtX?(3!a# zc2<_@BM={#5}}62$qkQ=_i#r{v#0~2hQiN5@QGi5U;fVauLFQDbDuRE+tvrbUVG1o zhwuHx5YD~BIIm!Qu@;I;j~Jt6aKW3Qy7nY;8fq6oz4|7C68Xb`Pz#4Db?CwAC@v!c zdHj=5esUWTz!~c9^lz;1PC$jy!pb$4R3yb9q6zWDdN=mN_lu+slXi68?x?!d@hu{Bc%(|**|FbI| zt6}?B#OCIXUfQ9l>0hlIKAFov0H9B%aP`{gZ$ys4sO{Om$k*qtjgM5n?0gP^^Xj7< z5N|<+KmHblr5pD{wh60v<^mfy zo2fuU>XCpv5%{|StJ~40EH`11ycCM~=0{vJ<~@K)@#jpdI{*_90JzVUMW`|M>IyD+ zOLCH!CmEY_4@$CundznWd*Q;?sj#r!h;w8D4uBRS$EBTR`x^)14ov?QxNdhB=fb_K zXTr)X%6g|kfE5Xe=%)F4oDofHS^%Vp?BWL~)nO)xpMmb?pM-WBr`YsuWQ)I4K?9Ye zz6Cf6CCm(6-`ytEci|>@7P>o_?dqT?6A2XHCo0*`zm{Jdl5m*FumNq^D&~A zX}W^>P>;XL!)Pa-tdp`@q??oqk>1r{9Fqub;{^AU&u`-?94 z>|+Uw!H-iW$2wCHIa%tBSSdMsIAH?g$je|pS(KuQh@-`83*!FEr1UxY4Wu1l;NCj} z4`0RQNgx3GH7GSdwQ2Ajc7#`vhO6)@${ceU3HU^-Ne0Cq#mROkJobMqQ?CqfKZ&3xP1Z;sbW&JugQIW~TX}wb2Ube}R^-R5?M$0YO zinu_Y!0AXG0x@t1EMA1-vkgVXXhw&A29X+=K=^o`6)mi1fT$$e{zj(P~mGUl&1)`BLcwYS(*R= z#T-=;a%lqgtz4?w3e)E?+JKof3P{!qMan5rULC{$uxrfc zG90ZUWfr0K%Y3HEne6aV9Wyz++gS!Rr|!%ZXtV|!_;jxprlI_kY3S&{Kc5F^*@P{G z;!^%gu(Vf@)o)JJLVI#LbSJ2cKtsf49CJSA!E6?}m)b4hHkg!HCW`ai%lO!eHeat-kS~^)wEIvzc7RS?hn2* z()CFo09Nq1mL5AW$?4QLh&xej1vakZcRE!bLYq~)cs{p1&+ z0_CiHt%%?4s1Gn|!ZDH+&jW;G*g=!0GAJaN0 zVdcWbHgl{4P_BWP;Rd$|auhdqV3!D|PN9m874Qmd+yS8-V!wA=u$R%>$TqPQL3z`4 zSgay<#*_}o3hOf%t)pAdoJVxktYjc&`K}MygUrG9nsMuyUrdCm;cv zA4rij>zg{A#UEa;R=*G zKzimhK#;jHw#51o_~QsCGwS8)O4z_L;Fsol$#>on+l?(8D> z?>47GXA8ZCIywji6?yvz&b~+hm5Aa1kOjFQSHH{rK^c%(1KV&AI-BPiKIHhH{Djv) z1}0EAJg;ISOcyECL=6CYc>@oHghI zciwwYx5AAd!p-`Wy@m;^s7iO^?qxb`GTb*No`v}aNG{68asrMEJ1m#_77%9?;94c8 zOx#UL*f+{VHOH~0lRyAQsh~6AghT-3Ozt@=hkncF+$eQ>ecyGmN-?l0XKWlhkN<~U zJG$^ms6GAy{{U$M>{u|c-DdAfO$US1~e+a-?ousW7 zXyX(cVf5n0CUl&QXIvE=S3YhZeGW_1rhj}ZQvL;^;OSsCeISc zYwq-h-|R#cV2}Aqd0A!wcE8grc6}8oNSNjOS3_>EgM587V zfG5m^yP$#(Kmh)9x*dM+GNORVN@!m>9lDp9|0*^nx$&q49Q3{o)Y8QE0*E`C^x>Ta z#$!3uHx=!na0eibO``v7|4Sw2ffhZoP1_4~WISL_sc?Bd;2S5VBNR-$Pnq*RBS-XTz z0{c~GgJ_F?NZ_I6halh=L(t=5M8chG6n?CANP`9bQN#sz;rbti@acaA89)p$eSvb$ z(*LykG;5wYP-w8n)X(B>WsV+TetFM|9w#y33vdt%aBbyO4J8qPV`n{-*Rg&w>3DTw|ApD$dvh zyM)b!EdYUnQWnm0;v%yPkKK)YsCO{fxbaZ@kSKt0_l0aa7b!BjBJ$w|RNfpB|BU)q z!>miH?j(%=L;#HRwhGm{#`RW-@XN+^hr^O@cE|0!ad*%$^KP76H)9U9?!iEUiRv81)C_Bv_Wf!Mt@4Bc&hnA1tH4b9k$O#(!}g zP>(5E9W&8M*#8sJ^zY~*BFA3K51l`?`L|S94fhI9BLeUQfZS}td&HMha{Cv;%LD*Dg%yjhCU^_>o(Cb`co&of*QSNNO=>f6sIX6HG zN)6cSd}?$+ogT$-xr}uYk!2AR#bS9CeFEx-!?PZkV{{N?pGTb%K6;tt{E_lk|D=tQ zCE}+-gFI3Ejs8qpcbIYwBr()0)|ZMJwJC`ZMkqT5V{!r~5dgba?Am8}AXo)k%~OA7 zKYMt{)hO>Ck_}Vs(5EN&&<1#j60zg&O>77Jv$OiNUYsO*-#N-J+5ZNf^bm`C36eM#%SFeDNS7vN^G&7CK61 zVfAsSuB?S~Tcz-;ovToHg#E?!uhM@f%(zl&qB7rmh2`+G;?3}Ye!7L6x3d6MAiG!R zMQS8}Rg--xyIPi&wcl3gGG6qKGe;vxd>fKq}6%5nO}Jjp*^gAjOjkfS%e z;c^(ToPogw8+7#!EZUzI!}J!)q04jOTz3Hx(NshNUNlo2dy~2!58?da4hQXnt?-{J zKM6l9e;$?qMoZK0;(`0GutftPJ>v)=lVxPX=I*NHbU*}0~`l|Yyxv@XF=dVY9s@lXQdjW2H`Ss z?sH&0oQV=jhOKY2uOWUkM7W|Ct&QR&$%{Sm-!x`v*Z}ByBAmGNIMhE}0U0TS4}6X! z^~VfDjbKIe$?{d=l+ZsHK?WA6WPcqT6_iAr0nD~Q;^w|C#&9U4IVHNB)nAUHt-xGL{eS{f3ZDdu%-0{50OFE7EzWUm~Juw@Sq` zHJu}|m-DX9-{#xYrKy~lf66nRhw}EP)FSvAx(FZ=Yf%3W(Dp}9WfJZGY5YV?LA_N$ z758kj`{a|~%6&gxVi>JJH#Sbz2+{5f<)JayEx_8@d_QqU?KJe+EU?h*ze5M&^lQT)SjiVT$K?>wjw zo=vCJH9?UOc1N4{yIT+ixB-uPN6w=|=EvbR_CpTy;LwR$Wp*PpF3_ncvlbt)XWpYO zy*k4T)WA|D+nJ@l>;oD40b(j6CJ|Zlih2O-p+i*{_L-?QGQH@Wzct3c#{~<=twL&G z`rgJ%7d%V!P{jTPIFa9#FXiD6pM9|ZmFr0zmOeoduj8gOYDW8K|N7juQL@IchmKzO zO0eNdgbb$TJtB^E3D6VSt5R9K8dEwS(u(-5l$h+jjD@TiK$1bep@3R>{U{s7A!Y48 za(6>XM@qH0xgBad9kjaZZ0dt9-NI3arG`sX0#BA6*V+K0+^Q>CXwAH z&UZjgiqMKZ&FrXxDK5X%=lQLJ|E7J9siBv_?wW`NXIM6w-a1wGP^mAP+#Q_Fflus@ z^sU#5Fks<_7Muosg@_EIRMJJvWZaO9Mkw#kuv{u&1(0F#DD|)3kqpzsjCS%dXNcsC zeFuk6yK~xkJ#zn3C%^F!Q9+awl}u}h8z*pVMICw#12LhD+Gg!^QD((6VTb*%+hRYU z%+!Sk_QAdnoQnefoSSVP)F35c-!N8jykb(0Bc9#ePBINQX85=8c`pJ$_v9=SI-E`~ zxQmQD*m;x6$o^|gv>L8EO9b(FBU7BzPH4K)D0@0zA+%>_>JH9C9V8l^Nx2BEm4b~pcN(=zB^8^eZO2K?0OLTbt9+c}L_uW)Y`j>|~4R?Qm zY_}Vx)~3Tb%p7My0CMktPM7f{C!%40x7cJhvHib4R|_}hPlrb{)v$2}FNbc1ng_Y5 z9drJTr=}z1;>PGUCFP}ky|T{ryP6>Ar1}EU$l8WIh7^3F29*3}j@arT_ZdFYq-!cO2l z2}))M+O4^+0u~1PDF`)16Ii%l%2>g7!Gv4s4xE;|>sVAh3{8Sdwa+u&J^Dx@Xq42i zmu!FMjpu%iQ!c{3;Z4m&JeY=m4?cV8>k(V@(&eQLY?O!4V-ErlJ4m?+iwxXr??9)o zk8n1hGC)5f0GumtDgxk?imW%fQv~2V2*BJW2$eb-xj!Oq048-axJK187aPWr5>qk- z?I>d3TLb|pfsyxiU`e*H?-sx)ymg@`7T}RGKH#MUxO4^k^mYihkxgUzH@*6PIG0^S zNTza^{{N3y{{xB{ye;)_*k2X@)(h?M0Kk9qA_xG%jIz^g_KE<~<~7E02kUSm*RCoz zO8nxh`UI2N6+~J-R?dIGeYJnKQm_9%~bwCf&`P zeO+8Fg|qAP;X7Mbi4!py%>Z-H|86P!H$a{bG$)832pM)&))wu zY-5gC{YI{lUWJRY`N`wZ`oSN=?84W^g>Mu5=NqgwfJkI_Gyh)*c#hG00hQhX7m&%f z=czGT(vRPPD~9*W#v`cq4bA{fmmVgOM^5ye3=HFj7zAkhi|NpM08)Q`A@qI);6Hx} zD!s4lc;rkEc+ovUkAWr;fjQa&lAp1@+sk)wH33VXx!Jt+!^rI`Y=NvUp%}O(hY^KA z_Z7w|Q;Z3+6MaL-O>lpZvt=5E3u8A)NIEq%DU`dSxPxK}4NP6Da>96wsbcjkz9Wfn znk}t`ZGxUPH}D9t0U`!s5(&~+_6YsX9ErMYyY=1kt+3BpxoSOLd9tTpbsB7_7jx<#dCo`t{Hytz%4z~FcFO456Z_s?7mao_etWXwSU*9> z94fQq9dvM~h?mmu2JI-;#E{vFKnC=?o(W)75qHCQ+2q*D0YJN}h!6TIh(?*ZPJ)Hk zk@FhRRsH|xaOamTm&PUUe=QJzHl|7)D6bggMb>{>u*aBtFI~0cWT1AO-t`QaLwMH$ z%2xsZ_ysvYRe=WKUv;)pXAC(<lS(C`{m}pk+RZh-iZ2*&ONb z8U4bg_yzp_)wz#se?9!I(kH7ZrL8px^D_xbFoi9^6!Q;`NI_o%$jRfphXaN)415@{ zctm{VQVHOcl|M(kjj6>V7M9WHG-QO%E>x%kF#>v6J}B0UVRT2Bn;C(eqV$d_qUL|E zgttaKdlE*JasZ0E$o$^^J9di_Mrm8vbD}ucanQXl`$+sdXaSKhxP)%c}ew$q%{XWogd-|l)fH1EOo-M+&5TMxyLe~1_W z4{Os2h8q0 zc^>pbxqmcGLnC)}HN5|%7cM?(gfrXa@XeNrUDc@8^=yMbD5KHt>*`gduUp|!SS@tJ z@(f~=^RW5mQ2LrbpYH&pW%=d2t-N0ZN=^UAH|a|Ne(MJD6Mi3r>IndUHB9^kw8&v^ zD+)4pQ<)eCYBWbg@XM+7u}Y09A`g0@^$6!UONB7IN{Hy}d{q3){X^{C_yzog$^zUA z_}k&9g&W~MCVnfmjd0`2z3}O~w?hm0@AA8=p?(GG56_R$o&IgiLN_v=BKkyU<#43GSZZ2_9PpNKTg z(tlbEU=Aq9GWz|%xl|8Dzk)%4800L4Hw7`t>eNjn0K}{C$sZCM-anPtZ+9xt*nLHryhnczHu*f zCvjGD72to7KB2Sl1D7 z^#Paw?%aE<50vN7sNZ=)Bu=9eDq$Bh73*?}HE zuo9`Eg@6C=|2-oT7})?hnfHL*U?yTtIRoD(`Lm;Bp1;j}iw=O$GG&9$aj*2`4Lv*Q zqx_8a=}biI844$30d_lQ=}@RXLX39S-~&Q6%0|qH92h_0Q$LR#Z};>&S{AYLF&}o> zNQ*d*DeQn~fDvb~nxni~>{y3HF#|syA-R|g&e22>2!HXDP+RlpFU<8c{Y$aj`jr_W z+k;+p;yIJp)}iXq0LQoe3QkJ4)I?T%B2^bf0OKq3pt>CUe%gSd*F@N&ZhlRou(cn+ z@+UH6(dcZ1QP!~!<6FX$oyvYn8zY<3757z13|ML|IBlqIqP>kt*#wdQ8o14E;QU9! zzh|ERRPs}}lUsKzqxkr+jB{VK$R9P9!%}4>tWIx)%|+0HdDeywkEZAltUpw1Nhz{` zSs%qIDnR7H=+?IID6X5Vh1p#6CC}RePAN};oAduTYakW++?o8Wh!ic9Yt}>-jk05R zXC{X4jTQkS0v79-4o}(Ccbuc>fIc&%cb5g7>G-Dv0M!Ft+B2Rj{{(K>o|L4S-{OLRZt`(5LG~IkQt){u|}X@dfVs7i)-^!Ofamh z>G+5spa+o2dFbNvV?zZ?@_{R$*r#XNh#&p83;2ioHm~WSe-qWeD^8^Bfo!e|`~L3V z{kz_xz<3;*U;m-+jxCKF0Z0`)tdfJzdcXL^FI;wCa6|;a-YBq`^1u{ep1^I3TwBGBlMN0B7v0*V|*x5aNxVN67J=|G_ka!Tfza;b~n__9Q2YVmP z7q(ZV4*O0y2Kz~h$S}htWMrYd8LD@G48!Vkw%1D_5-1xQ_uWM{18Z-1u?=Q)(6x(P zx1VUOSDvhgQz+nE%TD9dy}~gSb-EAw^f>ng{Q?IS!S0q;!;dTX!c+7c?oED={ew+W zr6m!8v9m&tQ``N%VI1r;H>owK(g&ZjNutTzeS|l>{|cPAM-79uozuv6cJ4=+Jss_)HI8IH0!b-d969wiuZEr8 zchHz`AQC_{u?F1)yWFuYMk|h?LV=Iboj2#s8ljr+&B8rFFKCK&`>iWb&m6k+w(f(V zX(*c$|7knpdgJW876JF%b@SQ~S|8u|FmvAc*@^2F#k3uyY@4i~GbcfZJG}fy=Ui`5y>ITW4x; z0_eINA#ffZC$X^>ptOn{h3NHaHFyva~0B|D3FZtu7h^sQO;c+Qatv*ohjM>w8Kp|_2YgSeVO;%7!!L`uZj3vFW`5- zRK~H-^bgrP?{bFie-*?I%0DW7CJ%dGX1$MDw#|*4VSsRfSON==X2R6%DNFzt!(w+f z%n&(`t(#HJ$5yw#igont_qezc{;ctN_}zs+#jYRf@mo-mS3#cWpCWTw#FmhC3^fxz zAw~mpU;UTpe234flMirZi^zcTLbHT6K1y^YxN2v&$&We1T#b8|refoqJ1$HeQo*t7 zRnLZY?|nFM+#~o`XX_^AGNVCM)X9~@vzweIbY4UNpnbYf|E-7f=ucoNv1@F!oUXlKRP_niItO}3ILsfBM2^JM99f+EQi`!O6 z%RY7zc7XsuMa5VEd)YMC`>@XfA}s6|)r4PJ468Ml_^h4ibRc!yYQFJ&;D}9+u+Qu-h$2F)u#F}2rdeLHCX=mVmDlF zvCd|xnHb~P$D?1m^e-g?njAgXDWly+ArW8>1n!o z2}!&>y%yGIVfRlG!4R2#ah5rb$h&|dWC5AK{j+cC-;R5>mN3|fmnL#*w1`5U{m#eC zd!pzOS3zBy=u6*mk)<91tMiwP%qs!7eG5C}rr(;E39a?$x4#AuCu(IEcgT^b;T>^8 zXqVWy|Rcp2!$;2s4?HKU;mRY?X=&1;l0$4BIR-$^;Lk| zUc*ppzb|r7f^DybOJN5NK^svRVv>w~KO;18rXwtqZB2-dYn-`b9~j!aR|Ns!PLFlp z>tSi(w7@%71+1z{42Y8Z!hZEL-$N2pH;%_%Gr-*szUafg_*(z&;Pvi{TpVL{|FAxAG$DCmAxqwE*#`FVFMFda<10%pI z8SfTrA(r%Jr?~0RW?5=D7E$9i!@qvFO!&^$BQ}K9uyNVBEn@yn_cm&iZpV zD43x;P5GE`&-I6I_Y!i^P74sa2HS0!1x7HUZgfYC7(jWbEcD1$JfM3WM>k52Vrx6h zEZq;a`?tcWHLAIJ8TtQQ^#11tKh9B7?!OJZFZ4BB(n-G;l^ znQO0Gvd`S*HHDJxkKRPN`Afu{IQFR$%m=T2_4C`fQH7(2PsjCUc!Xs?-uww8{OQ@-;r{&7ur|37?wrQ^;Uxkb z5y`N8fqt0<@Y6SOZXb1Wv3phKrR1oK0f;uRv{?HXWcohr=ll4&ze{HWoM*1$Sm$z% z5W5Cs-ABN~7Kbj)aezqds|W}gNX2@mu5bpCM?-$+A*QQkOczgK5kT}$P3mIe(ydNq z`ke>JwDGRj-XL`N!uwGE)K5)(k@h6}KL&8i3p(My*2{fFguI3?hWcf=9Vq{S=yrRz z*@G~1)yW$ot~&lKx*&2+Q<$Dc{ywfDYODNa0EtsSCrB36lqYO;~4JOiFLWlmp{I}4(`DZ8_p2fQ0L*Nqy#E4={D>uH~ zkN4?yz0{%XQ-Yd3b@xV?`r@N-ftc}Uo2SDW0{=+gB^AJZzCPA1+5Z9z4FAGYRDPc< z&V|+Y=KvJQ15aOqOTwlomGHWzNc}TzH~uV|PL?M>f;;@*AdHZQPGcJP9^F1m-!pU( z_z#TT>)NCj)l2HNv*N~%M^9YWUM6(ycY4Lq4xL@h)FRt zZ`VTaBY>+;vd;V(0QxT@Mmn8a<6QU#>w!6iW_jc+G!1uIYGgY1{>eZ2C$-=Bjo)~@rxt0U#J=K>6Ty4& zEB>VCdp;Wap#^{<0B*;F>yih*MXSu}Ym@B9H0jZ>k8Ct2XLSp97n@3PlRg0mqD<3+ zYS3v=XB(CpVgWl(1^?KId=hm9JR8gd=OjfakPKNm?y_J_b5?6m;BE(7?tUq805I>- z`A;2$Vv=Km&9w&qtwan6=&bnf;7s<*`0#sT@al(a7v6+Bv;#}A3yZH;lkx`-J<7Z~ zyoi%~nm7Oo#M`h+c2MeU;NPJl%O7uM3~P+wCx9~@)c5(**Z*%?pe$A?*%*!j=0_1f z@mx|Jx(2ZJ;K&@kY&?MoYu#4oWi^t73#a_?I1GI5m=@zy;|`iBr5*J2EDMayn1TavngOYT1gr!6P~C|=f5fcboY!Qj$(od%=<%2S4uBgcBP^DU&Yy?EQx?rK zegp3P0)z=iLIg#b_y!oZGE-)Y8>w!B%L`eU{vHeD5|Q&@pRGLj|3drb$FM;!hVae5 z2_%=?V#9LN8{TnaTzWRg^{1h-x)wg%oC_D5SHi_sosh1xk@lDRr^K=LyEfrV(2O64 z+W?MYcr`vzO->A90vb zT*JPO?M!uIOVn?@48I|hG^^y+fh zoZkvkz3Pkq4@pqM>xg&0?K|KOWALQ_TyXh zH*5XE`}sJ;zGp!7gCLhwu?;>z3Pqffop~7M=U2kKA%km7MBvAf6XO~GMO_f~KVX*x zMy?C6yQeLaAFQHXpdZ0ozl_1_BNuy|7u}stBH4i9Mx=YgXR#ni$LCX?fwB{-*+T{g zNRZ2Xl=Wga>-{fdL6nf`)KLnV2KaY5P=5=Ei@u&ofb4{qqJ-t0xd;F-S_*96V&~mL z51@S$4dd&fOjIo8Yt=LPq*W`r%n{=Ru#RdMk*$IVbkVx7ob= z3&u@uc)b*qZkx-$0vXIqou$_{2-1RR<{vMca+w8xut3zZ=y-p2nI-r&GyP>g0% z1Q|jXAkuPXwez63VQI)fq6UmD}{35p}I1|z2({!NTHOLH5YJSjYU8aS$FqV=xp9(nNcAT0QC*vl61BzsQp}J zc|$d4S3!u*%jSKLm|&S=OU+0faKxATf6_aH_r`KPZUn%J?zWI? zf1A=dU8mp7*vJ8pAb&0iH)NQ|$j|6VuZLmDa~}=d$iHMf`BHsh)-4AJfxvH1H3vTW zI$Wm3@1&0=Ms6G|8qACWTKMqR0G4OjScuNWCfwcNx&4OujW)O$tTs(#v!^t@U=taTm+d)ao)|`0e5Br&on* zpx=F2=t&ef%0@a=i!bG;6Wskoq6Mg*6;M3xEx`Riskx;^1e{^^B(0btfx>ke)6Xu* zp&`w?1RUz@JaQs|NIqbHf|c0@d(-QueGidYpl^$a1k0Sua7fA^kY!vgm*5;7IxKrS zB=38>x1gAnFXO-1-+OWq=26>SMzo{nky5%&=i&S5_e-6}jR5RdnZX9^cU?zIvI{_g z&lx*pAP+EY2ByTM?dc<0SGMj5d-`eM^`T3)_lPi5SQ&M&<7t!%drYKd27@^fRSJhb z`Fj0yQY!nlGxRog_Fbq4Mgr4PT;>@Y=sAybA3ET8~~Ji9uonuJ4L%iQX)mLXMv8d3NM?JRHMGo z@%LX~11n?0UTm{TO+#I zfr_mHPK!FtTcLIRCOZ>=2Z}bkisE2ILcv_*%!vdXnk>Mz1=4!<8uNm_fc4*cfNugj zE^-0LfY)$?hRr`~dhr}$hYJ8t%7~NY&;nl1hY10Q^@q?{_!T;ry`ubxrEw#aZr@@5 z>4xfgkU!#_s1r~<4eS6B>$R90_{=D;|AM}15G57;kSB;|;09!i-^4BQd%Qdee$+re zaxP53Ev`Y#RM7>{kz7&sf5fhi*fp_^)WQE8`=lLV9{0h>U`X!;X#2s)eXb+7SU*h9bK2ORNA2 z;q>-<;Zin@=f4_$-Rm;WVm-$3$B7qh{!zwS1p&A{*@kTl@L;cP&DV(n2W4b%l1PC; z3A~O;1OPpa&|G03BB0ZPb~5}Ua7}dWJHGCEJz9?kwl?A0sQvwJVs3M z^g2{%DKzguxqf^GC0o|UscXc#XKfhpNA|W3wFK@jN&-VIRt(04FOSZ{<mzX)&k>@9yH%Woo%bM+ORL5)aQ>6I;YQ%^iXCUEW6VntfJi{pG{<)WlUaSXuT&`CV{}Jc?@(URrvU(8>b{G) zV~5baF@{A9-K&f>pIWhqFJlZ-nU0B-aCdWB;bBuJMnw?hB5NZSLhJu0B(_clAJO9mPC<&^FvFG22SCC%(}=fVJQHLfYe}> zJ&X7zm^~NUu>Vm|uCTsJ^rKc}@fe}c9D3)iD7uHg60jS{=8yU?FT%h6{lVAL_3(Kh zi}75Z6arwyhi9AjY_R8a#13dSn<4-|;n<(==} z2H&48qqWY9H&`4+<UG&Bj831XJb96Zk$rI#aIm1vy2PvVim>ONvv*~Em-zDVQcCC z;#K_fZ~sMP+JB98hn0ZqPOenaof)o(8M{Wc=hqt^zWqD1tkL3?Sa2-YZ>RBXF##(g z>fx|=z6hxpF6VXqEe34JZrYW#rr}m@;=*K(Jsoz@XFm<)8+ZexpN-^Lo)a0!MZr~K z3G@&TOnn>EV-!X^STD72ywo`P;^O z_5hv3I%_!j#Fe87g@&zOd+&%Ty(&#P3H5&(0HCw12^8JP>1{fw2i!a~5fssyV3<^t z0b%Old246+n;-)iZERqE^u>P(g(o-Jq?=*!udl!~K*TZuWj}qFoFCwX15M;V`JCu& zEWGk*L+9Sb2E_YL2Z2mmmO!w07mp-2a0`Q_rrAF_bk%dhB=5PMyo##Gu zB6Ii;94>$C=@{K0+rNfvr^=sNX{2L#5z%I}nO9 z>%gT!9_fZxB!X7~QyN2Rsz9UT7GjWM!iI}Z?52u1CaLZ0gsFBBOdIWO&@lnO|KdjV zf~t-37zQcJ7{C8$0^m0U(<$2^`w#>`{f7ueM#=FNzw1<$TO|@eL^$Kn+sBde6^rdJ zi&tE$lP!)m#r84HY+rQUE9=g=h0cl3z7p+rZ2IF9FXN6E2Q=O`aj(50QYXoDkw8=oJxBK-Pvc zz$ED*X6$V%l0;<5{OKW%iSr4iWxFUtkr_0MJ_ovBO;PG@(1ma_jSL7(W~WHQ7rXgr zJ!s|90_D7$!=A720Q1;9W48T4+r8fN;z|E_RR}<8r0q%9=`8l62;d8jJt;04u)Pur zYN7xgMF9JE=$`L}e>jj;0M;y?!vqK-0Y#AjYw$L`xCauDlr^bBpDe{msR}yq^0$#~ zu7r*I_yV|lpE&eep>bscdt599aML;cE4ler7Y+8!r5_Wm>w1{js)zH0?))HJAnIQu zD*ma|cAT+2sPg&HA`b-k--G`DDBKDUm`e|_^X)Cj7KM7U9YWLBJ++&#F&>7ndKXTZ z%9tRrurebh{1vGFsNL(3$l{N_4g8p0%4?T?nu??5`MSIx5gRx+n(9|j;+(ifloIq{ zwo!2GKy_xU6ENrq*p60bGLphK^!JYXWX$}CA#z{wT~hKrT4rCNw`iY9<>hHbd9-!s zGz7-q!NiZXg0k!u{t;St5C@cSab9_hWaTas3yuKzziX$9X{o{gjBct@{saiv`Qkbp z0HO_|04U561sD}f6hXR*vj61*zyXke9ZJjmKF5(Le~UZQfU6?KPRRD$ki;OfO%MFr*IPt0x*Gt7M0c7D;tOd;C!**>dm=uy7QO9 zweVh;1_4m^pR@kQ*`Y38sei)$q5*ING~fZ+WJ~pLqKhCB0|KC)Lu%VNiyn7gx+q}lWHy<{m?*y(pzN{vd5 z1&xc1z0UdFy&obIW+F$kJ%&VV%8y4$R;DETA1(H(zUJSG07mJ)XYab`TyQ2$`Y_!K z$neo#iVjDxL*f$58ke;_H2k#|DB+L2h!Rdw%o{ECQk#W{Z*Iics6N#r^{?l@7fqPF z(4+r#=^~_v$0lX3;v8ia{H0kzTp=gJLpf^NNRFQMtACS_$pkKEqXIbS5zzT7!-V}k zcHFo-@71?(Z;7^t<4tQ;Y^3e7Va$KI0h%u=n8rf+_ziX~vX-8u)N`DZ`0m-mH|r|x zNp^vIQv(8}EQybqUj;}7&D2u2I1&szNwZv~PDpqe(o0Dj{1}8G}{c$75Lo_o&kZF`0`||8)JE zy#I}-#}egl(4Td@{w>Wk!UKE~Je;2(HasRnku}QtOUTT4ianWJ+=!rTqE80gG#3nL z!d#Aw3x>eQZ_`(^2O=X4TCj)5!wemnEUqUog0!wiX;z#Ne&CF7YyBF|4ELg_*W<$A z`qWieznDkvoTrbm7HDBA2n>Mg2p#k#GKrN1cmp+wf{9Rsi_(~$3k`xtRnQNJ4uI^^ z5t6+g30An(xdq#EFzY`E>wJx45cns!m`WS|o$inI{3;NDRN>U1bhhy(e|P8S=h5T{ zKj7F!0PLa2_K$2Vq%lzh;N8)ZW*k)j!4x*Q9SlR|1VkNx(Xx5__Fxah#U>IoDEaK3$Wkn_yyQ3gzEi?&{(d7*{x}u{}9(5-+wy)^$<%R zSJL!P;BS2RWmtYU&Q6Dq&Rz~n^OK=_{tTu-a4u8=v`pLaI;K=DS4Y$Vc!UVx4oH^f zupE*o?k(xP*Rc(6>vV7rFs`zoyC?#R0CXjA^u1ByNWSS0{(9(%b3qdLYo1)oI!H2Q z=tby=Oz(&&&vrKn^}E3uf}6G@M@{TYq-nlEJQSmX67vM}(gn7zIdp954V7)>)Q{i< z$YSH3g5H{Dfa(G~53~MDwW`+Q9^ii%BEYLBm!3mU##mGW^k(U`DcwuIZMZ$0{oe2W zo}Kawj@^`ZCZIufin|>HmOk8l=|~sk1QH+@pp1ftz+Vo)+r9HhoplXKFeM zFd{I2yE~U6Qje;hcm6-K8=IF%sfgtEM_S1UxHX9aP3jsEmm~ zk$jFl0(`3#0@xf-<~b1i^B?@+2XX*}ed(}?3AF8ZPWOCotclrnBFPG;{!5ilXAAT? zH9lT{|NGw;0l4YIlys%2^B;k~F`!FcJHULAgYUsC(^t=*MH}?%JcTx>Hlx#U17<)5 zc0dHw^~5SIR_OUJ-`+V=4~R({O;1}JuiyWx_$hx6w&og9(eT&Zc}fV|R(NNv8BVQq z!lmumaDjLOb=$jI4qVEZ5_S~2X(MaNg> zp%psL!!)%$Pq0Z{{0;~fa?SbG(0=+yD30Ow6#MeR0tl3H|BVQoF%BN$ zrxF*zol|hprU6n7s8-EX-%|8rm;(Jpp-5#n&H@Wcu7KE=kL6whSBfYB)(EdXQ+rh_w(t>HH_R1kfQ6Wec;Or8|G{2Y+yhp9%h@vn$=hG<+Vs7hf3HpOZoW z4yxZ^!%~A&2gtj5E-Y|SObR8J43a0xR2a1g{QY`QzaCU%{$3e-^ad=Q9r9_Qank_! zLzl*$W~g_2{E%GUK02reoZxCMn=pNeTFKb0XK3Q?e4^so6ZkwE;oR2aaBY1voNqP4 zB2fczya|phcW1mw5x^EkC693aW8kOeo<88y9+}yktuhPe$ zvJ(%9@BSmGMizkGK0C@n*putqA75e*IBHV`KFWUa7y#|_+1j+Puq9Y0`j z6RiR80FBP95uY#}v}s+)Q@2!YnM$nQoo_ zSMHyf|4xzdBvCqiqY+}O6V}lHUZ*aK0J0j>%j2u&6WysvXwv8!7H2UT3YDD}8sGF~ z5mUe}A#%Z^=yT?HbO6)u$G1~@JQM1mTwY?zM)4J=PBda zHS2qc!Up%Y{$3iJGc#1#5CAJ~o6~u?CaJOMY@-YR z?4SL!Njw7n7T5pt@CPo60y46aCLYL-yInkJsmu|Jc<$}zZaAPA07QQP3n+%2=aBvU zpjQf8YJ=({@@*PV4@5Ux{r=QB32_7}#Oz+^PK2{~**XpQ*Y-chu$=lfqXl7eUy2eLiZZ5wijN_Mg zoCzKllFnQ{mr^Ct`MDQf=Eg}O0K;{%@`DXXzf;3wXSCb6hYR8NIi5!V+|ppFlq%Bz ze&RtB8z4sjc>4v(-gYpH=o{8p0OtVy@4@n!;f^{1OCSNzs4vLn?c*c&K*W6QbPnPN zgss&;oS<;FHyy6g-|GI)f&xS!b>vJBe^JU`uieW3n=Ise<<;=x`kk=SsD;M_W9iJ| z7kvh0AK8G`@2iybx_I$J`~WmVcjatY|Lmhs*dj0!Ay9jpYoRjLB>n=;dJigwFsMxH zs4w_cYT_%Y>rt0@de2>I@Y+hIT`cWjoFhW9k@>4868mZO}ELMT(5=pGNFMt zK}t74@^DBKT|OflDCqMc5+!VnkrU9*Y%tRS$YSw%vckU0*-L;>OmLAhmEw|;q35Wm zmOuVF{&g3?fH_Q~4>k|LpJm^eDj^0y1W*QEUrhb;fBw%u z;@Q4QmT}y?;|A{V*|916eLs2bre9PU@CMcZMhL91xORug!v%sFL(#6|1DyJcghHVbe5t*PNb?1$>eo> zVXO(;$Bbbb}>e9_YM zx%Juaz5VVDzdHEN;B{)-e)k5RrD>XO?R!pncyPM@u!z!lC5&fXz2{2Uk4Fm8ormvY&82rh2j(H7MdS3*Z3>D+(s?T zZ!d;v+-^;R0vK+?ZXZ_?_#5zN6JE|LE}vH>>tW^G<*+(c3#};trnc2lBNyoSRZAi* zQfv})#xJ=1oyb|~7UshalwG&`G_*I?L+|<*aL5R4igiHsH0ZL-4mbk2U;Tb>kF(Pc z>qn+Rq>NqVCeORqx$^Ds{mccK(%}2-61z|0b^n(J#OawkN&1F!e53zbx*w@;-}4)e zUcbC3i}#*o``k46t-meHdmg^i{|y~M5E=F+?pHKzbw45aRS~gb8RtGC0r(yzzP#5A zqn=24Khyp1lWLe>GZZisarD02FZpAeCEZrO1`BjbjaHDKMYFO$Bm((;J z*UGZ&DcA682NENqV}(+rfUxdvN$N1WclmDv@9uM%D&W8h{4Z8E;RJNT^{$!#u;An_ zyiG6P1CED|Ylv!A*;onJuHOvPcW#7tc4oqb&b#4suYn8T27PXSkFv}TubQm?b@XbM zFaUg5?t};UmAdzh?}ZHzf!-pXz+!k+sGb9R2M=@~u$$*)o(RCYR@kdHy{B%}gFvw{V)??svCO`HX|X`73L z>%cPsoA)v)UGIC+9@p=KK<;kud_$aRp>)peAB4F>=C;s-H$#T+tuQ?zX@oiDSuSE{rCp(o;-of+>B%snQ zhlw_JE{GTFJ^Wr^^6H!y@vXxJD*>5HJgc@4g^47rFNNZ#|CMbhM^MxH5cG>sc(%)B zD(rTBzizaGC(ly)<^3L&^t{2^cvx5on?%CfICDO1)j=FNs}s`|ImSiyS8{DUYxc-j zpg!RYfd7Nab~shq4j0t^-{k;|k{x3M+rJ2GitPU=cG(@Jl+jaR8$XcsL}8D!Db1)f zWa(Yc``sISK9=iOfdJT$!DF!DsRPoz^1uGq|5|AL?>PScU<>o<@9bxyx=4<>k^7m0 zTxF#z3NS{%F|!)1-rMWc18&TcRD?7wa5Q!Z!UT(Yf*1fS5w<@K|4t(GkMN)a{of8P z$g&+AdUS9C(y1lNf472MJhwR0!`JtmCaIKKgFQqbw~c>;B6zZMI3xJU4%8%Wm`f;_ zb=hj%ZuBiy{1tA70K6XR7{2#)$fAA0ffiM@1s5D#moYQP`_|h?y&3J!WnUhL3V0W(e3(4nY{v$Qe zMyI3OY!WIig#U+Q4+3CTI#noPXP$vMN4LO^;9!nHkzgji;(#;PpeIg+ta&Q*CV95?Aneq( z!sZrXP$6rJON_&=^JiPG+A8|%8FyHr?9RCi>V zdkOnY1?+nQ!7|rTwhoJ3)6$4wP}c&i^$4)Jmd!4y?Dr+}>Qm6Uk{yrYceG1D z&ig&u-V?Fte{0$K_m<5yDYD`Hj(6fS`oQu^+^cZ-p6#pHM(SFo4z&z17iCvCBN&MP z5*NT0T8^9nOE9mzq*xl){>xL|8~q0?q+I=k!+OuEzRT|Ra`!D_bBoTn&%B4o62B&lCh}bc|@f*J}`;Y(e zKmN(^$4*Yo0E=i>X8mhrFDcXK-ap`m=70?bdJc@Z4dz#O&^friH|Ak7X7TV zwYu3wPSUGf0=w0HxeE~hp+g;9`3z7TPD>2Sym$>Z$Ob-_9*553j~RmvLd<>;l_M7@*W1OEXpDqn3jujCGy4r7Ru)vEg=v@@tN>IcTJJT@$R2kqnk2Q#Z4~9AHaHwVenQ}^( zy3x3tUe1B0@5ws%7xZ<11_2fUyaHH3rAS16Mf=FpU!n|xUgwLk_@a9M2~Jz8;o(3|v&Qh^#$6kA3}Ihd=*)|Bg1E zx_ZajyfVBgrcDA2p!?J`ovk^W*S(_qQeVe|!15 zq%_sBZa^MDC(sMFEpj`6?w9~{iy%C(e0$v{fS53-TN`jh&>LXWFEIaOI8;2JhyVzv zN-cnz#ZJL0zs?QJZ`p;`w=K@YqNT2vlRJMy( z33>1hkq3dlUwWN?>-}d)f~Dl;#QVIRqX2n6Iieu&&kx_spFacLe)poZ_l>+|dAZKo zREHPkGM?x5v#qEyh|6Ga_00{gK^7m_}l9fODBy0*r3!GUJs_!*uf5Q z3z^1QLJx;PKjiw?(g$|2RsgbaVc12CD_R1uX^7+cFBO!&+3)N-6@Whm9}GOoQe4lV z4A?AG;1CwVCYb+lMfc0+?Y-e1==U1Re|3E2N`^G>&;jM8x4 z2mcoEs{ptK@PAxi4L53!!qQ|LD*&7i)rbX-(p(Q#XAjrILc1O^+AaZ#qHtWl>&6cU zsf-SSWP{2T5QDGu{RJp4*v06nyU4-omSUY)8`jn925nuq5D~GgL0bxI0Pid43n2Dd z`#fY@>oMGE_7IO}G}pjP3vE<0@z5wsySiPAENzwr0G-W@vlMd)&Gkq*N5p_k!4vZ$?1PMrIm=6MRuLbN<>82d4$CaM5`a#m{ zZ7KQ$^q;wp_B~6?|E6#KB1ao?1i&)VxA}eFPv3cVyG~D@QRsOs5(1FFlb1F4wbw^U zmXfcJRQgfA8s|IqgDVh2(J;{|hS~M4FxOrWJCn=_qIk9ulSN*EUMFL(jI;FDGcU)& zD6x%F6U(qxyw1mG)cP_r9y$#P{~$p9<5s2@h_M2f%~`41=7(--FkqR_ulE z=PU1puZ`se8! z!;>tY2JD_Xree@7;cR&;T+$CTo6H*Qzil=w_r14i#2)A?5*1*zSMGg+M)MzsiDoTa zYW`ZdmO=fo{pkJAjc8oS4NI?oM*LeUuZN$`-3;Gf_(@o0Q>&b<5JN}u7B7Iyhy&1h z>fwB4XNfsg0_q+Y_qbXx z#(ea1pitjbXP>b>t_ht7ZT@!va<~D@cSH7v|1K0B-v|@iYH(-nP=Y0@8%V$btVMxI z%;F5ND}u+agl%Iwi##rV{6Yx)pZV)LCK0;xsOqQF`5~hZ-936Kg8LcEVIo z4$TArVv4nZ$RVIRYiBC3;|W(x`4SvR0bV6=da!et`dE}=%^v^#{Xkn285rPDK53TVldZ<#M zz8H|}7S|qy%I#l-^4jAtwYna@^B6bGtLMWU^ZY99oWeY98o+)jI}_$X0|f8Wu;>$z z&%u38(&Qp=O6 zho1i~AoHI=-hY-x6_M_7VzlvF@8D7(J^EGi&6(G_rv0toW$%y$L!(+yzS zce&n$aa<>u=Q$m|?)586uL1!`4H`VB2B)(fWAA%-tsWVlvt#_&wgjBH@CQ3r-@Z^>_e?bictAlqn#p>5y5Bi-fY zEWC@Cvr|CV1t{xD?4V^qCXlgT7RR|KRi8WmSta-ncJT9z;ANHzpjC}@V zKr=ku?J;X!t0{xELjf<0T0N9j9)#)_e;%rjZ->RrV)(TuwQzC$d^m$n#0Q;oQ2jFP zD}C>bvVK)#N+5iYvljU$ahQfz#~`&cZZ6Mp=Ed7@4(b6%&e2jY0`o-vs!^qhV^ji+ zyRm=X+$6v|50~$(2f+U{%6}6o0CEUFhUfM{J&{xVAiMhhN4Ka15m6EeNKSwx3i2cj z6F3Re)RY;7bE&gq&-3h{-#j{*^ePa5!J4OrdM{lMVnqoND4{eljUwQ`<-Px9FoXP> z&XwYFcbCLVZqA;6ao;;>Xx!dv$bqIn0-7B4s0F(3CvR^a)&oLTeEtV~{+BpUVjeaJ zVm5;!m{!gLg_8gbnl35--{S8!7<{h^I}`k^bQ&PTTv}{ zmZYK!)k%s`8yXc+Zf4rBqw!wcMnQ_u!dVk80p@hPL|f4zKy(o2AyY7)k7;J@miTHf zV&f>XOS@3)QnXRp-VF8ibvQHYVX9dTi--fxfRvrVPr})34#A`fd1}fF5^@x6e3kx^ z`(u0!c_VVlRi&ePlQ%0=NS;K@5HbSrZMGP#Ip)}Xs zx*Xc~$wX`eXDVUlOsG|CU6SfAuRIEk+ds!G@OoH$vKl^o2;e7*;Nngt ze6xKDz+VIKPr~m~!B6@9+xfoVTzQl3DK6WAz|m9Y2ClM~rb@WXu7-`ND!44ZRq&6I zMJtjwdoH-=&%yFPi_+g&_Wh|6mM}+@`wz~C$N^CCkM&=~vzE$#5e5yulwbdju#C$D z+Xj&U-*ETw5dN9c_Ll!T;lHl}0f^gczhUl-gAGg#Pv?XL^ysuj-u?N$?I)LFSvQ+t zZn)g+wl^bgJdpc6lo@+1xC=YWgl@ebw(tF%>juj8?}hID4PHZE^(x{$bpkXOl%1-E z(W^{W6t9*AH2n*>cdbA8EX@DtcW}h?D15Lv6aJ@%SHpYFvrz;5o%Ujw0s)ZPe}@wfaG<=C5xm2e$5+3iKnpF_t1D2k?>PYf zyVZ?w2GQ>V`@YryqbK(l)=_l^CUiZ*qkI)Tw~{^umVJl(69UlRU3P)~AlORR!{^bf zcf>DV1p+WwmBEJD5owD~os!OWmROUrlOJ>ZD#xA_BLm`nsfWVFaU%n=TcZhzQy{ni zbxdTcD1oRMihqd#~OHnn}WK`-M%=)&n=20WP0!`GBKrS zqWwP$c(t$@)==bZR|!3=BEQE$Gdoo!o%_YOc=z1$2eY+Uqa|T3Yf+f zQ49>*_&ac2@2n#(P{R;JD6&-3v_7~EV}F9kqR`rovi~wpf2J_;tFNwx`DP`Y-L8c5 zxPMg7vz05(m7&T@%H=h`}61gx}jFO(mB5oVt*hj%uo!Ux-@ z!qpu_F+^b0oKGXZ@yq$g*P6FEjk^a#lyhXc2^@Naz0AGBlkf=NC)@bE=q_BsV&-gL zbTy8}GVc11KR;Wkz5fJ+!vx&lDk1>k!03sbBK%>GLm_=PHqG9Q{tfbfD1``024R~8 zdL-EASLxpHwZBg+9YiOcSb=1mdfUb)80$Sd$a|@yI=}tfzkT{2{iA>Md)ymJux=~J zUNFDtDu*dA=SV;l@TTmCKH2A|B7g>ypcdIc+u z{_MhMVRNw=rZM}QngzrGsFSS!*u&&B;t;VfiBP~*D4{P<#ecr$gq8dELbmY$@jyMa zh<3RBa0U;&7jYbfNZ|Z8nAvG+AG-!G{t!f?fCsn2&UPr_u-eZ)AJ#loF#}9Fv|J*(u?NHYwL?k&f$Ut-(qDgT&OMK{6~jyhyWtkd2tSV-e6-W zm*H^|k3(^^un4HM=M{eZ&iB9neT0%wE6?Csf^m6;o*@E$o9=o2O44&RKA}=m!}dGd zAs#+U*AWT$!4H0*9st7Sy&dB`l?B6=%!OcR^gEQ84i3Aw>x2^LZ0FFR$zu5lG z#!hHWu+>>`J|*%ZU$$7kPlwYB*^s&gh8ZZ;FtMu;YzOnh0zTD=hy$|^>R+Tt|iJ z39Dth&<<;GIadLC>lMtV>-bR7j8(6fk$wGU&kF&aOnP+yWcydyJIWjef;%?eBkVzR zQbgXE2c}ElEsmZ)ZvVj_`~mjD5v~c-5_}tkb?Kvn&M~u-`txOS0Bmq-wCzis6M;X! zJvVYA1uT;0# zG`nFHndt+}z@k#up*eg_AHw>NEN|S3R&XVH4e!m1t@DKcor2|T*k75=F1zt2f&T`Q z%tuf%PfEBjox%AJHvf2Z3KhcPIwwv%F=<3g5>0(&;Dj;af!1KHFs+vdPHy7x=$TZ+;I5 z^j#ma`xTQl;go$A?#16Vhl!UEL)IYI#=ny#V`qVnGxob>j$$liVi z*8e1fKe0x^^_=}SLB?_{t-XR{#OjGF4|r~=eJP)6TE*0gu zLb!;!%LNdpQvjY^+U!t|HyQe8mGyKN?f>N>&VT06-MD~{!Fg=ir^Lv|Ti%}B`pr=v zpfpWzm8&=%BKS>f?QSUD$DQ!@A`$XdL+{#O>3;^>y&_9u{QVHQFI(swJiH!C|37F=O?*_T@1gjC+LtGKDY^31cgI5lC7?5GuHP6eWWEf^812QfzvNiQqh`w3wC z^H~4O1#lKMZwC7z5dc96`tDB64GjOp@dt=M0^W%@@joI#_214u{G%^@=}W?0dbsEQ z{Z{8ZuG4FE>>JU!uip-|+)DzW^F#c{suKjVb?iIDBY$;PogB(jpZLTlzQ+Ep5-bo$ zkx2|g6eih)hX_CuP-6ZSyKd_^>|A0}^CnOOj4~;d;3SDUU=aV%j>kW^yKagyOiKGp z1i&z^XCs7_og}fy7`kTZ{exlc?BQW_M_|xY4wV6FSpJjlw}vR5h|q?lJMillRd~>a zSA=4y0`QztEP)78qey+xn#9#_R+dl&5EW6Wh9z1BKn%S|^+FAk*Im+=gbXk@$ZJkC z!xN<7orLdC6G{yIHDv)Df=c(1Nd z@n>&c@Au>xBT@e<+3mJ)_giM2Tn|GCu)RsF^Oe!8txcd+P32GluwdeTZr+166Eyz5 z{1qI}0M92e_#2@nf%D@0duI}ZW^36wy|A;F5S|fnFKK|7(cAj)Yv8W)+_78#ui;eH z(^UQN-Wpg=-m7vi2>^YdpVxk?@AMtvJ41-yA^-MPI+SlxU!y)n-Boy$bTDKGgbv^h zgMLz=8_MDv+C(>$2<2$3ADdmTd~_H{01E47>x&lNB>Eq&e@gR8Qd!Wy7RPXl44O1m zWYn}CDcFthvTfkYTO|39?Ax5-A4qxVFW&DnM7lEFB8XSxQxJ|td=t`009LP(au=!J z=nTI@2*~YD0K!es{T|rEZ-PP%1^j7}&}YMPi%XVSS+a@skd4)nL?uW$S3ep1?Gj1$ z@bE{M+};DhypvG90xTDjzV%NtGWcD8y~VwMMlff0UZdZ1ZBT-{b;jT8?~y1!I2RDT z!8-*Q1sa2A23K_a0-`H1AFmVSXA5tb^=Q+s=jLo9N_y;><5nHV;y;VnKOt&)P&gU1 z{3!huT1dj!jRM<8kN_mG0npOzyRe28>emJS5n=Ci|AINUK|A3pjDn!W0|H<-5fDt8 zTT{VLiQU`2o7nFS_iGk(c0lL8r;IeqwXbdR;~)R{=%+vZ>ECAm|Dx_FqQ0V0FhFt) zkF+we-3xGH9ZA!ra}G%+^g22R(+2qZ6J6j*O=PN&8Pc~fUXje1x*_(ukS zNs%5}wiMd5HL7&$$a%KsqY!evO&E|}f{3E}H9+Y4&CgxU-=IYS!oG#JgSXTifuX0% zz*YKtksEqK(~3=)67JS}sxAE*tOiV9Ij>*T2A+V`a)I>Km(HHI%@N=s^RE2tPgye! z$Dherb!^s};{1iM9AUb<&j#b!eRZ82dp`AQm&vlfdXvp$8lR zpbjDU4;(GCQ1b;AaWO{V8^W4~qO_-tUx)kF zJ)YL_agMQ%D}1oTipnieAxO}g3n^?hLI}$%0M6X?n@Ubz6s=(ZSt?rwtN)BLF%sWc>K7Sbiu+fe?N@gGy7Oqi`}EuXSMUF8Aejh0Isl*B z9dM`D?)kgsh5ueXzY{D6@7wd%JNyvLyebH`h$!8mWxOwh<{jz{6PE(cZSUJIdeNx78YA|L?R$EaD~r{i*qsFZAVT%|pFnvNQ} zo;1)~i3DzbE!z?eo@G(wu|dm#i?H@@rZ_2r^dTvlRa&3Uix+q_C3jh$floTL=4z0nWK90N0vlxv? zhOm{1U?D# zgIN>$&Df?D#^AK4iD@=cCGJ0nSHXV-@$bj*2qq9xIGP6-#2_H+1xwFfLK2lCIU=D} zFA$t4iUc4H5FV3CKvvf*JB41AE>Zik!qx`}n0O+#Yxl8K6!d3p-om(DrnibVOIAPf z720HI)Ma&3AE_IJ0<{g0;;p|8#Kit=fR^;4;CF3Rv}#oJH+V*Hq{SIr8z8aZI`N-6 z_V?U;+j8bUl(jNDDnb8Hxoh+9hPVYgTPjUWrC}kBmun? zH7de{2{Bn(Ai8rP{{rD<=lS7nvZpQa>;Sa(^0Wu^8l}x6;#>$KAho$}XXiI;_R6MB z;x;)=e)+Lx(s7{J{1Nr-?aAOLcB08F3)iX;B_Gx@glIMk+e zeOQFp0Abn?#WgS-#Q?DIUEBksR=B!m&9~lx7y#K%%vtNyyPN@*#UWM^$KtyRU}oRz zWQF__{zJOFin*-550iHx1Ob-cDA>uyn9Y#_aa?H-Sqlo1q~d3NfJD@TLKWChcm%?} zP)=}G5GlAKfK1vCihkGA^fwT02ME6|LfPE~O~}6h6$MDize{|nf4-ifXOlG5PPL|8 zDk23Zo`M{ZYt3hY^(i=QjOto(Y|b50*F*%#YXjm9&WXr_NN|!M ze$YOILvWqWx3A}n>$mn?ZaC_ebM9HXTssgNvOr~5S^WTBZrhATFpN#{EanmCkXN(S zdgMa4W%nT{`eI@o+9d9O(;)rXNYN&U*^$BsP;mex?d`v?zKQ=IiDwZ6u$2p-`gLdd zlyDWN=y=>O0wO@T%;Pn78Q!4!{cc;GJMgj(v^ns1`%X~Dhz!=T_Wf4-+e82q)eHo{ zpK@*|0pNy!L0}QMkic40oC`RP+Xjc*_b$4Nr3&8=vNV%q6l>866DSRKaY2F9vWK~d zn3DfLBIqzW=uEk8`BL3-5KQ8<+>V5zRTglKc>IlwDhNjU8qJRm`ehn z`&D#KsS0;|Px}DQ)7?wB;SezZ!lYgn@{~|Fh5mwilf}l*E8x=RMh1;a9j;B?d-8+J32pLO|E;muk zCb>pSe6SLqe+(3!ya_f>o<9 zM&%aYi9uN_K^qx$ z^uVx8_7YXAT)`DOiWY^|1bJ{yOFZXsKL@mu%udO2?;P3LL^QU%~p#`X|ILE^-r9o&S}WpIeycD zM9J7cW|i_DUHc+k_~HN}-9)+i{CQ zxQI9JS6URbE64;XKlhaoaXXLe=pCr*u8%^-RC-uhZ=haZ$v-af1HL;q$MoebJY?nTO^vv+cS0=eQVqSb^%K_4sK|Jyj%h0U;Jg2p~<&j0cE>l*^$j-*VD~ z8zf!&n>3t_!V{xPh-Z;N#6>hfK!_6+f^Tz~fe4z>keHc`5W16hX|mIBiJt>R!U-WI zhg3K(HHDCi?sJ?a=X5WXA9zNvoTc|xX|^F^Yw;Zmef4GBM8A%KXoTo%IjDA26M=;^OIdx9rhb9Syd!@Nu~a|B8T zE1JzHm_)kRXd{QM%LKGp(n6zSwmy9ff^O7Wr{80(IaE8+xqC#c*R}h@?QHM2fACnt zop%G!zTRJ`ZP2f}OBo&q?BQJd3OFF$jQJRJtMx`t2Hd znMu?i2Cq1=KU)R=am0Y@^BsNt?}Vf1?krW}e@_5-eAW%u`Ewd2?cdXKKL~)%5A+}J zw*gbpW;VD`nA_L-%P+rtoa6sQ-AMp&!Yu$sHw2K9fd-I>^@wg!K(J2&K;xiLk-1g{ zVP%LQ5=t8xcm;?F8!UmOYvj@XgXlU`+Cu-lPTcvDG9mL4DTql!EOkN= zEL_yPgm_3>Y#2paN?a)CbS$JU{GwyWmFilK)nQr}y3chU$4=6qW2zHNxA(P{9M{S9 z(pReudZ?bGKW@vhD-Z-a);cr@l_Xvos6kR7&@ksBJX;2TxT?&ZP#A^`j-XpO1(j?mV3mO4-S+PV%U zvBE6-e@g`df_rW&03L~JFw}6m8TJP)a_Lg2$OOPo1i%FL08Jov6$rQ9l)u13RGc1{ zb%5Jh1mqvtT(($&zNtkm)l!;SfpR~T!|N9btM#v{L?-cqEtCCkC56Bj#KJ3~%0=W2 z|GmTd0;#0L;HrfoNrqEM0yvh}LVT1tR0}u~A;$(Gg@vyoEo=j1pp?OtFh3ti0Awf_ z!KF}uhs>9jA`U>PfQn0!1>MIyk8q8+P-4A1F*MQM0-Z6xxlpe{+-eAbiw3#%A+BBr zLRv!X4tepr*C7k>%h1gKrt^*f&^^K9+&#kj?p{7XKC^laTvL>LBdkH0hEBIeZO)D% z0mwO$F%BUhqEX0o|DxyVWr6B~&`*Ik2*`gaw{ABtCBpL4@1CvwWse~wV-Z;G14y*a@ zIif$qf=2YAvIs`=?S^vPI?pBAwr6<@iB(IM<>iZ|I}%W>%E@B+v}7RYS$&Z|g7in=P~ z5dXKr?~vMd+2%7V_76|IYXA7uYZ&U*Y>Su_(K?bl`YHMkEiy&! ziX*KYl83aV$Ie>#vG=2*f!G>hBF3QZw)^HTUij$NyXpZUvsn!Nvdqn6!0+>k6?=@p zZlkyW#+V}^5!QVc$54`JE|#8VSpezq00^XMw>{{S!cClIF>Z_hJ8@VrjoqqmPw89x zw>|7$ow#2Fz;5W#**WSo9c!!VxPP{es`~Rk|MNKrfIsE~b6nvL9$#`KE@LRfnu4jqvi>LTf3#E}N+J@H z2Ar%5{v!}MO!Tjg3ADYkHJ4#o2`YXoUb0PU4vXg$x@m^`@WS0T?r|IaVbVxFuxC*h zGsBx@tjgK8s@Sg-nf}@rvK0*mcdc)3;AtSHKkUT(^gMv6CDvE5-4nndxfQ0{MrnJ# z@Bn_0cLUtG=8MFnF(@GM`B*35?3aQ6A93cQQUfSjVQ(u*^FV7@*8U2RQ?^Yk@;9;3 z*-TOM%LV-dT3ZGB~T zyXf3KFZYW8(1-dD)>b{**(usr#{p5cx9Zq>TMh6U`>#@AcXk!TmSG@(jFKdV3`ba` zl$K%w43H*Rh9g;Jkcw|Gp$NWNPoa+GnZEVAUjM)yDx|X9*zl%E76_GGNLap*v$G|v zq8kAym*uqxfMFI%0E+Pcs}R#`#QtxLk@QE*)&#&ftHI@M!+qs2n?KOA921GeT}WQv zCKM^8-^9})mS8K6mQ^4_LrDXoNckfv&|-z?a2Pw4wg^CU6`lPk9VG(5yO<5snqF^W zAqeqHlu;$b>W$ake97OqVNY)5Y_9n<*&*|GvNh#I|MCXVeCdr`4BS7J{ZW?wTX1!+ zO3LfjAs)oZ4T~PvBtTL!kFCfiZPB6Xkc*^Tid&FoUdFHm2&r$q-NcaJ_2_Yf z^?>yLvqT4-2I(vCk23$oUE&`Rr2PPFT?<5GA%-wA3Ovg&{DT0{n(8vWgo{?dP48yw z@D$rl+$CJ*8=&p(eSgeP_qNFQ%?-0LLXQ_&;)>a*<>N_?|UVw38Eq{!2e@^Wv z=;}oNI|zy>kRTY1L>`}YB6ihF1Z0saptru(RSvYk{Y!-OSQ1?$0fDO392_tf*#Mn~ zqDcIY&R@Vix4vP|uBYtyx>ElpZ5m=o`u~9YA1>sTsn;g9-V*mN#8<60Tea9(sQU4+ zBLdp0>;nPz_ibF6@v>`hQ&d}Uxrz&B)dnF>7}H?xaa_l+uyGo*INS}Zn=4km_$>$k zYy@T>H#>GZ;7~P-_f!D{&%dj`;`WJ7sMrvp!kR^1f7!xBDx6rY+XvSt?Y&LJ{jDT< zB2L&bMCjuBcN&a#e|xY>@s?oe&xcp-9fJI<p0Dl(sJp-H4rfKIh}6xIb*jYoCh^j6L15&zDWov8H{GEjkAB{_2jal$ z^SEw51`#j@%$~ydFNyA7_FTQf{onHAusF<^6t! zx{vAz8z!BjV*w}5cn}GIvK`9nL2i$-C5Vn76;LdMNsOK*@lYWuVyKEwA=w#Sz#$QC z_hNoZLR825fYi_-0u&`Tu=-zJAWGpT(IJy?{>N;V=-qMwR1hH5UPS*Ie~J8S7=Uh~ zR*)UYLX0>NBWt!av1+Rm>sA>h?*e@xiIDp1po)e@M2p();~BUZ@a-`>sP{g4Zf`vx zP@sz9*Yb+rg4^FX@H&NR$ou|lsCq3TvfUG%@hgi_DrGU1QYp(Yb{jivKk(U``OO|b?lF+U5g6}B%KY` z(W=T3;1+GytM@x8t5U?@h?P>P0J3Z+m{{@(kgt9I5@N)e-Kw#f{OYhN@9?9(9vT_}gc>(A6vBY7~cr56&{83gecl31p9&TeRoA*1E8=)&Uyg@ zV0Zu^6n)$Fdg%L+k8T)B4`|qB`7f(~*=gk<0J3oYIjSQ6^(Xodnk42i2>b)yfcqB{ z83yqO_~W*T_8;50Ncn0!e)9OL6NhQv<2Svib6>~zrQB~&s!mXk`p)RK^_?i{%Gcy) zKJ%FqANj~f{vGFjhI(6(;ZT&IC>pdDX@X%;fK^MpNn_J{QOxKht|UVEY5d-|FfMo> zIRchAe}&_>8VM^n=jYy^d8DosQdzh}{KX|pEH-V9G|A_hX?Qv%{t+uaydvbUsB#kj zE57?xe92$2w`>*P|BXC32ynTM0r(>X021?k%eeuLMtdb=y&%2RC9Y+GEAW#s4B7S7=6X0TqNA0j4JO2$nPXvzC zg?I(Q`{zShTv9QwK=Ks{8pV?d+DW@PO|+n6<V(lh3O|Rc0LB3jwMJDEfIyGb zAf#l4T-MyOxW>UN_+WaVNYb0Z>N` zd5&sc=pCx4h9ZdkLkpJ)eH^v38#8upD`}G;#>r+1cR$27Jr=c6Z50tHfB)ss2Fah+ z?0R&gOvHo?GBxAle0vm%BP2pY{Vf%U z>)*Z}`RL*y^?>+*Bx@iK0U#nE4}8v}0#Hb7d2kIP0T6c~iLsEst1|rKTo>do-19oP z=!0xo42}TsM1aRvn$~`jXg`?d?6k}7V}JghZ0|P#;6KuLjPR}B*H#^;G4`FQtvXnB zl&ni>5(NDc`~QKuqiC?46(@t&62}78&|tQjvaA+>)T4SYYM49%l8BXNV}VD&LMv+# zBml&3?fpSV;YtVK>0w>Hf*? z2Qa{zXMKnOa<&%3eAA<6_0t0}&-vpfEX)5KDq10a7xq_U)z8CpwRHT5)|>|!M&v%z z>>iK#CE*}`BO=so#(!EY9*1e`E4w@Pb$s8-VITn1F&Zb|LA$pi0(|wzU)$Pm{Kjvb zfdKd{`?nDQdZZ)(5u%rckrOs*#Be5{gIocdwE~PSx=Z&;Ha!$IO0fY(m}KwDEZ7=| ze;Htvfs?rC|<5``N3`1u%A!{zuNEfI5%F|MWT&vQfZL@*39fn`G9* zHMKR3SM0>&K@Nd5){-u!e}5ow&+!yS6|&RZ*qFE0n_nTc@q&%5SM5U=TK2s+1H$lo zN;4$Q33UE)`0KTZ>sPitxqi;aSM0^l5g#Is;ix3GyXVFBOIr`>sN?^`(xtgAZ57vE94J5a}>sC@N=zzGa6z*P31{R29;f!GEhB!5n4 z!O6a(@H}VKdG-GL0Z@?-aA0U6QIn(r1BsaSf7RjmRiaIa{{e8RV$m{N1xpohtHBpN z0EENy{TKf)qd$rL*C3>o^>2Z=?yIRSE8y-`!rHq|@Ehs8ork9eqo37%IC^yGtq1}K zVKN6UYS!RQlLQ9Hjv*5T`8&(NA-_^kQdLL~qfqJp;~Q%>vDL7-V$6=0Pz@m+Qapa~ z|MK_mr;xtO&4D7i+huhBH&V;Cm|e9}4qYx@50N|o+Gl_47=H&qJmlbo9lQO!e&1^Y zazb(d_FO-(K3v2m_x647ee~nO^?*42G;mlx|AF5>1RCdDAh$m7tCJWrwvrjBI(#9~ zzr4u0Bme*0#yuzaI**S$e$rMrOOr!eUw2Q<`#yQ@o`vJ{GChj;D~8H;A$6T(PaC#CeE-eqf<@*4#n3d8{5Wkw zFZ2XWm5AQAz;AnL&tBK)89~*&2f6V4Fg5_P1JJ)m<=*yyxYitum_lVtg8avU9i!2L z)Bnd^%>Mz#glD-}|781f9%D-XE4-mK)O{WOx^NFoQFA;#5^nN%N~k~$=|l;>VcPnA zcJE&~EChh>0d7~Cu&HhVNpc8@VyA%PW2<{y53>m!8 z+qD|#8c_rETg2_hcx@h^0&~>r!-|}nxk%3i1Qbk?4?NG zzXjr#*ncIuVP6>gx?M`#w9T=CEj_bj$tRg(%Ap|756}7U@nF#?PG|*`&=gTs@!Q~N z(7$p6MEnn-AH#+yjMbs+idqWC$aY9C8MJW^-F@=+pA**)T$n{Adk)xfGP&Slw4`9p zl*^^>f@m=U@{gyd93i0KKa!$3X~6CC`3BE_6WsGdY=!)Vi#lW|JcbzJ5q^Q%y+Faa$WD>Ks#DT{Jpwv(zrTG}U`>G~ z5{d~RkrNVt<7`hv2|X##fZpKVzVA2`KMK=I0#ICYasS65Y^Jbt8G`@_{JDDt@jJgp z`hNL%2OJ;beqy>WM~e1#a@}6T*Za*}(XLG-ZE0rOR;Q-O`bTkt zM?cs{{<~QP!Z!`v?V8Z94SenEr3va3QhA8mIO2bW09K6pVFXLi%Oov>`&W>k=;}?2 zEnKnu;-Z~iYue)*F*}dN|8zCw2ty@??p5qB&RO$8Y9E3aLkJe^a_XjC$X&BbBR8Gl zXJi^$<``=iDS)FlwZ444!-)H(=(l&c{Ek2CIhyrBr5W^1pbF67JSz9H2gH!)fy3iS zV<(Ux$}=m6<$nfAK%n~{U`(8=81`Zyer0=fhJcKB7t4Qr>i^otIeGRy0pN*%PF$sZ zzk2;v_p1!h$l%6d{yi)NfbS6BNqcQQmF1DY+hT}umIwR=RULj?(c*RD92d$FgAND) z7wCa42Lp|So|!=0B$tyB3{P^X0u+!!_DP3Lta4k2-06fkJ`n(LePOb@C2@OFHZ%fa zIxbHVmHtZL-ls$^8vy$i5dXDA(Jo|4b}?JC_3=q7ADgr4r*~OuN};ULHle{}uh4O#l9oxWd*eOO36K0lZX;{Ij&DUtuR z*pl5$EL&xaL`V~S>^RlYFgz1izdeBPj`w+h5u8+8I_r*02RaB4zvNz;{r#_ifnNIP zrmj68i0vZ&xsbo4`$ZZM@ap2%doLnF11!v_%JN@~p+x_9jJdSG-Pe(D%wM!|jz|7} z>+zGHj{9wUZ|DJDd6;pPI!~RgG1b;r-^tpl<5g#W@fUybRRS{nCi}lZ-B}pO0O7+; z0^FilcQzXUHwL|{dwJmm2GBz><6e*fVsuUhExw=Gd5_J8?FI|HznmRI)O{ZNe>G!-(o+XW)~OYDCm zRjEUm^bL8m5v${%a9i`x2>t3-ryg$EA({Kt zZ5~6y=UbLsM{-21I>||oYMg3FI zwtk8u!oJ$5Wl#Lpw_j69J%3 zQpalR_u1V();V>m?`(1ZP6EI-@$GMa`wZL9P=ABEtMFK$h@=1xC?E+Cwbw$FZ|L*} z0TTjB2`JAIGL(s@$w36fos9sD)2_E4xkDKND*P`t0O2xG+=+AGk-xP6gY;Jr-LFj4 zrh+YF<$am7zOQHT@6Uj+j={lBo+hU~E|m#tj3_U-Z?<9+=vk+b0EFQD6L7&{YjU~h zlt||cIdUD`UxS^oIg_dhxRC^)wiG215dD+OSQEPz8wFd&VVQAR>J3}o;r;4hNdXA* z6Ixra@X{4al;d`MW7ZzS@NgVy&?IW1tP}ZbKJ-__{nzKb) z=6AYJMvqN&{jxKwZzip@kas%&S~+da*)ym^Qi0!pn!a<$pH7jB>mbEh(D5SXKp4qO z{MuVi3Xoe`vQvu)7S=}5^C#?7b;McwOV{6D5GawzfxuO~|K-p;I{%^*`!CL{SZTWG zqWrZ+0pb$<%iymUi~o*q)r@mxd&i#`&Q_v-(1UB1Bn*xURU|<5-J^2gJs`Q(s2DCn zvX28xCQ-e*h<^|OF&H^{XY^YXC@zA&KN2Nmyh8qh7q%_`yFcttz%d)(nh)@EC-N5# z5&__mzsFZ11g7=0MO@lcAWNor~0irTph2f!HECSAN|oB1i-&#e@_BH z`a}hJkWpX@A2X#|ZB#aRnI6%55tR~^?g_C|2xF8Jv6%gEdet^S{C^MEya=mWMpSrY zinxCHc4PIOU0=6n7x<8=vH;N6cP|3-L0mtDbFJ7n>}|yUTXrKE zwiiyP?b2A(w(>b!JNpDy>u2ah5ZCB*!1W7(xi}3xU&Mg&+Mj$HWS1u{(O2+FAoOwy zB!y*od}=^s*S*T_Sin%zkdn1e-S+*fhBzkIk5~dL(&rW#{Hl0=-0dJ0cBu4hn>~aSpAQ%JxiR3 zDbj>zK>h<8{y_kQV~G8+qY(iRW=%OsfTYFU=gz+sj^RrLd^!mLO#+XX{8rPjvvTN) z&K;U^*a!f1OlJpmcA)ls=c>bf)j+uVg)e;JJo_(Dze;^SwM$`Woz4di3l3e;0!0bl z5+Lany#Y37J_z!Ug+pYcs@XJ?GtERDL7$}D)Db8#^{%gqjvn-H4LXNa;%lA9)?=f)N&2XBB@h4Ik~ReKw%+Z%kC&iF26D?PSm zc9U;x^1Y2B$P)=btvCsOhER%567u&P(h)=;;{2sDQ6EYt)o=0Kt6nNgf1*D|Q2nG< z7A%g%|0wYVPHm0Y`C`V|evA{}UwcCQdjQC;Ef7(t`JiZzC5S?$_PriiwiUcT9a}luO{453}9IIqZ8p)Se6u+-pYcRr%@g zl*7(O`A!sARP8)ghimkG)u1Fl`N>bB5Ve0z?OvEEZjfaM;KBrBz$D90r3;o+p!?u= ze^&dfQ~^;Yr@{n}BAQY}sxciy1Z1d(y_4N%h?Bw9%SxLTEfZ6lphn}ZjE!LYC(-Af zFs<~u;{0XVtrWi3ZON{p-@P^(wX2h9yE&P&Ev)@(W4Nr1Op-*6Xm!$AJF!2{-;Ka@ ztlw~HYY~&XNp5+$y(#!jvjV5vIU6)9j%x93=X;!wKkjukYJDSNRgiv-(7N^3EC!M% zPkmW%U9#_WKZEYIlKec7m(W-@@VZsvqOMo!|BzIlN zA4kswFLgbjM-A{eckk_g^rZGWa8x}5<^m76x8HvGqceBi1L|=g0HGjSmI98-@_!t? z{}@$>UvO8V|Nh39@oMY)rAu_ieh&U4iQM0H_FuPg3kFI%xPRdvkNo}Y6Lji?P#hl4 za#$q*8dJZrI=8-KwN$`|aQU?Z-a#sZYJcZ*No2QFoPq>yL;40OCYR^(YZg zvz7!Nmfo0=|&b zU21^TO2JOj{-69J$Uu3yLA{~ZGQt|#L5`RC5r@<_^x z`4L+=|Af^>&{-$p?4{q2vzCOsv>82rpi-E#^4fD`_05C$&s+1cAHX$E5&(#% z5sW4QTCVQ~)%(lZ-{r{0t73h@Qm?*b@%gvy6m}m!bvb9#g%MOg8GEig>vBIx`<-+G z@ZP|!W{RXinj4$&{of5;whN&fwn2F3*WdlN%}?X@H;zo;v6}PsR}c*)dg>FJcO6!t zgwERaqCQW$xu*H1Cre`DGA{ytoXDp8y6E#2k1pTU142&tYaw%L*)-h#MxE9PY1FAY)_LE_+IA8F8Vn822tgVqND}mO?28b%t!VJ|G)K>i z3e<#PAtQ9SfDDBW}Se8m0#K>)3Y zl^vGuPWzxyc=zl{IxZ15Er{7K9!V1FgFOhTV)woYWNH)o!;)k(zHc@Y2191%Q( zyxJn`{Ww?sCJBHN+7z=OMJ(ReG1f_xFpguG<+>?ltOl_Q{c!&~w1*b>*{oU2CrR92 zT_C$3E_c;x*2>N9z_p7PeT1F}}+& zR98A;N;?#Z>7}O7Y93C}lc*x(1FDVn&A>?t@TeR}52(k*{b#5-XZ%;PnfQjw!IFRo z*bjW{+aPfaF6ocN|3TVc7X!dOP;b4h{G4zKXBBXc04dv2XODk034C=^v3<;DyR>KK z_VJ9%5Uz*5zy*=~&b8Kpkodk~kaxoSJ~VGGy32H>Q&48mWI5Z50S2hpsXVMP52 zMEzM{jyxpPf2garv01m_=(Vj5X|Zf@@r!Jc=6P-2QtPWWSq#|;h^!f+`ekwROSb(! z`a_|9EP}aFfEbhk=z3(+)-zkSF}7t}qeW|E=>VC1D6^yV{de;{yT04EV5kpmzr!gt z9A%+4i)aCSV*m4~983==sZTzlD66EKre+cQi|d!gmb1U=3qt!gGUtHvN)0cV-zoOL zHFx~AZYvz}VV#fc+~<FIoY=wd2FOH|!pr6&6*J7q;>BC7b!imo0JQqMa^{ zp#%P)ov~>an$n=k_IW3ulSQ|p`bqS^hUDYFB)?)eAOIG}^7i`k-(xpV{u8U?*S~e{ zS%?6ore#9$+Omq%J7YL*O!A42Mz-f4g%f}e-PTUS1x{) zWgO#}t>w#6E5AjC3G5r1$rA)b`ezu#K{VyhSab4OzMZ~PTm-31907F~%|gl(!k|)| zYwX6Gmi*R>mROy)IduO2;!?(*U47QZNag!n<%H#MWmSYf+4}ch0vVbHV~x4-oybMx zKufloU$?(|*Ej9evu|5H!_0X%IoqLYS_y0lpzC%`t=?bPaixes3EEVJqt$BFowK&% zhCX*C&5(*q?u<>Tr$mSGj{@9xyjPWJ<$!O+0C+NRiE(PR{A7j>G# zHDw&`Up0p+Kq-X9C=4=Tdwl(1m$_c0D-mOcYBh^*ts?BK)nSIC<%b{|J_<1 zSa$n>F7x4ayBc00lOKs(Mv^X;{{{hm>N(a<8jE$MsP&@%o?9FAs#Eg21UDc;5d(0; zj{Dc2qgd$jmi+t`+IJI(vV;U+DMGZr6tN?YTO)kZnh884a;QtBGEx6U+k{iE#8cOP zp}%Ck?xOu60oYiu*vd^yt*xN*57{Zi{xf9u%Yytgusww6T-FurLU6L@rFAVku*(|HL%mnRK!DtLQ)&TKzm_wn`*eeMKLcYobth6r$? zWS)OlW720c9-_+yOGkjEQ%F-MfuoWD#K609`|E(xefLP<1?Hu``*IHpJp9ErF4@K{ zoD;5574GT8MVcO+mBYhb4!ZnlGF2bd=<24YT5Reo=WclRp{Lb%;{MxVm z+P`G~^VHjl@Q0)Ppy)%my2&L_8KJ^Zi82UmibLLh{cX4Jc_PXHnLuX01Wh9P&mi7Z zs>)M%21L*umZ_H;xO7R6co>S10T$q-Mzkodf5+-6tp9U1)yU%d7dZZ@nVtZUMpr?7 z#04pX+dDB_x#0d+<5jykGiA$!qg|hv#JCH8_3S9gY2cEi$9Fatck#{Av&vvi+$$K< z>8%~y)idwnxd%B0Z7{H{P6FX8ieIZ9Ldq0H0wBXvV*1nH&HN}<{uujZ2zrzU@e`!V zQm7k6kZv3K4f>rl#09Jg`Y?>8f2drroJ;5vwvnxj%@q?iUCTP1zYxE-`RMnJ;*u5V zQPQD#Q2!-cw71a0ZG{WANqXnjD1;`OAh$X_d*1I$dK@!7c6g5txPQ5~VxsBhf0J=( zNfL0BEl_*x%X@j5(D4NNeYyP|$K_9lS^ZQ&x{V3Dh1_Bb?|1#)--(5a# zGlbkdiRJmRRt`iE2#EXuRO#Xsbh;AzFObCLbJ;iSt@si)dMW$*_x-S~kBt%0ZOqEE zrx4l0xe9s7YJE@+$#M9!6ZK4JbJ1-1l7$m&tLxbCfK1}pRyYFQx9~pq>8{tyvS0C) zw5=^Rt@I9_62%BpioiY_??>}OOn>6|Hy(QeaX6Ba1Y-X2$LTW=zeLO~K0+`CyB^*9 zA>w`?CA3@wYBH*syaHp?(cz#!$|Mw6(L~hj67>qs@U$)c9AmC3N z0>J5a`t1%TTLh1y2!VdWVF&=$S(sxndfp(s%Oiy|UWAGKKDI&v!YLlVczomWkKbyl z_{y#;IzF`Js1N|Y6Mg5Z!?nVF$9v?j@6llSI?=WT_-W34k$QV^$Vor~WP){d1f6Rb z0-#xwo7rH3CLw>U>ZnZ{!+7P4!dCL;SV;K-q`L|T0RK_9H|k!T;q5XAlkb0V!}sxKHj5SyniuN0l-&?=U=c3@fG_vdAKWN@0&k9W2LFnfx%xMf>}m? z!vc&>0s#A5#!I2KLD!ZYO%ZaU*t-Sq2iMomy^kz@%3|2qB%Nd1EP?kfR8r|Bf8R2WU-}^ro ze47FpRaw7vi2Np;|F#6+@J_-0KlMJ{;k!^N)u&0XK8+M$Dux6AHEN!0t5U0Kp84zg zX{KZJoYlWd@gC`$n0 z4`tJ~8>J5QrL%K==liW67*S~&EKzJV^fynl{X6R0)O`v>fK&mf0fN9lnjln(j0EyLc0}De4B#B>;Mg%P6A4L7r>#^{JujvYtjKT8Hb5WdpU_O0jN<0CcFYMOSWdk%6Ch_J^i@A|ZBGkvBeV_R9@#Ik=W4&qN(jfi^9@Ej?QPh;$dgd{(WQ_&Rq zeTV=V`N_(Ee}L3S^Js|rPF1QCQu>C7>=$2OA-W^^9ZG4NC9qN+!_*WO|NVsZ-Q9>l zEmVW&uh=H@V?J54>uGX8pyMxRm=j9vjKP(YYUt+96}7m@-< z`c(__)w0R(ZmPq0$wT}M!AWIhNkdp=fR{l)HBzjTXid3RJR8>UQV*t@?n3eeEO(aw zP9h2L*k39sT=7yHcWmPl&UH!vJl^r!ZZq4>M(#VbWnU8LkhEHz=*PaZlhyH>JAMFw zc5Z<5O`clQcI?xi{`3UufRD2O57h332_a*^M2Zl#$ZcD7f&$erSgIqkl|+E!eu+7G z1>~S!&!%r$k(dB^e7iqb9=By;>)#;K-kTU(ZMtlP-J5ivXC+<-IfSmhVWE|4mRt|p zaoTql-|taOz|t&96^V7P5#C3@?-J=Z|6=kg1OUceBN=<=*$>$2G%6FK^;J$h1rZ=a zKLJMF>xaxervE?AJ^{kJjLyHjWYHXT77;e$!00I8omYg16gZ~;#_e$jT`CLz`Uc+b zgz_!Em9o-XBr!tm)5x8-+9YCsx%I`c@*jN<{e&o4k`n3rovj4Zd0Xed$2)pC4dQoV ze{5JnWbzBY_7YM4uG=)yhyV6M%1&>bvlI243-U7t5fH=vML~Z0En1AS37N;oe*?~c z5nGV|=fsv>NtJC4V&;1IDHbOL&sdS~ew%f4)5+--O>pR?12X9OLFPXFz5915mce>! z6BXW~E#PLbMmXkr2Ahp639S^0`H>yKT@9z8#SBc5BBxHE>wiz?hRp$MvWonN{$Kf4 zR5ZlBkEXn`+B$v({6WPQ&&)DZC^m5c)C}3Dd=#7^y+73JK-|B7w3>XVOaH6>{(O$_ zNR5BTQg_JTpVKVyM1c51Pr1cD@rh470|D?w&V7~oerlJ}mH;58ZwY{6EaH5W@acEr zd^h!cGrHW~<&-E_r3{XSwk$=2z#3_7k29&0*Z@?}Qw9Noy4-kAPVp^>hC}#*8@}L? zEg1lgf&9~mg2fXCQ$q%S(&@_RZytZ{S5s^DR;GwQH%Wa?9Jks@5WkGo6zE6W{VD6- zzf1&*MAtG>BLR=Sv^`FJjz zz`uX`IXHf}e!28bBl?%bL?1B>q~G}w68p>eK*oPc>pcICg>PQ8G@SpFYv=5lLe@rG zSrYrC8SMZV_6}G(UnJu=sf9rJ%#vlqv~T9hb|FV?+w$p!b*Ve;+s{9Py9fj2~g^afr6NxqnRy z;T%=%`^xT)eH|a#a@auVULB>*^~HB|=T?Yc1K|k(uLke~nESCG`?2Hv{xkj|-M8&2 z#zvH4;2P)y1W6bkyt1<~-Ji4btU6hfJdSuPhbmx%n!(34rE~lSD!Ye;)(bJzaiyt| z%D7UuY^i3M3X82tXk>^JaZNsPO98|$&h94S_vIAU|Jj^XG4!j;%0D5OJib6cumj`{ z%S0$AUqOA7ghvfH{S?NK86kZL zBp1V924o^GC5B{X42xh=e>lX?*w)ZND6`|%ip7hYHbECoS7J6ipN|?c0~jt3luCY+oY8y};;nolhw-|5}Pr>4;GA8js2#J)n7~DtEs$h+Zkx1slos z0n-$?R1aeH@7khuB?*8SIp&{(=ORYk`F&^nzii_QsPsUM%(fc=;AgUCb7yt0Z=dt~ zhjx2ZBmn9_4>mMQ*i&MOL3cS<(c(}`$^rh2H(GcPWL~YStgw? zR?rg@w($HvwelDd{@`Mp6F62VE1fGxax`#u1ngd|bMeWND=gec@MHHrFdSjCI| z8Q%~w{UhIb(S>zBzhd^^AcZ);{)CMZ2ukzS7-YWag!zQRnFCT=M$TuFlIstfdr z-b&D5?qnj%pk)HrmJG;#0>5jew_MjG*FSy1y(o%pAj3KUbOhi3QR3=PY>~YX7B+#3 zLVO`kkj|iM8NKcT*0>k5RlAB|S9O&1v=jLF3-P1-Y`Ne*;_fJWFRI}8e*dbSic*LO zI~3ls@JJmM0E3DPnNr3E{o3zChkU)pjAqKWzlo-zfq`9p3!}f4JlYEyJB4xN7*j4I z?jK#T4E|&zp)$<=lDfoO`%7AawSN?&zYwaO9QhMYZXUPC$)_L#PeuBZ*k6;pUm7Zq zfN61&>KWu;Krp@zpuRzVhD#aDL~#c#j}qTtjPI7}MpB3>wlvr}IDU>*+2W-xyoT$9 zgZkrElv`JBF%S3}ePEaVh$ za2zAwS;0mm0SPDeN8&dyP~@S&Yx(;}n0p}?_E*RsBk%p!-Osmi1Y(2jsDHvC!Y7^x z5Y7<-(CTkPfbD%wxuWw&q8udxKppBkR`A~sfFA^%)8P04@s1Sno<9#PjcK`!cu z+}Eg=Ys9!h65wF@?i+`BEJPvWKdk(=zo#WMr%j{woP+p@H5R<4u<@Z0$ zJQ`zti~COjA2GY`d4_g&p2p2FZi3y2{awHx)?I|^kbmdJx9@)n+^`Ogct1bw=Ked8 zzwnE%!Q!}u4E*u!Pd}t*jv@iz*R=0!4TjG7LD5ziT2%w*kUv{}YwTBkm8gTzkhb>X|FpER{44d57Kx82T|AgN8D!JlUEpl$f zqO>QHWjqq}raJU~6=t5Z_DAgBs)nt2DQAT@Kz@}GYoyOv^O>I{s1)4(#0iWeF(#Iq zpZZD^;4q8C{&4(~lnD7p-}s6}map3x@(ld=<+M$bU*H6ih-WIt2=YT96gSSjkD0{a zHRh}g{bcRGh*GG4!Qb`RrhO@Q#padxX*6qZKJ}Dso`&eb8>Buu!xkbyAUuug17f)a z2i>SZ9069t2@L3F*lP6-vv_F0R-}b2SpsX8{`y=5jv^TrLH<|x;=d2SW^1vQU7J2@ z)$@;I(3rE<)ES5y>>Gw{ygAJNIONYtVGs5Fc=XK3=O51h3HHZgWTj-T1#wjRpCE$Q zkr;7Y;QT`p`x8+!s#yOb2KHxGgz$e$xPh%EjE+4K;E})ZNhgj`19j|Y9=ope-*A8D zeb^o~0zh5lJ6HqdJ6{8#q6jTAR40zlY89tukrER;hHfNUa?f&f4w;WEe#@aUo4!r(ZgKXlq61gZ;3D_zDg zvI?@F!^eN_dq95pzKat+NJQbp{!DN66{(!V*Wa)x*8Y=gd3*2j9RB`EXYD`N92qFc zkLI9qJ!no;__rF`baUhqNuORxUWfa~8)Rh0mS?A|bo$+Hezc_K&^(cyOhRf86iST^ zj3W`7(^oDyl2+w`O>jqgfc^)w0TBN$!bj4MRp#6UoM2ahEUP2WSZ(Gk?wb%ba^)O` ztLxAv~6$9W7;r%ReYywyPF8`$X_gvL;h@?6yReY``B|3 z0Ds2uMXCmU@4}m$;RtGg5FDxt5~K+QqH-An0gmE0`Yj?MWD_8jKuWd&Sis6nsz9wm zXy{{xTKv?kGp9>rped|dt5~)=a#;bp3NARyaAz>Iwvr`QJ)D0l3+L(qy0{$?ME!qi z@1G&$F9JmfP2qnfElE+aKL|(p0MQ+K|3S84uh#N z5PDM)qVwW?o!74c>I;y*jw*0z8|Y@sY|G5k>v8HRl|ZLyWYE+(BO-UaJHx_@z#dptRK{-eL$dO$N#`hJOB$I$aj z-=CISH0xYkzZj%`iyz7D(I!Ahh-iP#gUd-MyU&1*_grNE&%g;EU@L?#&R^9N0GkYe69E1Ol1JtATS5IYZDU-0m zIw_o2m+b_>hkojYDh+hyEV6_f#RgxYdIR$hQx^r%x zh~~xJi^tzYv@b$X5&dp7mJonfaqVl^E8}IN`*A18zB>1WvwSaS&)DkBhamvSUYKl) z{T1;~tI-nyB7$;6Q3ZjvHjp5^F=4d}h-A|hOFxdvA{!XSN}3~6n}Lg8`R!GY#)4*e z{$JZ}=K1HWJaZaiN1}hg zrZ?ssxZw}qjWT-vzQmTDL+78z^8W*wtAzU{Mhb*L3@NBA{`)O5>I?M#D16}fllhZQ z^zS17Iqv_Clk1-g7w}#duQU7;j@S?R`x)oAYI5hkj*m<^$^?KX?R@8JD=?t*+6wt= z-xC2ER8e;N=IUSm_66!6Q-6lqy)eO~Q49gdolSszn(;4HZNa%at5UtW&mvKm zj9nu57uSd#dz_fp1Ofs)cBmg%u zS-Y7BVPNP~m#7ncuH)$B%k4S4z29*6zbKizxPKuyY%Rh7ifFEi*dMEiI0(ht9QcvH z`#1Lf1a%)XsYz^q8MBF-tuBN7NuO&|6C^*HMNI;s1kiEB(t!|4G(v;u{r$=67hWgU z{_29IH)1xsHECyxNgHn|%x?l~e`!<$akli@9`Q@3FVrtRx6Jy4_&1zQe-$NAiOgBc z0U^Nremz#PYY+gILJBj=yC>shddyjU>Npt;u?b;rG^O(wx3A*oiMDN5#}>i08pI%I zVJsPfh;BLwfI2j|Whj63ELE+1_gqa9U)kMJbb)@8oI}3;%JPR4jGkBxZP<+vwlD}V z=2K&~GC4-Bi!5<3@_Z*_t+k+g{dewo?xTbKdO)#IMqzqp(fcb+`Uv9xEH%zNb6vXM z&3pVNu%??u^g)$539XCthm=-^fBJo&q54nU^cuL}!)%2cJdW@LfN+PenpwW;t-iAB ziff5KI4awtN&u*TeTN4t`PP8wyavsmmk1}A9k&Kp-<|&9AO7*j{`PPG`sdmI>Gm~j zx)eQ0vq)ikq5dOrEW4!!sKP;jsH6(e+m!lMm-bQ|55mP^?v*596djn{Unb%F=O6~c zJgbV&)SBW0pcc5RBFu$5mQ!2EvYzm|Eozl8$MeAM7EuaUMp9NFm2Z`;v-VePe*yKo ze05*#mSLsT6J)ImwU+2&!hpglM#OZ9?$Rh8bbI`)Qo|WmA^cWN6&F9Ez|0X`#cG@@a!nl|S);9z&X+;dC0qorb1X^0 zB3$t11mb@_%aS>ZOin`-O3eW>bk_d*Ugn6@9lO6*$4>geQWMflPNGse#eD^&Xjci8 zL{vuzK8%K!bhdo9#C>0a$chDgvAEFO#$b` z^()M8lKz(Hzh8GhjiJWVZD9(W&fn?%C8nii$X1>K#0dbA%SEu?5&{4vSs2F?%eVxF z0Z4T#)KmE1r-(fsx0kWvUM6qAz(q(y5%mzOJMMaI!CGtAt$`=N2Hfh)b5C0m>;4Kl z-Hm78hqXTjPD1|TW}TRmZ{H2v2X4$BH;SXxIudb$5u0857NfIl(Nm}aPGR+rdLk_2 zKR?=gJZ4y@)nzTYsxfu`{x zH;_E2hSEg_EYkr6->!#+=d8q*;E>95|a26v$l1*7;jcm^UA03OqR~8$X<57#tt3##F@pWUw z)FD*|^P53i=M|exo3E|d1-oji;dK@}&xZ`q{F1aIkciZ6rMYH{tu-srq_@YDc4;DE zz1r#5$%u)o|d?%(PD)zC+!*B(d%-=0L>8Kn0u*?ZFS_GD_= zMMceU-Ya7my`G0((`38Ch{dqIi6$r7+S79*496lsi^aeP!1b9UsX;PaWyvJ6@yg2Sr;An9lhD6xl9fK!d8P!Pd9Oe)*Sw z`FRL{KW6`v)TgO?6duQfl6#=sOGE%Poc>?HMUVGQ+2i&-POFjf3>d?;N^t;=W4tBn z*fHJ}$Itwmb+KP}S%hG5t8-F-GI7}nuG6Zl!|}B29jyIr44{sClg*xHE5r}G?ScDU zzPh*D+kGbkMG-0_unFNI5uV$$DEKvu5th^atDEmd5e1-`LvxhIx3+|97~NM{BDv2s zIR6laekaeGop?Ub`3vzMq_w~QX0=N(97H6+^@kQN;`Vph!WeW`365|D$E9zM4<+f-5x6H1zrs0(uw7`y`3{WsnsQwfXD|Q#gv9(Z+hT@$ zg3!0;PFt_Ckz^!)0#yk_a&wXB&K#HVh^Zp|8snSz-!t_0@6<3YWH&Jw)Ccud^l+&tszrb#x^={(j*C+UI)(8i zqnQg+E8{hf^j(8|tNMCd{}-#jB%u(ILY#$gh;||(l=wdczz89-c1B_ciTvBMMI67n z%BAu}7$Ix_S_yqOk{FUYlgbxSze5NR0N&bP$l;)@{df1KhD3;2W2Sv#05prMNGCQy zYj|$N$j^WnzXk_yqj2{zh&x%~Yn%lbMF2=|F9J`-Y#MVB2Ko)j08o_5HM&l7K?r;s zklxLFppP7p1Q)GX8Wki0O(F&&@o5l=vcAde=2a1?0yNHktarbXanew!IC~7HN(0Y_ z23Zc9A-+Ws`UrEpLBO8H7*Z_)Tty(NMFi-+8Y+=GNJlmg%bZ!K6BXCLIzhjY+S-zQ zzhYfDLWn*Q$G^J`?(L8M?AHV8GNty_FpgmO=hFKk^3Ow{CM5Ew?{&?fUF+_XSC*SJ zSo{kPvmdx__arI&Nx^)Y0Cl%R^xw(-dm=y}w+$io+;Yj$EJvLH*xl=XpfqTHj%ll7 zPXqvJ91);z7ZDKqyTALZ=kNjj{D(gDq2J;7*Qk3IrWZh#$p+Am5M&~rJK^jAnzaIM zVefFC=1_k{jSd!rA_NxfeCmeHV8k_!M}Uz2O$^P}i5B=(wp)s&+D{RJRq&trONfnS z{I_PU@smz0>w?rg^@9Yg;aH+wafd<<65j?5>gP>^T`P=>54&{Qq0&uo(OabZ{Wh6$ z3uMhLI~xEO`d7-tgK869Bt+6Ip)04WYKxd6TmY%yx>k!kZS^R@eZu3`px>G&o}rIG zWS(#m!rXx<2kVBO?&3Wy#OaNv88e00MXJ--`Z1DK)&Q!cA0}H;m}_d}s;|M>2d;=r zcOhTbM#fd#JmV{sK+~PqSaXg44hWi-2m#Fj5jQ%oeOCq?0KIbzcuNF5dC-*Ke!o>W zrz}!hvPSqK_6ye_`0$LG1CT4yqwp@{t!C{mvd7SB)_7H~<6Uqaqe6LNMDbdgJ59#T zjD4$l%C5I2E#ATq4455uDkjF0Z)x&P4c2Zk+Oz`6ed?$`){uVHbBrm!w{l27;QpPO zLxj+QO}gD*_TU^RK>m*--dBddS$zCIkiKCjAnHX393yu`1fn3AQG$H^7s1~+Nw&m% zxqv^(Q36aU(;pMYO`3h@>HiL_zXr_zG2Sd-EgYb&>TU^u@J44qL5!~DglthFi)v47pmg~bBWjjb^x!0;M)Ax-RT{AsIGNi&%DN3 z+!QKS#(;9qlG~Pm^6@9J&N&qz2wAWT=-kNNcMNddNt}X#E~+iAg2ZK{s(nc(G^QSjyRPI9w>aBU{c-2i{`StWze#{u z1d}8VNK~rz^K22Q~yfjr_OU7WA)^(y)p#y|L;N28x#; z0QiPR>Kx*-?*XA_?Gi-Nl^AP9-|d1*G5_^VQq#1h8?uFHI<<}LB4p&pZ|WmntmvQH zW!QbO{on_8M@VG`BtMF@FsH7d*L)!N+FWea+tTrMG zhyjk>*zRhpF4n1CkLj@m{axnT)NY678Xg4(*MHwvv76GQEs&NljPzxXx z*pBFFv(89&<4 ziZi}cNk&>;J)-N?DQ>G5J}SNTfVwOOtP#DL0#@Y-ATkU?M-5$0+wZKY=17Hb*%ud9#QDglFT zAPx9#BV}uHOWdmnyD3h*Boa$k&Hnr|X3N(CZvWX2wMDWZwW)IeW5k~-4ygsZ_w28@ z|8M-28SZS+@KquXe-YutHwcql1^0$6HjTPPBRH(mUcxQ9rAEyBDpvlDO2kSxPFrbl zj`178&;5keC*k^|z>54S0{p=JJO6&BjC|fbhj_mbh2~th(%BxruNAR_%WvNpOtgCk z(mXLNdk?Y{I%2fCX3>q;iDvi?#9zUpi?4wA*8u1ws>NuG5&KfFVpcg()%jfACrzc5D~z5MzQM%6YF1$Rtgu~C~MJ$`IQZT8^3+g z*}wnnXFvN3AN}Y@Kg>sJ;ISZaM1TkZnUJai6}Hs?ViZLHbP@wvHJz2iqg~o7;AnqD zm)3U_btB zqR=y9g*+%S4W_UtX|lO7AIFp;)1^^sxx^U>qzz@>7lU*4(_J5XTXCE}pDYeY;dO;* z2^s5*?PTSxL^YBGNDq8J5WjD*2o?GM`K=w-ID}zaKt{!m=tq}u0s2^nICx_p5zOvi7&fkZ* z?*~#yH;)QRL`)fX%9`dTlC$Q9HI^>p1p>n7y|Em2+GKwW;i;l-7e1HUUu7OiO;Lnc zhCoEKi0_|dAI@LMKZ{M5p09WL_qlIuf2cp_zN_P!9p{Jn(GSnFgxs<4a0I{v-2QBQ z%VyB`%f&fO4XpkZc4^Qe6{|S@1WQq{wjJ)*8H{MgsP0(+eD-ey+t~u}9P(%4ZR`Jq z>{W&AI}yHchMMdvyAM_o;(Jg^=iJh4@Pnp7)N$ul`xp_K!&vm0tUGm3wI~OKz-0{#Q{QYmJycx)MX5%ErDDd@|Q^TegQuxIbn#9QiSl^ zCc+N=M)03V5#$d6q^3zuGt9#0w{WeLV5UV7r#jj4>ZI^(RAl8p12RDZ5SD!ewh<{1 zze{I}U`U3Mp6efGdmhGTX}+mHiGZp3*pezBg+f0BSD!gak7QsHHyI1&EvlCg$OPH3 zBLpM?Xr>vbFoY|9->o!AA7ii}JvHOx4H?z1_iJ81L}Mx#l?3q%aON4ONuoy1BJ!66 zAPeW8Ce(DC^MYeO%x^z%PypPC_ko^bv?Se;zF%?v<$)#jYvAs8$EW@{Fg+#M&LbiB z9pc~3@e71@R=r-w9*?lQy{~f*M7d+n9l@{EH~A_AuYGMDf@dqDNBi0WiCh&`*r^Jr zU=a8s=l(tQf1>VN6alb>8lXjHKW(eUC9Irppcx=aAZ%u>3WqyDkRb8+!7RjG30JgB zLDBZ5BF!NT`Uvs^AlAdN+vMkFM*s{U0Wl5HY1`;4-#Xua= zWToj4Xu6w47|f6bUVt%yu)0@h6S{lR?JSyrO_~5JKzocW+cL%?!Gmltwnl4sgWmjJ z&DGy`?!T+fyZWo%U(L9XIUPQ`F{>~zT>KS^N=n? zwowSd>tFTQXKO8h##mR~!rL-ya#owHyc^f%_gRm$f`~g4(kXUFtJWv~Rn>Fs3swKv z$!hmq7z^FTHbCqE-23kifb<2|;5m}o{{-8>jv$nAV9tf-uSe~Vh5xLsUSEOp7u3lE zFr-o9UYLtSNBpFn5o_=OEd+HQ&A3I)rT2?G+(8<^emC913XFI2DLc=KC0-dx}Q zw~szsjWKEILjcg|&prRk51hlojuajHXz|}d_!}5K$S2kp3(Em$1iJX%{};deeFzF~ z0Q$(e>YvV*gaNg`X+D*~&;-y?FA@aIZ<)Zz+0wyYCq;;lC>im?3a#^_D-1w=E)o(( z9(dq^+dur_5C3z@zk>)zSUf0&Cht>NrNZ%{Wo%!ggU;e=S4;Aqo^y%bEq;g2HL`yn z)HO3LXkRpRl!xv~u7giZa>Ogk0ms-T_@!yQm^Hbi7p84Yz%gdCZugVurWu$6#|Bp_ z@Ej6+js7O_XFvH>;v-exG_HT~y4E+sfFBfZYx{f}{LP?Zo_r1gU;=lyr}x8uUW(R+ z&wJG?s_OceGo{gxj4mPW*7^a~_H{P#-T1KLR^vPSrb4N~?Wryap&go?ILp{!vSy!6 zWk9ts`ZUmYfy*E=0GYp`e5)D{m+`N@{SUy{cMz|~XU9v2p0Dm0Ihu_9c6g2l4$f9J zguPf5f6^E+`-i6Xb3TJwf!f>OCGUQcJN)wppyfa(crt&Pea!yl1@ZuSfialAX*%3I z-ypd)!&VfR>Hn84Y|V8+aSze zHFUD@m)P**Y0>$T#3lcgl3pnW?28HC;63_i+Ny_eph2HL33Rrltx8H;F5_1K@LPF( z`Bp1M|8lPr(*w{URsYf(t^N1F{C5#YFap%tA1kOt>6UwM+b8PCkJQlRRMh=0sq*dn z6!?NDboa^cm4-{pxiHanU@-rn`N0Q-!5{qjh$QFJ>9H)>Dxo_xZoaqmy(0SbvXneR zJ<<{Y6hCPIR1LwcU$84+hR*Zh`|rR1=cxN>VpqYP0JE%Z>n?bj9RcH~A19BR6I+1k zDeO_4(JV70T>xr+d*FF?1)RV|@Hq?*kKzR7Kb^d#IyEzxv;m)GS>QCw0vo!g>XGpH zlT~#BOYhku)vk$OtNN$Eh~XDU(cIjs1`jjv{W5FOJ3;j{?tEu-@^glxjvv3OI{n2P znf33gW)5?V?{)X_)tObQ_SZIIBM3;#>>FFBdDd$^7|Nw0dvaRd0?O!JwhA?WVf>f% z(>ol8Vf;6t;@=6}4b%U7yS~EVKIhVe!0s=dku?|M^@G24uSS^&~&l(S`Z1 z71mdHpX|e@^<9T;gmyZZe-syZSur4ibj#mPX8(I&@`nb_;oJW#v;T?Yv&7T={EDlg zbu#}%=@9n%T>DQBf9gH|U21#&mPhzmX!q9vr6^6+f6nZs{lWO{WNoQ)o`hN!k>u72 ze$TBM;-dwO4=aoqA3h{NVZIcglz81+-tv}1zyiOBMjv*aN);BJSWi_*v%Q>s z>e^MkhP4v;xc+Ic>__dNw%A~GyDuHFd9K=z^u4c-y|^5{;kq2g(;G9W0r5ff>f3)mGk=Z#4iI<3__g*QV!hwx$y!HQPgJ^n z*dVH|3^EXzdU32T`~7>F@h9hM?g34)Yj$-{n`U3f4P&M+jOE^-_ws?@0l^b|3e#;0 zG7l-*dSR<-06KlC<_Gm7%Vz8VLOX}hC>yfF*yH*>@PQA!;-QBg`taR%->nwly~L#h z1k0PaPT7ac$^rH$&*>ltqb8RJ=4MzPz$Co~xRT`nx74)YY{ETkn|sxc$EyjP20hK$ z0S>?u>|TKdmWJ z0q{Ga)u*A^4{$?ictq)Y9-GX+$scIG^}|*d0Q{&CB=7N&gZT@iBUrC65Ly89a!=#P zYhU}?SF;rGA4vZ`@gEQ`5$McxSUYh)s%1R}_O{Meljqp)EO$zNe6>qieu(7&&&Nq? zazn>?iJqi_J2tVWI$=5I!#|3R04~#({{!oBh1eAP34&(T|2Y4t@DkSB!aq1mdoBZ{ zwg0vFeR1s9WXMk)pRFdI!dv4Ed;f31;{4Eynf>G3$2I@7cf9MF#acXBxktgkrozAg z)a4+|{}4ug2QWUq9c%v^IIf$s7ppP${MTxK2lq;YM8U{7#Q8^SXb-m29`4f*Z9p|B zQRvRzL)!cwpw((?4Kja;tWf4JZI>zp%@6wT!EI6`R^efC0;T_&q*r(v?QSO3N2byZLz;K88pH4(6L3^OWw56 zz$^8_WgJ8ex0CHRyBL%j=AU^}a0lpT!k=rJs(;*x)<@u~_OE9h^#hc@1p@^GfdPl&C@OuI5_d{RpeK7#`Ab`d z5d?Jb)1RsQKa-3EyI(4~wdr{h#HexbeYia`yIWY7eUazC$>Vxf9C9`hW86ui>AVE1_VZU?4Eyh;W~okSeZO(^NOf4lV+@Y>51y$8(F90Mj4K;KT&F!0|B{m*JUX`Y{D>f+(O(bS zrx(=zUH!tVq0PHK`N_3>l1UF*vfq+!ahYdk4=bvUB65Bxl5N-K~ zv^T}awi6gE3+8W`9VLVSB}mgwqI*C2$@jmSLnS`Uc>&r3{2uWVK?&B|1KDHVKa3xK z&opIuV2XoJv<>j5QyUrMGJ_fb8K@7q6C=Qp-e)Q4t@cmiXPtwCo}=yvZi63T+aUh+ zmU;K}YR-GkfaYn?Ozi1v3jndrceOtYdS?&-#vh-;nG7c?%-&K>@4AcA->$-Q+>22C zqyC4$q_1B8S?w>D>k9_96b5uTelyJ8b^q&F?|mw};en4_Q zy|Nec4x1=!6pnDYP!=Crn1A@_40a5o9VQG$>_mB|>fuDGZ=}riruPuL47HlS7sJ5h zC`dII9p8w*Tkf&246xFk=N8QNb|Wy&0D{c}^0s_`Kl{@|#z2M>)N=Zis6aw?N7iqivlWeEiX1p{C} zy5Nj|j1w4lKtpuy<5HqDM76(5jMA2#O!dDUQsNN3sC_!lmzln^eb)Pv>OZOfYqr!S z^M4Pw{rxsg_VzjRmu?3gm!=1O4|?w-wJFE;V*I>!3fn~k;LA4qUwr)N0CpauokJLc zfW6U|-DNKFaPT-bB1)NGdJ;4`CG8kM}tR0UZYEBxwB9S6C9K@4~^{ zDX`L@Ho&lp^}5?fpR8^k9;i;D3FyU@@M)X{J&D`khsJl|G>F55Qd3{`G6%QZ4Po^+ z22&pJePz}lo#J!=kk7Tu$5MGR2ioSQ-0s(^CXVi_&OUaK_5a<~%u8Qc%^iLvGk;Y7 zLkI)z_b;JfpkQDg12X^JF!--W-G3D`f0_S%>@L~^^B*N1z}mmXB%)UNOCnbg9HcUM z|KaRsXy=Vd{qJ7?zM)+#k-ANqx$*FtF({AYB+{pTDR1-H66eW4{~Np|cypBGastIhp-mg=%J{?FMc>&8kOcPLpZ-%+A9s_Vd7N3pv}SfrQJC# z5Bgp|PF)x2c+{@nZ7VeFZq~XL-t^*kun$MHChyacj{4{rxv&&oz#gPmCVrf$Lv=`n+Z>OvAuh1K>~EXO|y*==w#}2;gehbv*{P>O8%AUC%(j zia|flF~dE~z&+q&3eLH*U+d!e>W8TxDjfrR8W9U;NSyjN*!Q`rX9CASlqY9EBMLuV z+%s!Z-<~%mF+1H;O&y)7CLTM>yR#4Q+Lu*xd#*$1z}`Zv#0hfQ^(9#_u)Q!)leIlC z_}6fR?;RNW-GO!gE7?VK^YC$8{GMUk-CFZmbbTkjvTUU6XK>qjqp6yb=M)VjeFknoMWI* zfGPGC@8b!g?Q(vZ%iK!X%eKDW0i7vi9Gb7=CLIdmJ^PX)JdA zOYXdS_p4s@s@DQlUdHTS5+;q7U<#$#(sE&>%}ZU3LFXec+;*XBk!uTLrYv3cU(@f` z-WZH#gwimOu!zy!3L>e1fHVk52};*C8a{%cASt0BEg`AY2nj*D8d7rg*eMl)X^@K9SXrZ~EFivUs&f=3j;xMr%-c zy2%yZh{ow2AdOu1?>(|2zRsC;9J3PtMfUaA_&#jmB)fYcxRV`RrZYnnbGXGtYL{ZR0&YU7ZFg#`?>2 zG|o2Q;yvJ6g;U&hkw2>84cTx`3B2+&%1OjL5te?;vYK7!oYv}FL=I_)ft@twG+u{cKcR5NB1 zbj?6_fDKvv2y3`)wBH2)W3rw>kifq+dR&V zz6DLYIe!5KJG5paF(xlrgXSDQ0luNu#wFqH(xU9MKI}f5Xo>a~b|Pig!HR+(XH*9* z`;~!D&B)!vn5Dm45vmRCV{F?Wg8akGXYl+M`qr6O0_62Row;;`vjd3D=^hsfA_?0{!8s5;_Jl4*K;$tcg_mabtB%oz%Z8XIPCD`19-BNuXyvi2 z{TH>|1wC1Ty}F9qOApu<(YM6}Sk6^_gits zMH)=;$@iO`Ho)k(A9B@z%vKGjA{arW@Va$bzQJ!LOY=$$e{FITJQDjHlzs73%Aio6 zsg|6HYoBFb))v6K!znow?&wd)=u@-^=gyRha{bFa9&#t&(FAH?#&vG>=#>~Vy(fBj zc-ejSSw42-mMW)wroZg#mI%T%jNqS$cBw=MEEWWNGEF^ zjI25(LT>fXq!YqXfj>g9Z$)2N7oQ(|D=@vS~q zlXU(8H#04)QjPHJ@!W;=KwQ*#;(`#SrLX& z!eexmb1#qM=ymrxTNGUaofw;0_*Zdd?pTizr(fQnM*|Frg6{(a*>ydjGtb*B?00Ta zKN{d;EKwiXFE7q>&|MQbb7c2MQdU*RB>RQS$yx8mJr3?f_4Xj!LT&&F&M+JoM|U9I zr>aAZ1LA-01*Y`m|De;?wj{7h8PWhyVt5wOJ#t8GKQrXBrIymGp5M^7h{bDRY)oA~ zg$L0&=?ApyFHx=i(7(DRV=L8e;4Fy-xCBGkiLk2rQ}o;)BU`xs~H}3CfWlP4&dN^B>9kCtVZ>5rk2;yzFfFQa97(& z>d~-nI`!Y$pRN9dSz;=bt&k0nJVOYRwyzWnyKYkX$2aXrHS_Q|>lsENfcBHFQ}yep zsTVA#Ti{O^mB1t60CMh9mytxXRJ$upnNt}TdV!%wDZ#O?GD(&|3bF8HS!&0NrxCJk zQO%0;39K4Us4~)=^RLH^$Z9RQQ<(@|&FvF-2Da^~9jvAkwhD82VK&3Rh<;4KjhNf@ zowr9(UEp{8I!*^xM*_wprYN_ceHhJZUY)GWZ-7ItcKpwiYpWM>+*Yeaw@L_XoJ4T_ z8Ajc#z;h!jAFt=D#dSYTtZzuIph$GPX>>H&e@7N?MUIStc=y!=ZjSmTGVJYJFny8J zNq*Ogp`mEWYWS&gWS7#OeQDDprWHOYU0_XPZ~v$E+48zX*UnCJo7MbNDVk^7Dz|Nx zZBO?!DCGZZz;WvbWMhco?4Uo}1yn1ol*Syx8iJE#`aa{UiBg`+5885k%rrCrPU;z; z&EgSMje$}p_n!Gua)mP-E zYcM(@=#i;EviW6x?4R>q&8?=4U$YL;OpyoDgO$mWSsk6Yy#Gbqg7)byn~GL6 zThnL#eLiGIyI0!-uBv5VABuMC1(1&^XFkFGwyuL_n$V-hW}y#E;~5ik*=aDx3o|LI z@%P5Uuj2(DgdGZOT@F^zxIH?#{S6W+NuK+IwFRmTITk56`Iq1xOC4sUHnKryTV%Y? ziRki)gC;}Xzhf=F`X?2{p`7IJ`*!cb#_Z1lg4+Bl>t$Kn!&`u23bTLmgHx+RYyXVHWvS!iG|oehIMv3h=Qn)fj17`F zfGR}KLqDn+!m)7|lXXPtcI$Dv@3T|l@c*76E+Qy-gRY#CRRVZ+J{{+zUvUYkk=!UL zCz4wye@RB|#FrJ|%9>(Xm0KA>0XL#r1;@L#^`|*1n*?Z-v;)W&huWu3|F`@{m;7N% zkYj40Y4}Xn6r+KWG~s1eN@HI=BOms1F`hBX)sTV>)ONh=9bay$dbLpd9alm={L=`E<7 z^5SRO7s}^Ob;^(X)SeoI6B5d0{yXN~`*^eGTZ{pcOm}|N+HUH&noKi$(N|U7}v*hf?N%v0!{}5qxg!Z-6DSr`;cjxcS z#n;vInbNNo=jGHZjZUoi+$)0Hr1vhQO%Qh+U)ZAd4*=RwQ(C{Hxle!B16{x z(;Q-0yjkGOmwb@RtHV-58`I63_c;bHPy zg6V|7kE%k^Z5Jkf`)noz@>-Pxp(!u>#!7H2ge^NtWyTbLNtwA$w|oQ^?Q$KB@B$fj4M?(RYhEXCDP(`>LEc)CJVif#BCig>goL z^h8mq?d`2!qy0ScrY&#%VBtyl#9R@=*EXiF1MLN4--G6ai^`)>>P!GK7V+qSPpgH% z0}Jq+LD6a6E5(yPe&RgWTsy1z>Qv210m;m{U4b0)Rtuhg5<6s?Ssaj%&*1_?p>ab+W$XlHMtI!aO(HL`{=GryW^w z!h85e{S74XIn%cHu&(DYcSSE$;Tc9Xu4bYuP(IcG)G|s&SKHv7IY)J(sfoQMzNoYx zpxMv&qR5;cB^ZlzH}Zpg3IO?qVV+vRYWOAij>o!)oS7|=sD@9=7c`CM2NVor9V$Jp zr7C+P7w41?&;RI6?S|W6|E^N@s;xd(gZ;s!f>9*`B1ZIgeLLvqXFq6vkQJYR@D~i= zoX>;lV#O1s2iT~9=^s=6S8N=Tih|B}nYh(9lN3&y1Z1^fMDAi)zoVIU0;ZbCZXB47 z(DF>q+!VFVOm3)0?&7zw#@;2s_@Si7R)_^~Oq4Bz<;zgqQAErjy)8>_`~c*8t~o#I8@z&=!4gr&`*W7>D~t4#gO>Yu zz0egDfDEWf);*$hK%2Xz#`xLOmw#iD5xDh>56^z(S6@?}Uc^+gY!0pHobhT;U>W03?&89gZpE3t z8fs&zOULPVFD^7RP&NR(mi%bM=bif~ot$3|qaq&LVw9#*>lm$~T(V>NC8GB7xPOmo zb7^ER)%Bh?%Gj8=wq<|09==s!GE{EFPp&MZ@JvNbB`uR^GP&0N5^lPAVI}!3&ji%= zuPNV>kQ4-13eRMTGBRaR={L}U$vS#W9QBw?p$44HpmBuy^Rq99I*g7Z_Ok{>D^%Z8 z?89QG)*J_1#XnMjJdnW9(gnK<6k3^iNUP-)cPpwLuIw*)jrcV>_9DNIwzs3ipY?!y z7d}aFKX}Hq`{e2Ulco8R_xY4*!KKLz@Wu7&_55Y{3}KH2pH`9~cWm@xjp5~5t?X$= zt3ej${UPR+A){8!@d-Fpsq>0omAKGV|uTXZb*vt?^Cv#8PH{L+q@ zs)l2{ev`qT&j4fGw+J_bVHvdVEI3+Zd_y$Dy?0_y zTi)`90M)*|o4uOH$u)LFLLjT+)eF`yTPVwDfZS@uTcnHt{Wo<$$_IJ>IFu=9(aq1u z?4T_+^}pHPz|Up|s!DHJksA@z)2Aam-CnRB$d+2$ENJpMAO^q-_y7xcWF17*Q+*1A znJo>SE_S~4F^YNn#FN2K&zdyF0Cyvo0+Gi7{k7oMo12J>ql8_<#?!W-ZBzfP?U|#+ z;K(+Dt3`26foShfU4R9jbVaZbVr6tfZb;AxdM>AA8S>8u+PLk0u;RF9_r@x3Q|nz* z^OyERX2jQoK*CNwVaJ4&m#l_>x}A37K#B_)$h+j^rx^oWzP;!MZ7nIAjPwp33FA9< zI`w`c`;#q7A2--^+F*(=C!3DE!n^O=UH$I(dC<53&+kGf|L3d$UW)uBs{hUgkoda@ zo1g1=V5=7>0d7L!B!4hp(1(I* zmGJMZ02fzH017o5D?kO{1hN7Pv@Nbee@U!fzL{3*ndQ_j4M-x^xcZ(Mn9tB#m%ids zHsNvn;l;)f&OmQZ_qH~F;rhn!2@O?-tefo*ztG~!k|;RJ6i>!xs}baz9bBcZ9sJP| zxo%xgCV1wBIP3TA+V+wO+sVAYoU!2teMuOCJwY-&t3y-Wul#FNtUQSj zNIiizvFW3m{|X4F(9a76$7?4k2GR+RL`qJ{P%-D*l=3Yx%g=`9IY+);q=D4h)O7rG z4}+3*0^p$MQ|6YO^14}lbon4Jww@PqoqdyzcG@a56Ybda`Z&ZZtfx$H#J9-QroV?5 zSMHkw9okYy?9=_+K5uF=a>@KJ@^Yh#Gz`b@#qXt6xpEp*)6@J6emh=lZ~uhu(SsZ1 z*E`9fPc}NDH(GP4Mx9Epy|?<89j37jbwApPp7ZbaI1z8Z%ePf8e6HUH713k{Lpi01 zWxG%nYg$0*wUvm}IX|O3IQ1)WT<&@Kv`*XGfsu^Q;TP`%$Vol%>`f+u3TQ1mayA3z zS$_RCE?e`}afWsGOr6u5L)39ja{Z`%+ZZFvNXHVz|L#XC8bUmRsGWPQoO@xZFFn^4 zs}JrK$^6J$n+!0#Z&MVQd^2y1m$U_y;%<8T0C_?;p`3aCoT8FJUI!PZ*~3o$LhgY( zjl(KgB7#!0m!px6H&^?hFK>a?U(=GZ5vdDxcKQ+L^1NmgXjXUNzFa;GH|081})EvYwj> ztmd5EnAM!8B4UM<-8l#zHaG9Y1=_#7_AfN5D?u<167Ei4-5$T2w|neP@};wk%&a^c zQ1;OiwQB3@NM4gApIGTL<}fU|YRJU&v3C6Pd*Q71&!;0bi@5H!i3SX1A=)?5l^v+5CHf^6Bq|abGJy1v9|ocY&?z z)Z&t=}Y>o;j7Lc>wfJR&+&HIC!1g+R&pTs{WiA8KhwK zdXu@2Ztv3zxkjMk?YW(4pA+{xkHUZKcy2*3fG zQ0i5YchPxyiWGN>snGw)tN250~Xn3t*Rns4$0}8(%3GyJCx0RMNtbo(U?xY#Rd^jWu zG7Q=-+HN$oYaYSRkD#c6XFz*M)f*OcQ0e&>@h30>P8Jq@7G9IdiljG%w2=RJRgS39}x;JE&t zsDR%*@!Btu7O#H5qxusPFR?fotj%5*w{tqcY9B)5^wX_xZk~erWBg7=4axL9yvyGE zjqw+j&%T~aVP9lyRANHyNX6+AyxOIIU^}@drqJ{n>}ZXN1=K3Nj>-YcD#LDXa@ zhI$9yS>MyqV|Pj=x7fMCj<`DU7X+~>`T`CMKIV5R4Yclbp>s^BF4uUc(FD*elg67n z=CGPPeQZaU-3DXw?z5Nk@>cjmfdg9dQ?}kAgv?O>LRt+o3E|lbSyWWl3Mh#=J;=7L zVyuBx?Og|nvbACx32LfEsve8aZ8 z<Pb#Jw7xwKE@0Q#ViO+3`aj)pR7cZn1W@^0I$dKvyIFd_d_fG@>SYW#s zc%#zbkyEZ!8An=K%ZiXVWakA*!)mpkC>J zwyK0o1u-%V7Xq7GT)!y3i&zbozInSOwxW&-ybdD>NPSZ7PuI+#_yiKwWpG{&VeoS+ z$nTCSHa;*~qzqOtF)$#~Q&OwwajpQj<~W0~r}fU%_H=(b*Q|cT8WqRXy^1&2IbyYK zE}{XWkmsV5S)I`6ImoS-Ep`Ywf|T~1g}1pwdb1;FED`<=&ErIwWQ!vaR{e?3V;^|h z;}U8~-D!Vk=54;}gXdbIdp24$pn+$Po`g?ntvz}5`nI&^)@_m_=S)ia809Ghi2APl zSm`F1dsq9E>0!KE)Q-9_%Jd0A1Oj>pu;6W1Y-j{2wto@GZY)&HO=QqJ`NFrnQ6Jk} zH7ttD^<8Z}PVx@B)PiDDctL8~xY(Fo=i*QNEFlhW@az|tb#=|-2TsXo?mBxfvPH>l z;fVPRK=Ri)+;a-5=W0$1D#IYgZYCGSxUJcrl!YA*@%XDDf-}zOoiB><9C&+_?j@HG zxb$`>?Sr;UvDnIbJ(LQb_gKldAe(C;j%_W6iEQ{;T|V)VnaahZ?`)Y$$NFX}r$2r! z-8rasU60Y@6B7_r1IZj)Rm_N8%q_EzMy=4ZpR{pTe+;$9ny>Y2^{%Z~qU+9+0X~ek zRl}(ORR;^tG!$ZFSOLrlAHcARz;reF5HrW~@++(E>(tu()adzH@dVn6E0T=#Z|G+m zbB%7>htFj?^wquub96|FM05fX1-=hCJpPvT=~gHAD^(j`v_o%x5rUplh+Im9sZ{JAG##|F@r;lo z^QP5SQ1_porF*OjV5&+X>{#_O27A<(Saxg$ ztv#jepk*pKA~^r0J+aIsiwlp{CWt7C0ehuBBBgpXL0~3D_JSA zRI3Xco`_|DF{yJEd_}Z1sVx^(EQn8UUzAuc^J-ap_fK;QRncb2Mn>OF)TdC2MnWIDHS=JuBGG~ zBkX!n&ud*9->TcF1S=o6N$64E}2S+5YK4ZfVwvaT{g?qUluCO)4-E)EpoX%ZzqjovUk36Q{AUiGq!Qyt@TRA6_qHunc7=q>#x1%D?r+^?sIU6fiV* z;YvAsrVTeU9*9Oot=O)<8t!Z6t$_1f?*C;!An6IKpmkS0<(Pi@U-2h8I|XJW625OnCuHT+bm<5bC}_(8d0qFO#CCw=%XKz>wz zYiPxf_o2Sj)3o2wLX|-9e}EeBBhSSy!~0(SpAAInq5^4tFs95bs6xrjrBH|XAy?H? z#Ipa4jflHBls{zUW*m%RQvM}_18Trmd|~4Zv^=OE7SQXZseV5w%`%;87b=+l`x$Ox zr>og~C~|zPds|!ZJzfM0Vd~@0TpudH=8hfFjWj)~ViiRyfp2hHS03rQ zHrEc)+_iT?5!9oBiMV>Kkvn4hee64T3c4MQ-I6le-z$+36m+G_)ooUj#@b@1(Bi%W zA7LXk(*^{99@!fnYO${NDBtW?b=%uLe3`fS;+sED&jUlNMoqoHAH`i2E*lYWO#2OZ z-E@K?g>M36O}-cY({lrXo0C(<9d+lY$-eK+bg?}^SK9SL>j=Lx)j*^uLL=EWL;PdX zD`FJOJPiQF{QU-GX8ZAQ_1Vpi&ak2wrkp__4d{;$P=2O$f-i$oc$7*xh={*H3nl4> z#%wIOgSaUCIUi)k=qm0RZBf}%$@>%J{Y7rpc-Xt_-q?8O!Cviw@o>A732!5;;~vF| zu>`uU{yVeq2MWXU&gx9GL?Co^CP?Wc^5+q+)4`JrL5C>vE~Fkv$ND)kdg#P9;e&j4 z##+9Uu9gN$n&HEEi9(Q**+B>I(A#CwAeR-ks=gHWdpZ2N92cn2eVd{4G7xoi@%b;5 zFPw*NMgDgPk%|r>{u~Lf;(GB-?drh0ZaYS)+KfhzCsWZ{MFP)Cc`?bWUVGk0co>2D z)`2g_r<$uBAO)o~zC6QmKOPb9t0ulqzhh^lI3{dgiuc__C$4Po+i41<9S1rRrYTRW z6UH_3%9*EWKoy5T4-B8xnQDZcTYP6&4q~(2h5;Eb5J|_6bZ`56Cvkb6ABCPcA8@uz zrwjc7Iy2z>sb8Y8v*U5WYKicAPHv@70T*YE|7PCudtM%)8875cC zjJkh33W8SuDS;^y`Ky>VU#CO_ihsE1ehE^3u-%lf^3eKWe|(g?=AkrYXO2_oGIy-O zKo%ow4@OpF`etf{!~CTwJN2*{unS9n|CkmDZx}lt71RvBy+aH1I=ZIwKCI(k^xiH2L&FD{= za^X5-b&dZnqT7GCi))8p?;w;cd6oJriT5V4O2${{jheg)%Zm#?RVUH|hYo?)G$0Gp zNbNAuA6ot#UVT3~CDTa^!r8uJp*5iT?lgoUi1z`N?yPDWS z?#JCzNeoU084AT|mJ&-S%liiEPO<}76P=9Zb#o?s@gf{_f;kZri(5A|yIL7*rXf~` zO=}XXe5MU*G^v5b9dVX;!_4Mq*t~W*Flmz%XH8kChMc#9z(emY7)`n*?_Ia}EbL+1 zpUkxF2?1ueLK~*|`F+t|2dfv0Gs#l#o})c$(WrvmpNf ze{!>tup`=L@W?F|glIYe5mUS3@d$l;Q(sLQ@cG1B5<#t#daNh-!1Dj^I05hrNg-=h zI%zkpR9orO;};U@C#`OS^j*1h!(6?6eZ>3YSJm$k_nFXg9*ov&ZZcwkuI;~%eCz+t8MdkWd^@XcMfcW zg|Z3z2^Wb2t9`Fm72?avZCw%Nh>5oGa2xY)Q1KM&t=}tuq9X(iPI>$X_AZiUjXI8M z%K3jwA1%wb zF#^|l!(rSHhPSt7zq8d5;7NFkEu&?e5Bi%hU+$t#OUS2QlW$lz-VFxv;Om7I_*op{ zG7f$F+t_Ou5h-z+aZGym6hn<;z2|3WHlb1!gNd=o|CNv&U8N<&vg!6>h#bQwS^?2q zNgiXu)FgQ(gdPb?r+6cZ+_4Ry#8CtQM?MhL;)&7C0sNwuzDn%Z(%KP+Kpjy!oN=BVJiwsa@%-~=ChfMn z_=mOq&)QY#t}~}kp-pYrqrm&nJ#52#{+k$N#F!xaBkhp1fKA=OFM)@Re^sP$XiFF6 z=muhi?qH2mqquZ$2m%KGd=Pm|D}bhwJoK5ZKE zdk_<$-1`A33rvp#*u&v&0DcmJCsWnSs)|A+H*acy^LxcUg@dO$=8;)h3GP@jJ&-Py zI{PXkX;R32>JHkiZQo3OGe*xs5fMD|pCz0FjQ(BOQPlz9Xm@sXjk6F&6&BDT+;!&N zOTVE`=OOxu#m$M{}!kF4fHxcMT&dIS`ss7-C7tsTdke9T7Z5?EOTlu)s?SAY)81 zeKF`O(B$D&9f3V1E6wLh!d@pZO*>BR0GYDG<>)i{16%EN`qC{-ZGr2XksG)&4|EZJ zlA4cOZ$YIB#s6M6a*(@rcWJK4u>6fKO>NT(SIUQ-4~ z>hRl@@Z*Yu-zD#Vl7X766MZQJp!NFgLt-j=M4;K5q?)k@SUYuGiXtk(t_{RU7YagX%pQoQruieEW0UyVmoD>Tr;o;h*f41*pE= zOY;#|JZVNadUF%PEc?bHzrFSSN|2L^)v8@)$%f=6=-zS;>*kXX_Ca8=7FSC550Vfe zDIdE^sTLH8ylgzFXHGl~9)C(k%8kJ=Yy9~{!kD$B)?)JjAP1;DcgCX!qOrNHv{M>i7UZQXlT@h`RghRF? z#zK+FyM*b{!+%3M-tcd55#rJ`<+@!rDC{JTXd}7umS>E&5@)A1&+thKPg3Lh0#Rc5 zeT)EHP_geL*^NDjRf*{RHA$xenuJ0-qf-JIbNY z4slip#glEUJjO-sH$AG-@Ok`+tS;2$+^r9=Zd)BOeC~SOmY)tT7ULsNG?!X0nNSF1j>F1LiV>JH@^ilXNiH>O%RdDJIbB{qjVZVSUV$L1v zOC<7_FV9e0wm6$_Qf{Gn!@<(?Tuujen^oJ-q^_PT37*OoNsebUU2Ig-NX>kJBJkT+ z6P+sf?rZy_{^L^YHMVa&v16LVw|q0^onMiFB(ZfP-eAseveOo=;=-(g_6)0pkD@9 zZ1m?Z`5&peJ!(W!Y&`@4s}4DsC=8C0)66Hdt)fMT_Iy&UVi&)Mh-Fc**=r} zP3533FKXfx^D+2oWK{@dDqBZ{LnB6r^wqw^S7HiJ?D~$J55plO=4AV>S@qAHdIHX= z7)mNB-_4a5*iM`%q!=BSnCxa5edldhLvzH*%DA`rF4{Cb2jP!4MKDq$^j?N9FCBxe54CKypMxU$#Tgl8P#z%CK zJHBqgsEoW{{WUsD5uc=rT5Q_Y@^lI=)H%*?w9qUX*k>gY$)pe}ba_tG2;NOJt5z

NR-xx;?e{lJS9e7gOVPT%(yED5N^GAkJO86}$F3N=|KHiJxjx&vEN;xy=B^fG! zQyTsEVzvK1wp(3zs{QvT0UTDfUNH_uUWF2EcWt&VURRkKr==ZS&)}~ceyMt3*)K7$ z(;0KbJ@W&j`B}<|!1MfRtR=HWpTyDW>ITmRNv7=Jg0FU8@8>|I9*fKF1tR6L;0^?@ z2e15mg!+DI_x<@8(tauYmKr!6$2d9(&Lrty)w4RJmyU>Tn8;kPtpd7wX>+CqO#IDBY0ZCw*6l;J1hc+63BrBmP0HdW(`O zA-9%K>Sirhhw^SmyKz|ur)SM1wwEZ97%uq?;*JXTu{iP}qO#ioRk6Kg$??-tzSpb= zT^!NT*f3Bg;l{$vD-{`PyS1P7*QhvqujXDS>_8H+&o(<+uBq6^RE!RX9O4Eenny$f zxIfeSE_Y&acl4M1aW*^siy=A7cX~sr_6A$y?m&gbwV)9@_o?pOne5X1rZtdzJb4dK zvGlt&c8$i-zzVP6avWZIb)C60cqFsC2UW3<3j1_n%87HEO0F>%s? zV!6aA*1`Ri&{_Y}Vradi=R6 zeo@)<&a8qsVAV6;<3lGOI+#H-j~p;hH?Hl4V$7eL^N|$niM6L;2^Af( z^1~*gMOyJ)S|Vu;P@((%A24m3`2n>(zsw(0#Mrf5%CdbdIox9Lg|yeL7`Sx2y^#1R z<1Oxf#k4CuzK}%?2sQrSp>1+?+Z&m;9(K+w9r{#1!&a^f+&Ft$y}hv{PVl0URWHqd zdz-c)JW?_sZ@%4N-;LvVr8-;f5B7LDBlyT_Yvxk)kO+E77PvM@%z1Qb%$@&4D%1=w zi7)<5nkNmZy?i`+^OPw(d_pq{W>nI3;_75?FYqouDI)7W@y4-Nbnx?eHs|7`lds74 z&zj$sg8AwJ4CfZiu%%=^Mpx=E&=rLFSowRqMz0+gts@i`%-W}-FFDQ-={umUUZNSo z`N=^}Glay>_6h715lRGJ#QQ5~HPR3FM6Il32 zijr=Q02Mi}SEa<4LB^fs$>25{lxTvxkcg3KMwmhHI!C1LH0Dc1agQIAS>vOq5swJ| z_*HObM`TH9jP%~Mac5}UrN7zbrfBl__MXyQjPED0dsn&jZe!Xbq3&eLFZwLovjJ0= z-MTEs*OSo4;PB^{BVA{=-OyyzJoBMX8;{A*)f8&px1PP&4A=cy4T3_pBIZ1%@-tPf zu1xp3FR$Z#_M_~LtI@qs0aCuwJD>?D`@YM)P+jrojXXC?%Q9E0SD<_#(l&5UR z5)twBqZWb480m+n&hJ^%Ya(DZRc&6Nwk?U8PFI{m(C1dGLCLxg(?bokoa8W)q7~0#fqbt^qiLiYiYEHaONTc2nO*K7Cx0 zm}QwxGiy`RUjH55x3utr<1oXp9!9W5-`7yYNbliT3q{#A8JtH*4mkD4C7Lh7Y4Bji)t!b*K_0IB|7I- z$9`o@@`fF015#tFvL(@i6JiKa3P!*VaM2jW{7$iD9Y&!v)-8aQ3)zoEBq^2z!Td?8>Jr%88NB z`2x2F*os8&J489y3nb;!$7a)?%3sNSc+MXAoGL1kD(MG+@yeRTUhxlZ!I(7ncDTPF zc1d&M4yvbW57STrHW&3q)a|opYAEs5<#Pv8c3Rd0W*N4f)S+ZBs)gY$p8Dd9068B@~jacX&YJHXZAh{l5ceCB< zjBfgBaQR(zx_$ZV3q;uYa^qvQ+z{%&yOu59v7B~Os*&onGp(;SNY^`O&uBHGo)z%v zppbfXWFzD>6*rm_Poywd(X%{7P`h!244s2w0roZ|iZDB(>b&XxMji2|$CR__S4QXe z;yxgU)$f=t`m^Dj<0mI*K@+(LS-}$urc~R4RR6M(){OlzfS8EWp&P3B;lTD(7I?WG zAA$Y&d-Nzi~*DaW2E+ZZpYQQn=G5PzI%hB7L zH-miHRqL?zw)x}FkCejBhDv5sVe zMokt&`K=)*F{;e;W3HRvp~0h5_AVsG?pPTZKx1u$9f@yZ7Pl((B4@6Mx@y=-TA;RM z&Yb9E9D-+S#ZS`RxiPeA@iG7_@*+-lAa?clA)kfVm!fp|jxLMN)Z;5+w0iU0xZ`vs6>h-KvQF=)IpIw>(?aGXm{l1z53?w1^k?8N4R z=@x}12`x^?0T{cGHK~mDbN_NyaGP-}M8bud9@eV|p_8~G6r2T$L?v<}gMr8i@NEna zEP@XSL-9X&L|NK4Mpd9tTH>XkQl3FSPHWBU7?#Ck3V-#G-MB!aKFdG1?DYKObGnaZ zb?uPT>ZX$^+iTO~l7?_{Wcu}mn{P~{`0)xeVoTIJc+d=biK0BbmD>v=!G_MWn9idZ zegJuD#<5&h$HfQ-f=)3@Gl3b#C5@OiWb(AdtfOBuy9e$M5qtGz-~HO z@jXUBxY19 zfN5L*(VF^aJ_P|yAD_GYV^>9HDR~sTRj9qR{6zq}#U-I?ZZBg+<$5P`NxIOx;=*#l zJSLxEW9++~j*19nW?2`h|$SzrxX5c8!IwDE&Ei#&zyT9S?3B z{BL7Mx--_B78&W(PJ%7njY)oobRuWCBx2O;Xq$Ub^He(;|?R>&Fl>_O|Am_ z6k0%WD2zFbTs#tC@Z9N(n((rIYo)`oA%HV2fT3tECsL!WA?1N1w$5#juZ4P&QP7Gk zgJGCodOI>xmWGn#XW5F`{r58)h%6aU!ZQz?kv*p=SmG)@4j)kM0Y*^4^7&-$BSiz>#jAdAG%k=6lq`y6th(I*J8k>Qb^Xq%H&#?KY=^#oDM-k#D`` zJG0}H9eHwbkw$o}%g`3u~R zUppZr-0or4GrZz~?ofWqbR_EL!A;4tCMKd?^of@I+3OiY_N#$yEkKP848akqx`*z; zIbR0TX+u+X-)44f2zfrGd$g@Li({vHT(5q*8~FS5PlUVb?^_2bxlG8dl#)Wv)r8x5 z%^d#gye=xxzDGxFFU1{xi38lis*wxVV?POU$28P4QY+oj3M=0A^5rJJZ|_ z4K>?&4t2MVS7u$j^{n$2zdZg&SG763-Ggp2e{e1&lo$?OnV(ZhY#l*YL*WH=xEm_( zA#!c$dv90ZpWoYgR~#zo>J=DgVkaW`#xS67Hr@H_&k%9P7k9MbD=3TB!f=m^(=CZ; zz-LXQ(`5Z9I~fwz8-OyDj&Lc<9ktJ4mX!e0=q~g?tB<#@nxuKI9_iJd)CU)8+84z* zaPcLwXCuQb`RakT#E;@(Yqa@@9X-3 zc!3e{w~O^HzH+8f7j?=9<3H!_eqwUdQdfM^;x}^t(tV>OBLc{7Q;f!{YDQRHz1XkZQyL5`75u1*@mHM06T;|3Co*JOGwiM-ba;dR?ehdK9!rjk z-}>F^yc?WoN!r$bTFYS&7Wb4ywEU>$mG;l}d^9O+@~E3%lH!#iopo(qtHM~r-8@BN z@l$av7y&6`){=RwhY^v>mW>54*4(A~N7hO5g%tnpb>!Vl3Q;9$O|H+z($H!G$;c8_ z9-0!QU?EO#q#s-jrL|BiHyB?>Jb%Ra*3H98lvF_Y1-s^pz9`w)clqn|?In;5NE}D-qfJ~v)XGFytyBGz5 zuj*E{q+W*hEW~pOPG(04Qf;e05>+1uyc9sHr;y&RV4!PZN~33bKyhkPgc9QiR>1SD z->r7J0gzVzI;tBoZ*-+PX@naz7;DOSwO(~ED!slnQN9+M_4S(C{bQJl)QtPet9vU( zaEwXd`K3*||0r4i?1V(CJ9)FJ*K0nrSsiRNo0nz+ynG@s%64azt|DOXQ$Fl**Yz5S`Gvm-o_!j9aCy6Hqdc+%pbqB7#Jg& zI?6Co{Uuo?Ek9q}(=kTy|FQSpQB4KiyYLBwUIi5pX(9+BMNp7lR6r3BD@auYM5^@A z0|=r(L`o>qq=_`?y(vlwRge}SD4hU-gccylJ*e+{@BQcd{{6nSez3AK$>hx0v*(#- z@0l~R$AI!%n*7^tQ!9@WJj#L5X-uhoOtpII-2*wN=sUZ&o^fs!Q~HWJcs zjVt*<`}rqw#$#k$dbqPu}C4=~38sc(DkdD8V*XUnfD`u7=3S*UqG)VN&EasIs9 z)l#euRw8QNiK#|ZJCb$wOmNkSI@Bq?YeqeR*K^&I zKE72>Nf%erw>m8OnQDOD<6h4Cjx2Ndj7(DNv5+9|SE^p7q6fI$o!_~JE&B6r3e)!; zxMCz`F*@;es4e8zy%V&np!7lX&=H=ifM7D-$a&hTIZX03{H0O#b<59<558!S)AT`` zrpWxgg_~I@lOdEy$E>e0hY*DNvp$}Iwgjnf)ybn6f=!t&o(gkZvDScusJHJVUOoRVJj;CjjHX*5T531Nqipo-#HuhX zT93i=_TJbl6rIrA!DMs4OU|mZd0+ff0+?(%8>8hmhGR->m8v3o(FUl1Ozhz@ zw>dZLd0{r6&4cLOd%qeSzRG{vY%1N=v)Oj>Lp&Ypm{M?c{Z3JBr!Ws;s0j~$mcD)8 zzoC4QavP`cScdp5GvgDFc#5=~(`S7KQ*LU_yVV;Ki4RdSZ-ZQhjyXL!)twSD@GLn> z%_^QrQsHKAbS!JQi-{C8sd`mWB_RNU2QIBxGvX0%CdJ65fq`F+w z*62$xZyp80)%lI)TuiJZZ9HM|Ce84#7`!7TY>(Y^e@9kovd{aK*wucXW_y&Dpv+p2 z1-Csx@vDOL3bi)h^@21{+Q;qp2KsdBTP365EUHS?GSj7Vg_m3E?u}c)`o|vbVnJB9hH&M%Lpp z!;fEQ0oT`$e=rKt_kd$n?b02Lq@kB$w+o4iAC~MXB3bf^~{k! zUu5-L%H74ypDV?sCV7us60sK>+EIA7l4b%s9f0i$mGw^ck|;6tDR+M8_3nZ5{LJchhi!AITES`U zY$rdjM|ql%gs@5}JrQCV(qfUtZ{Ygs@2c1HO?DMfEltavI!ZH7z?~;zZ-43KQfn)P z0jR6&GJI5RU4H9zi*I~n{oa*hBU`lmC0-E1VYY?9?I8=qC4*a&JS|0Lvl?h|=G(}m z24ZEARh=Gd6|F`d?w5A;Jlh(2o+mtKLP~_*DK6|4^hREQho^puNWMIhEL;&ShYP5D z8qjZ(nCij^A!`YII`DlUHB=If{~?{r(^%m*yj`})pI4g69s)-bjcbF|yq~o9tM^8JTo&CJyc0<2kuzaSL6qrNW`)+lpr966P(D06T>#+Ep z-OoLOQ66(IMI42hhqIsaHo3xnzL6O?Brgb041mrqOv#QcyZ=#+&qy?biCXqhj44Yn zVsS%wV^n=FRDEyB6th3VS4j%|EzQw{5oOi1hR4o1J#WhlEUvFDF+4?G#t@<3D(Ysc zb-GF!>Cc+;Vc+nRS6+!1L`Z|HgYm=-^z9+aOH3gy!My3&9oy8TI&*;b{qRBLO9dh%p)`kUWIhI~aq?a4E%x}GnWHdEqf)jajjCrO)kI(>-0b&wy~ zLIfA};d&Y{r1jLXjv!v5(TAQU9-CEd8u-cI)#`$~P%GPMPgu(DVQNXag{`h-L>rDO^rh7D~LeH1*MuDUl{~UKQ8+mE7^Ija#eNDmc;?%%dUd&#CGOm$; zYT0pU5gk0R{eYr=c&x_$ty(Dl(%Q*O%T+0~rq3j9JMdL1>fTbH$GWLMTB5Jl%Bk4C zB3 zi<|VH4Ky`AAg>My(R+j>jxXF`&TbBC%T%U&f0@Lwi91%~@;2*@ry`k&sxssEC4#qt z<`eSqOdj2w46H?_s!yA0IhB&U_x{H{;2a#?)ZxZA*#yAUa6!tt!S(Y8Rm(av)-m6tSt-vb}q^(y(9eCIKyC=SA z_Slwwg}dGxL>>(yjh5O4P#)m@Ug?VpFsn-|NQSb73lP8Ak^&Rh>CZ?;>AI;onee9& z8%uI(cxbEVpH10fd~!=ucUgvF`-g;pYbJ4UGb^q zy2OmVD#y6MIr7~n;HqIHFLlc|HnPNTWbztfP})T(KzK0F!E)`=Y>mpwlkd`%7q|m8 zl09YiMVV~{oSrH5Z>27GGUDd~HDnG8W(V;Hy4ap2LkD~%mx*+?psib+T*k- zq;~&nrO_U&ND2BmkoVYM`O5^+gz4%XrnhIbX78Q2qV=c>Tf>RDG5I|_v@w9e;U$D+ zKk)TlL_6myTD_A@O4SATGxke=-?LeHbCGODPp{p=@x9-$M=qeW|EgTZXo5$Z#!4d% z3k~(u6OAXxi1)ut(-(!OZm@rr8fCs#FAlxdTyX5O3N*OU`E+sXY$>eQfxjbn<;H}W z{$WIWhEP4G9#oX`#hH3?KPN?XlgG>$M;^{sn|Gwp;;**9FN**Mp6(?sMyVOn4Y7?y z5_OV4^N81f?D2=9kM^V7VAg#F*40=FtgC2JK>Q+6cQGW`rfrK_+e9V+C7kvZ9F|lY zeAHmKC)gdQZ6>C+5H|%Vn*yU2GcudXuPE<6j#hz-DO0#_hi(zt)dkf^oa&pL)*0lj ze4G8zxZO+5R{OGenFTq%d5F8VfIUw@I_m;IIDG4Nd!~eVYWcRN$EpD=p#FRCwHmN0 z2~PxZ>ai!~hm1tcZnD4HXJ=GmfEb+&(V(ZxI@Sq>bY?dwdoxquLQHglQGEzZvAZI3 zx3`f7K~UG+w`u37mZnuRwA=&NIUi`Y4IUl$IZZs8u6?v=sW)vds!uBbqY1WJQk?DQ z2^e0yrDnHflrDGpu^*fP*b$q}mwvKiWj9A5KHf2cj@rmnn5wj58dZ z%IIWD1$VG65j^5)hFri9N^XyTT}XlFuY;k;O3PyWq7Gu%EpH6lqtLH5d(P^Og>b($ zA+s7S-U+&)f*^I0BlvxnPTB6uk}f`xf${j|gT;jQXECeb+h#%wbf)b(hhn+ph5yXa zpK>$>_vOC6c>C4VYomu!t4F+c{n6Mha8Du#6I-<>)1pa1oZaC3U^wPDG==y~q3d$L z)$sO~w||GXO0P3jB;K>VhMi*fWZVegsMZ*8qXda4p@KNDr0FAbbtP(W=`nsHaw+do zURwX0`+|UH+gNc$={3;5y~Niu>2VG9LCUHUCDgl6dbA<(sF@x_Ln0kO{WwI!8!fLZ zao4q+ST?w=?F?fT=9^!LZrghq8-usnUkLrBW5TM>+q6q~MwbplnNEKgM0T8D<8ToP zWZI;Q9Ocv-+vD~L(eVfOS--LrHLyBfze~aeQGWK|ZT9>k!>#a&p)QGCIRsh4cY_}F zm5|s)*ia%}l)S!f+?T!US`1hOB+>#D1PfZIAW$pflHeIW+4?!|-1g|CzU-(;e{lG9 z4JO45CE)HYoWcz%H2z}gf8mC9zXDTysi0Ea;&P@LzGoOI#TV~7e=+ksrRJ4@klO3~ zFE5%$OAvuu*%4~^Sj6cMtAG)2tknd>{rmKVI3rW($`a1X3r}S5DlQZF;MhE|1cupq z1A7#6wRjd7py#6CF-h>f>Ehen3SA~bWk0(O#AYJ)q_ze3vKXTAvp8@G6|(6~J^KjB z6!Z9&&sJ*la%#*i1B3KdUNEkA5|UH3a>?)2#fGycUzDsgdV5?rDe-%XzukR)rSfre zj}h#^DL}f5({batbK#FH7kGP`Ou0wt2_E!RZJotTwERxlQr*h)l5%r0hND$X+p*H0 z!95gU1cnP)Rx@soGsiJKIwm0K=5Ocm!iIVqJ&n@8vNNXG)UjKcrz1Qp__BBFZZEbDV>O0ozUaXRE6s@ydW15fpW&;>JM$cG{mVf>oMucql zn=4W$Y0B`hyY#SoslC0OoIy;^7(7US!8VBFU{>M|kim7*t={8jR7F6AhoHDmFya|Vok!gEJoTdtl1$t- zu{fyYo1_{<^|YZRT&s;BlOK2Y?%nqP8x|s@;g@UF_+_YeQ8yV+fBwZD@v}PjuQvXZrbg_&hmfRiw4`! zqi>IZe|GNDwdT7@m!DB0cVH$rxR{H0Y0o|dO^um2^Q8mJxtFks#W&^OGH=P3zVX+< zf|gW_8li+bBM_x(HB94J{RSUAJtQy7kUVbB%xu^M#?exyxvKmP-^SDJm~9T18*_-1 z77bM0O zN^-ZTF>Z1qc)ciQRw(I0-J%E8;6I`hKDeYn;BbD7C_j{+R zM|R+f(EcfpA$_|R%0Wxe>v?FYk%p^Fy`1IGsdN`tzRm0Hrmqw@T+U3ayV3IOX1o8K zoK?M#NZhd$QoG@w==0v^-AB6bFNSyIT0kQ*PFc!E#IUfiL>m|y;;giB$~@leIT#kI*6vV)~qL z##fcK3e-K8M1^cmn2DT#r>yB!nWfVcwgru&+D%Tv0?T^l0^5onTwiEDXocKH?Jx+P z3S(+&YMSjp2xOe*KlNCs#A)#R$Da*Gl3E%WsK)+N6Er-@yO%pvs{FZ>92E9X zYlFdlz6>w!O^u9K*wGy`qxD)HyV%Ygm?VES-hnPlj#zc<^VFa=VKZ#-`bcrx%v%e}2JyG!+vs2!TsP!3EDe+`HJ_ z&&7Np5^k&BOUMJ&egw2OtFg3|4;LorSzyy1=?I4~*}l%jwG__PK8chNdGuIt^4zwDM5ev!}rh=XjFYW2F=}ekbbo!t+=1g)d*USWQezOM^XZ(+`$f zD;hB<)%`n}fcJVOQSK(jaFVke3+BoSUGi~J+%eJtx9UJ2?TQ9mgEMIcs z6pPWxQ3VtpV{$`j{oI!CRaW6NWWM&AIxN7#;s*^iFC%r@t8d}Ht#}z4YH$JCT}&^^ zEstwnF>3!?H-29)H=zCfF`astdA=KH2iD?a%7cljv-P$n@l3*F-`PL+HEopk6mn9d zP$9<_orL+;z!oLc+bXrF*=_W?WsH^Ax>&SKdQ3{RNOh+S$RERR-LWxxXw}vl-rkz~ zsx91q34fc0ngy(P2h1b~q#E=!lM1u&ROI|x%JM=09#rP~p>Jt4=6Paje`$YEN9C_O z+n$AQFe2SbZC1_@f_&n2SgTcgwP}&sgmyq{tvp_TN%bmsCr)5ZDdD<#>$5n@gZRtn zx%t?WrySADY27JKH=C`jzCID8{}~?8insc+1u$PN4S5}8;Gi=@N;TYK~P(8}s{{T4&y+I433}%5$yq>ldoh@PWZ% z{kYitZ2i_}F4J!pXY0j|=%0O!TAP?_B~u>^I}mfwLeJU6#<&rTMi>@sdaIG2P*?)y z&DIl{l8Whp9_a^(r;zG2)TunwC=td~qB*L<#RXI;wzs?!T+BU^vfQXv`o<(6-t+nB z1r++b%XRQkX1Ev|w+&3~vLnT$NTmdY_Il!P)M9M@@n`B9ey7)C&b`)n;@}Z-)HIRe zY=Nw)G9SLKgoj8fTq3+l$o)QV*w*@>t@RG{NnxWk3=sl10Eu@u)h3opTWS3S@wE1Y zeC)}E<&SU5JL#hE!M$#T@Q-Z9$dMqht8Yu_OMeqf^;{s7>n_e4Ef74;G1ovsEeP3Kr0i5HFX0)LZhWx=&vtCl%`Oew*n#u#RH1ir-Y8gUwq z%ScJ-hcW{qv?qDF(z*$w$oT#H_RoPE~DV6r42p-d-KlH~60xI;oxR@PHnJ+Q) zRA0Xa+YEu*Jh3V$t1vdV;9m|V_IsP2935*Ox@^=kBE#*_YOssDS98zA0+~v#TpWit0tqTmHWbuR2k1}<*nzCBX|v{az)RO*EYm~{SHy}Az( z9s*wrf%j_Pt44W?<4k1Oxs6LNreM5Pc{Y5fm0j;yf!DS&%Dm--pD?qK66Y4<9?Rr5 z#+I3L6KP2U^JR>nRR4eamp@BO4vGn_vhb^SC;-5}8`ll4m1tRo*jvk71^@=6<{cfa zPvCwyYABQ%5)Uv@b3Kf2{xQ@NZ_GuF0H~pIrH3ym)Q6wtpiuyXGxZGx@}4sipn^!u zM}x!-p12yI;)1=2tp0ze>o2^5GP1P(yx2f@@Z zJsbdJkrY5S7=Ta(At^M$Q~*HR0w%uD0szY*m{?{30FE6nvBv=>cK;=gErSW{F#urt z4kkL70DvX|OeD|%0OTH$0=WkPOXQjb?=i;(-i^i|O!?D*67WrcvP|%W0#wun`>_IFVtr#kdveFac4o6NnTP|cYzzXqsj&%Xm#d{g7!ou`cg zwZtsxS-lJg<*W9TWQHIBCJ5~@0ZCO=Nr7XukVLSmkSL%NVCW?7@9*vI?eBEP0xVeK z#ug5PLQSu4Z4j~1z_G4<91g)n16G=f=EUpujs33I0QA?+dMM--K<&4-{R@1X#ZR9N z2k4=`|U81KBkzhK%`x#Jg zM17Jf{UR1DL4As5eisfv_fP;J0+(P6pl}0pVl;px@daFhnhW^42WIY+0KlL7Y{R>=+6#Hg!NmM5xaLKoTJsY@glYV1SER z5J;ea?ay}M!dc8QfKe2HKq2YdtYEVrbi;uYP|l4G5EK_AB+j0b5QKmlhOoDRccwaA zq=N&jdK7)|8y+pgr%uj6fo@>2(Ah&UcW><$nERC=Ee4?~rjWpeEx&%g0duw1_QBkh z-KJoGm z1UN?6TjT(I0G109w1Df#i3>dmp!!&U?-D`*hA=W=kO2UM#Hc}hvQUHCq3a@$!@>YM zG=%`}RS@QQ1weU+2xN3PK#QYnt+>;i2nP}9xU@yVy#i=A$cMPuFt$*DmL=#H?vT9k z8aRfbP!4fh`01XWsm-nR0}2HL_Sy8EUq_K+sbE zTAyfpRS5mmGO_jtv`fRELkpRT3X9Ux3ybn!4laVYrE13xh8D6GXFa+5uB9bPkLg}! z+sYAcH%CiC3fYR(X&{K&wlA6hP|{Z2x_Ja#bXrvM2V_KHDF86%G(@*Sfn%+0ZAD`s za2fFZAHIJ7`YoaOPB6fXh(|~Pz~e7%Z8gof5P%nru6qxDXpPQ2PUQ*!bP%W^kPBv} zSC50ph3<|QCA7fX7z?RRme>d~2z(Ga72F1GP01TOg6_`1r-HKJHs&vSKwu&A%bU~& z!1POS8#VG{9|6qX==xOn7T(6e27E4zN9GlqLXd3@jh{ajcC5hx-qnu6!j$&LS5AO( zVPVmSocF9;nPo+9>$8i#F9id9tVdTDz050>29gRt#e8XNWqnnI_*9bQ5uc9*;mZr& z9K7zG2Ni2!;rsTsHpI8D*|~9rg}Gr}TOgGkj>8L26j=cGatd>j-}$=Q8tW=+m4H`_ z9US2oT>~$qWrq}3B0uqm0Q5Apl3-r-_#gCc^adBQ#skt{+ZsQHWeISw@)Q=p3#m}+ zAbdHWk|(MP3$O6Ux3#suE0KeKW8wmv7~Fb$gkKH8r#CNB(@=6#9`#w07Zrdt|5Q-i@^fmR@(;ztndz~i{{Eq{Y0TdLf#QR$jg76t z|5p@muP)4CxBsGeqrEh{sJy%=yW}elL@{mGc2#!IJ_$~tCGYoVS8V@5@nqgWB!zk? zf8q~_`wF(gD2yb^zyO7^(^=U4hkJ)gNTC##^{*d8=;^y_@^A9R3?5;4pu5Z?261el~K$rEPRDnkb7tAuCahiu0Bzs zs^Ur}Mq8}jmud#HP|?R>j<~nv_uXKY)uspA;_z+BC*(ENeeENNo zt($p=(lKzvz?ha`3YYsCQeov1h4g}smL}`oK`aYpCZ@-6?1+Ka%Hb5crl-Z32b5m= zU=~IOX8zSq3I&YPz6@e?{}UNbVQsBR#Z%U`gd|n3>E10a4F=6`A@K;oMRUOvwu7u< zcD9-Q{Hogey2`@rY%qJN;E29gW@^Fgg-Tau7B>FIjl}5Kf;}P`%x;+cL&AsoOBBk7 zj5H<|W)1LECB}Ee^%xd(qpc>d!)Ihhj8#FRzKFLY!|D1=j}4+?&R7-kP6_kLcY z9GqqAppdpHhyGYN1xl{y{)get;_cnjR<9_~-O_JI7^cHfMm~;CUnYf9pyMBh{?YJu z*~cD`PH9O$K9+9%hlUA_1s^_ERu+6HsN4KM08Cu@^=pOr{{&!r>x(h~9e6<5Z37(^ z##4--$HsC)_u3r*06hWlMGu;DAc#*Q6nulYgT5P3(sz0p{BX_2_=c^%K5!mP(*uwQ z`#%>zz)z>Z7XVOaLI7&;9RmIXnN|2uv3!=b4aJ^=U|wbTc)+QblLGv%B3 z(EKNfLTREjarKYQh;uT?LXU;KN`Rtbzp&p92EsdUL1?0&U&5g5^jaE%R16nG!-S}K zn9f1IsJsf(pgLPlFBBGhU69?9jT>#|ACMokQnJ$6zq_{k{(j+Zfl_{beM7jnXK6*V zeSpK7H(OP6)#&uWl9)I>6fVdP4bfnyr_vPspAY||ga5(7|MZ3b5Ai|cc_@G5r|==? z{}Pnz8hzud7OY`u6Y>T3eC*Xf+5d`cUz7Q&j8z^_tBOBz3yRf`8T2oOuFWM+MJ5IsW0F zKG4CfZ}w9?rvgjS7@LCyo0{En>KUvvuAT&=G>WzCWXS%fI_|<7<#a6lQ@^gz{}USC z>PZQxXAK(t6`JO49=QGm?wY1a@Z76s6_^dIa}LVJ4g7~WS+xa2--Zh5z5J(0ZDwyU zqo7#xT#|Y7nLkQ~!UaFSZq?`0E%K88@=vb&^kyBHq{6)`IekLav>8edi|qtP&DV!A zP>wqc8oOn6E7j)T6g*2FxnKgDpHUk2UnF>W6JM+RQ<8>|>o|CXC(S?WIYtM^?)kZW zLLDNZB&Sb#@?R}{riL$)4qoVz0-ScMl&8z|D|{@2hQIEx`_*_RD3$pA zbaN)$hbBC0K;tS&%FLSKqJnJ)yzMjRoVCf4}fy zg{Cj!z6p8mmQ8ioW(WoesB45z2~|gYX*9HC+pe<>8kBD=(s<`p@?)gglXbHN(H|g6 zx3gJ+h~6C+sxFzu!&WAAy8m0c*(L7Uuc>MJOn)Jx$L^Ef!geq+)v+#{8W6IG{PorK z$B50^_{jV-^&d-i)1Eux8TnG=jB`n+u`yfs5AOu+z%!~U5mPprBow~PP}y;|+3Vpq z>tc(ie|6!ibIfPDt&Q)cNa_hF=&;m!)0=JM+M2g_${IRpr)>7$cum-F(r^*K<80O% z)&>#w$Z8(c<*5|Mq6%$$@ruGM}eWT(!AmwRNdjTdq`!_IA{ zd`H?Lb#1(3fnC|Lqq3AzX0Y_HdROVqb_IX2YR2g^993`99$Ml{!qiOLcr|QwdM`I# zmHJ_Me95wkf31Gqtlls?+NS!ldg78TsRywm*YqH$8a8-n1Hny_Py1Uu2c)V!*{`|aMi5y;7b!7ay!1ESV ze-`BTvz9mM=r7KdeB0Un$SFs;kqCZlbalnl{gA`L;pBr$yR#qEEOK~Bs}8%3p5OPg z{@hV>=A@vjIdz!n=Yr)YM?%d^3%UMuI8@t~DmNK2S#X=?X_#xE3Rn?%MCUj9VmUC$ z+g@>gECRJvV%JbtIi0(`(eMnte!j!E!Lj6SpsuUp#QKMh=5bpooz$vK^v;-hj=IWV=(u2l{DXh6wmi6R%x&vw}-pks&hpozJoN-@ZQ7Xwe z@FS_D+MAf4_QqqqLruQg69)Fc)PJPu%uXf!JkvE){-XJR5#q*&$?v-^U(wfy;@P;Y zSZDQumEhp%J-#lX zes<54$!&3eL0o?b8S90Ss(6uB_a1AC^U|J{?XII#yW5-Y8HG>U@4)?gy^x5@=)sPn z4A`!9kzBX!{)hdFVq)R&i>dg(J!pgRn9nilmk(0}0(N?i-t@y(k!9l!UKW@9wQJ?2@RdEM}A9RlI z#aHcD=bz^ET-=v)@k5#Sxe=@t(J@L(sI3apeQXgi@*g2uP*IIu*6?94*XR6G1;1#p zu}6_V$8$607tCXnpCBEP{zVNEVtMPvm`XkW+VvD>RX01IADxKpTL@ot!)Z^hannWL z_#6|p1LcI?B!(-!obj4>A36I<+1y!nfcWq~mafHB-jx&mAfm{z0~s9YQe*dTFjZ^tT;AR=-+0h#a@f5%A12kC`%!>(vzA zso*=58V3=`VYw#&dq&9XwQkXqU%A!b!AFRn^(tQOknd3A7&{h>>tyjr?_P~7KsQHbT zf*q-|bX?GVz_!W8+I+~G!D-r4Op=#0F`|SvVKtOhPwbS&+hkbtQKfV!%eJX0bxY8w z8D^;Esz0UrH5!kpnNzsmTym&sv!u`;)2BAOx3tGHn2{H?UJ)-K9+X}_r0(!Uyydn? zwZpPGLyPAff8)l`UKg(DUT=w@n`=Q@Ye9~&0i`#q4`#b@;w`FAeLU>g_*Fhjm(hvr zK$1QONM$WX@r^0JnOtQ;eGix=M=1>rizEwRi@UTfhvixpzBZdp*cOFGT|#|Vaw=P! z?M(Gj96?`4C%RSg%;!lDq5I~uc1n={I&}#Tgw3^N+-dT!m2ZX6pZ1k(?g>OryCFSZ z_JpArmGPxVN5^tG#_^sPA$6w$_%`;*3qC=-{iY`$(A=zw? zbw21*PtKS8_+&>Px0xLHIl3ejp|7cVPt`eJDSh<1z2X)xT=AYG4Hl~$(6g;QO)hZB z7|0pyJA7uTy`O9|%o_(oE@@9xXZKXMZ^F;`ZA9hIQI_N09*Rz%6YYvArIFo#^vLW(y2WmYu5& zvOAv)j3p-m7(HxDDYH5l6pu_NL2OtAl@(4lCJ`Sf47rI~7Z~XZ2c6bCXwNs8kSqF`v@_)?rALbbY?1y}IRNW9R7g?GOKT1UE9V92Fn` z`4SpX*1Bekrww{`b$ay*KjaYWx0^y=9JmD>Jen=e?t4Tki`g!@8VUALdivT_+~J58 z0)n`P&e6ya!CV+R*SW|_ZYem-j&IRb6sPBgyByn8KTo-D^MHLLFa%-$Wafj8))j+f zZXe1WtvE$zzE$@grMGD|osyg;UfE6C70%Trv*vbc3fiXV+e&NM0!~>46^UM5WuT96 zpw#YF!mIYz6Mw)y!*>79Ulf_KQAL>Dl`fykt(X*P;$KeI@qRT8Q4G{&{jQHjlGe|c zSq_a0DAim>3!QTn8dxMc-wX*@-zcS}X56adMNRo9Vkzu4RHUGX$qKXQXyAosHjdpt zyxUDF#8Yy6KEZK6+krxZ5snVoLTVN9*7KaAH2$~T5Bp&6p)#uIj}vm+UgJ@k6kTg| zLg#z!Q^_RDoD9zjgo#Vw1@E6cPPYV}V3oxGs@F;@SpC6`zgEW86Uy2YvtHh!tA_R3 zOl;VCkeq)hnsq|64u<8+M7WJ+=%L4uU=XT0*lJc6^9sXO8f=+Ydfrb|vVW2DUO>96 z_f}9P{-Ib~EFD@=NS* z65@9p>aL{%Q~Pz5(E*PT?=S6#2y72n%c>)*%lzl;#y`rbCN`|Re@z4SeDR=2tV@!Wa$h|A*ilb4{zS@?7Dlp;Ll9{It%;cC+H z8GkFA;Bz#_7hBK5L*4r5%0sIAcGj#WEjf$7nD!)vk*yO^THMxSzZf&QU4@$=td&y0m|t3cd;i2Ee`Y6*gCykz-pG(I-( z+`^*Uh>44$W@wx}a_n6%BA3+T>u8${^I)!I*a1PD!Q(G6bM7q>(oIRk_di%5l8y>G z1$Vi#>De7*M8r901-siDy!U>u(|3zeP*}tJt-*~`M3eAzcaL~scfO34ioi;^=wk;z zWMXMTr*6esXU#VlFUqWB+*AP>G1lk#^{+RpC^|`#qOS)o@Wb`Ds zD`Jau)`2Pck!XB!xWHP$?5Yi^WR|1J9y7Jbs=ieR*(raY(U7Qqo7f>ip_=bEG5|}m zQinF1+P3Hr`^6~c^M)lV@~w(pXMx3(hYYS#G4MuvI>Lpu4%N=1Hn8Ax(Qbt7 zlBko)*bcW5Q#*kXQ#E|vsAF*|>Z;>n{jWcy;0qZnBSO>_JYF^ljiTH z3-8pD@-9VB!mn(7h$j~*LfHG|y|3~=>=L+^O?YFVLHMbrw=r+U*u_KG3Uijd7fB`WIj!=6^B+Jikc z*+rE5*4=m7enZ9ME82n8JON{U^C`ui)^(**#^*f#j4KUR{KrW9re7PaDrCao_YI1{%R#T9A;-(RV4l|Ziodz2f&`WkXyqYaMo>xb3 z!`e-Cq7gRkX#sQDz1O$x8vag}DT9k1TL1Kx)&NZ_jKj24!{xeA59=%FR?`Iz)1ivM zExVK-JD`6X?IqVMI04GHzu0g%7L<-hN(5Em+3p^JZ^lb-Lt(fVQ*wxmr<93;hY~mJ z7O`$T1rSWGPHo{mRlm+WT8U=aGPcu?hb|MqlbbeA?b)MSS~V81e_RD<$L{E8@#&11?A98Lz;l`IrEOlUUP4AwyHlDyJ!vh+B z-DD(#+Pys1qImvNwMiw}_YqEtvNOUa*t^&jKqHF!_VG?`LM( zmZI0Jl>W@!)}8@d6?4?8JQoo5)$p1gksSxO#A#&{!)1A~QJ5ckN2@hu+N%*Q~3V19jux9V}rePXFtP=7ZH3d`uo7nc*?sK={7G^`wx zsbM$Yc@9+csmNQq_Ri9tMcI<1h{pM+mpVu?Ew>3JR=b?d^yhOfrR|z5Cd8nd()VBSqOhuUjBrXZc z(|OCR9;n8VY2D?7;|6Uhi`_x@h+k8fU1gjv`8)*TAVsW67~YxS^dHGqfy`o#YEW-s@qzoX#E%Bb_68=%bFUGL|o@ z-wizx6q43o)gqzHD;Txrp0mQP@Rq!;V4_@Bk<7k_jVLsep^~o$ zQF)HKNI2N5x@TStX_9Lc(JEi;L_R}&rZaUB+(FYYH*$B~T5ckO^{4?F-Jsl#fBDUs zlj^{%#%sLCZO=&lhn3dA+NBk-O7FMcV>=TdMNFwN6?9une3w?2Cw{z6tm zG*y{2_O9`K@XUlPGMjlK+4ro^xzUU2D+|73QNE*fx`7{ip9%cY+(tL3x$Oi`L6$$} zcjuZ_2KJ{^s)>P>YMv3B)3iu6sKl*Vt7$K=r{fg|bP&vbw5^Rz8JQV|yG}pwx75A& zDRT4D7%?p~2qb!UH2iQivMP)?l)zZHGgf?lf{>C?B`^I}_5R|CF#Q1E+r^2_C3@cU zkqgd)_hahqhaO#^+=;$9p>mhfkbB31z~)r$RGX&U@Z)%ZqAhj&cPH1MMk5d2nDQDY z;WeOSyKzc>H>Dva(jCVi8)e8S%hNgvtu1*m7Y$ce@w1I@QwGU09#!rpe(a>IaNL z_o2<2Ct!B1lw#71^4=bm&jaYjw_~C-^woT|h%L^p8zV2E#)wHZ$^5f%W^@y7Sa1{% z_MI>NN!sXuxrm9VoxhXN(k$?0>EC(|3M_vtu+&ws@rR^RjaXIjmCAT1#=yZ1b-Kvf z;S}F^Bg(`8aA}DBo-RU$lAf}KFgzL{xp!OU9{%j!xH0-NIOI#d;fWo!pGg>qs^6=7 zjo-^Q0dHs1tb>sNf9{%ZK*bl@#6J)b`@ad?4MO1gULjz+W1y;#;k!$$85 zLsT?0%!PsF;Y4ltIlpX+t0(&KvMNt6!ENZ&Oyof2T( zwXV*iKFEDKugQcC*rgFTSH);0$8bB)S2=c@ykem4lW89P;Y&OfXrO#?s7^%IxLj|HtSs|KjBAAc3*@p!HycmiJ*V~V22zD7wwc^yh}1Q=?1qcfWiMT(T2MV6@uAIe%seqd0Qj z(`WxEX9JI^*CV|v@S^F(KNNwKP3d_TX_&-%Dm<*u&3)0O8sJ)mx9qF$>y{q#;CPv# zZ?iej-LbzrW4w8$ao;F1Z<%rRhYl6YkzYlyI>&(bo;2#j9<$o#m!n}i`lq7E^I85z z57N%y-94c`I<2J-$<*DL;#r4rhxxb2#PajO(hQ%6t`rZw)cccO}g9v?u{>nS}ni*H7xo^DjoczQo`)c#j&%!@(be1 zuf-}@q9=KpoV0niPOl1AsJ5wTs=MGZ%=9PXo21C7_@D@U%g6T~YxIsYC-Gs;``-K4 z`pX>#zj0is(0S_@ak2)AYG*J!ahQ>&_Q12_0vHm){(wD}_HtPDztSayoA7s1~oO3I&U{d49TW;yt3k3A~Zi zbi1rd)BkNkTdMneUtak+zTpS@QkQyMY1Se^V@GJvrDZ?(Bt)ZF(jRogS|F`>l&9fB3p)S?ll7gi%fsVdtLLKQ9tO) z^|1czh@C{EGv|`?&Vrun+T-U3CV@tL=z0&{h0*Q+$B~ume|;`_=t}=|73@tmh|!SN zUm(5lf%Mj$WjEc#<5|)B(fzie>d*-1SlsCzG-94lUqu-LhMq$bNq243W*^>w3j~s3 z^AuyE`h~}V7J^h?Yg1=pgBTb3&uiF;1aGYliu~}uE$^X&ms@#mq{<1{sgz|I!|zj< zTlS#)^p~{lh!U70ZjG|e*Upync32Jh1Cf1;8=ex!GyI3MS)luGrZ`Htg7R)4);$hp zY7)O<`xJMll!*hPSJoMVS)&G}ls?$nkexW@IG(yZZJ-|&8SBu|`Bfe+y7y2GHmvmY z?n9|VdRfzII8J`>Wn%Y%UL=4n$LZs!^!vv(j!6_TLCPc5< zxjz%0GmqFeESnr&oILl(eWYd|TimZe*~VY(Z*2JWiZ-yaY*JQ-Wi0EeGcQ&w)>Oxy zr&_Leii{Ae7!HyfyDPJ|%t&e0(t96NF*ix9-z}h?J4QR>#yv7n_0-`mgwL#6k2?t})W&bx8&v6mtDfLfXx@9XR5*^!cK z(h-{KRIO&Wcdxd?87O)u4$I5y_fC$O2ma1-M{qNvZ~a^`d?-w>HsaB_@?5-5;C)A%LKVG8~y^#il>QI9xI^2gqx8J+2eo5B0P21*3;LG)lH`o(= zYyzwOht>#XBA&f^koN=gD$*;5qHY{p)CLb4kFrgFAu z$CV2x3+v3(^zlY@B*UwzNZb|ssk&>ZJafqP;aclFdnc+7 z(fYw;%5#yDo%(>d+bm(^V+!F2a$-jRzCk!9sXc=13hp)Eq^@f{7{URf3i z^V#u1N8$EM4O8R;KID!>m`07sTxwi~By3&Z<0AGXrBZV#gJ&NZ@ODe7Tzjdjx&p#=GB=D}|6FU|a? z8!9TpEg@aWfn+5iCmaWwRgr6@wx6XK?CJb7tgL6-|Fm8fZQK8NR2=z)kX|e9_L`@o zMu1-=#Opky#R2vMz@67=H5%W^FXk_b5og_UIe#2=f$kvqB`n$~9aH zc%cqen(@#yz9(z9HTGryRtD~#x9OOtLSG}x$=koycyuZ;Z})WJNh|OdlmTOn!{kQI zv$JE*U%hDH*3bnT1ts<2*9wg)|=ue+so&|e~n`}zMFDQ?E1+KKwUl25<>OYZsq zde{GrhH&=#7aUn5Tp=;CrSIHk8Ga-u*sP6qK~(BIwYb7<&vJ!iTq_DuG#BYYwLgf9 z!hgbv?2+SiM!>@E{&V`p`?v$gpxni5C4;!Hm*+ZbJRmQ@*MS_ zLpY%CJxq%aXJ3Ys2l9`-`YxcGOnPnUFrGC-1~_tIS$#86Y<6F^mimWzJW-4(U+E^_ zX#sb%Kto1{`GB)e{^?IvyP3ap)z2IoJ-^PdppWCeUU=|>s~Z#-?@#(d<>ll*dh)R{ z?AspCs`>dhRQPT*imx6|Ie9$(GMr3N+SpSiru!qx{D^yqX6CF#qy37yzrGGrQiN{$ z!+XTXVh?v%^Ef?*p9~eyT%3ZB9-3c#_HQn!+1h*S37O$(eO@L~lH=jdk*SmAcewVd z3u$&K@T5akFI4)dmY+Br$*5E#NIvx?=c+oLH%B4|sWc>H74cblx4go4r6+s-(Fr|h z;6PUo3URN8d)z<&A9lB$5hG#vAIy%?=BXMwa!wx*ip~i>NoQKx#%?6KH+*pT7G&XU7dt>b7ndHmRaivjXc9nictKog4>4^N2Q%B);U9- zS$9xhK>@k=yYAC_z3w6Xd5coRocW8HT0D7>U_1XTq}n|htA}ORTA)3_NMJnYr}0Tz zC(~I$#rE3p`sh1u>WEYTw1S{hAFrm^(=2~5s?NpeK>1?yguDPbaFcFzq{~LYr=T`0 zbi@_fqxU;YJRjykV&KoM)>>G5>FfVbP7)^x4V}eb3sI1&vn?O3<= zs8Iv^R(^H$V4Wx1pJbI$?yYVFx1zjL&ia}c@mWSE=*l6qoWPON`AE@?85k)k{2YXE zK4d#$%TOj}HE#G?c7o);K|WLj>*YFWr`yWvA7=ncSWl%cS>nHE>SAQVcif5irzD#XQ0D=vrz;b#G`xS49uOIU>#zmmIbP#;_JjENQ_rjX9mDw zAAuf}20q+jD?y6h>BwL}T>^6zen{+hq@*rpN}?1L-6%neJZDIg%c|XjZ8AwNdIxjB z&Q%_4AZ912*Lt(r^6;*4mLHPpJx~TAS5>3JzingWC@yK>N{~N~? zL0lb71{rw-XDm*N)Xov(iun`^UJpTSw zBLjt@QHYaZLk15zXA1y!99gbDpUy)XfPXimk(h90MV@9*K;#)^w>2ki7)T#B*eG*OfO|cA-B+REfexSN;-Pdox?2Y+XUlt6^U7V#!6!vQQ(MBmeOf5 zOM=EeJmF_y0;Ygh5pTINRYtL&Dw17I>Dj3{TpuKDeEff|<*_HMVy^qy|Iya@QrYeb zE`PH7_+J;UO-j^aR<-QT!!kSa>>A3`&+4MLO#*B(0#qqaDx*Hd&iQ-Z>s5cRd;z`; zLsle#4DHp9#!}$v`&s;LrjVgH3FRgh9xcOE+uLJ7foQKoevxzSX%KK={?s|vz`@8l zwYc~@81M*}HoyNnd~e=j5^jBL0Kl-Z8-{`$&VyA0$^`+#Lrj2n6U>xi5 zSv3qlwQjgbv4_qM`vG1y091LvWq>H{d+F4@$|Wb9;Z9TNGcrniOFycN0v2~x155^> z3)Rz0s@Fzq$63h-;FCMav>Jj|UM06Zlsko9R+o8s;O>}v!}o+ezezm0y!S2qK%8X{ zDJ;W?>H{RaB;CZaH*SF_4# za^s~Do4|iPhal-L-uv$^_Kej9Q|=ac)J6Y#R@WG-6kAfkjplOW=A_*SMyEy0>ZJ8! zs**qhJED;arbHbvQV3;X!lv8ks^or`x9-L&iaJ?F^lO~m=J@sP&e&pXL^{=#GRpn2 zz(Y3xcaxh{J5|+;o0afJA|R}}qG*E?aA!Sz2ZrNlmoB5Kqshblz4@{I77<^Zn>J9b5xzL}xe^f!>-4=tAa-N(eeHERIota5}#%K&@u;Eoq z1wZnWAcsB6Bf&e>dBfx%`hz1!V+2)late;STgL+=ubQeS z03FR$1Xqp*7j?#pqgx0a;m?Q^1K;l2Pnevmsk%A`ME9&w6yChgX^3V^0%W%CiyWEG z_DSQDCXzxy+s-OB8uiuOam(zERO77O4EXqYV6{1Y zNb}`r`sj$*^Z^&3=5nIz7H3!dxlIJaanGEU^axA%pkzZfnsk#|_vC=bO z!8?&yMg3V(#QJwv=*GJ=J2$5dm&^0hf|gAj>QQk2USm(6f*&-}!}wsu*NXY!5jyR7 zILca zFKn=YUQeHlg@FIj4{(47FQ}(j0g%`Kl6HlJvfN&2&3*f*?#!j_g?IimwnG^ywUr!*Hw};V zX4aZ41T+|2-L(tu4fRon@j;YBjbAThU{Rs$Yd+Di^EBAEljpCX{CoH|`=8KZyaL^P zE7Y^u6M0r@dhrGtd8zd7bluaG5?xF$=iWlmsdqvip|o9By(IN;Htus=7LdAEKqSmgST;R6henTtm+RsexY9efz0O-4x-+S#Vk*&v>0E~7B=P=Wzj7eVlN&AU~@l~_DMaSj+ zd}>6oF@ml0xEp;L#0c#yM0Sr_k_T~Z)RehQn}-+MGc-{})H~8nAMlZ5{dIEnnbM`i zgGA~hF{jHHGz;ffz*v<(yXrgF?!peAO(;VYcXhe%1m$inzwf09E>)6qj zvKD*}!M7yJGPOZ0&y3w?srR$h_#$HvC!#Xc2{C|(1X9eR=5-K2@Be8$Z-bB7IV-0h z%cs{lv&$Bk38KZKqPbQIu4W$yL9Y;+7s543vbPu`QQ_SQ&$@!#uLR}PvsdF=`dO`u z^G9^Ao3rTnz<bL*d@XBVaK znIgk~4UbN8iFU8(L*6esYXZ9J`SDrT!S)m&_wJd@O+?43?MQI2nL?=*d)~pa*-CZC zvzM`O=`|zd4Xkh6LA6BO9a~)1`KPQ9TOAnJ_=7-vKE?7H_H7_Nmhk4JUc*nWlkoII zcyCk9=w^wi_N2P6{%G;nT)4s6-ul=Ww7gM<0JP&+WE=uZW>6!B%rEn#nZO=AHrq+> zGlL(lb5>92n}sYBwz^nu*d%Rjk#(l!H{J{}!hX6+5UL$qAt{Xw*-2-ps*PfO7us?* zy-A8qaScq3`;SamipEe|)**&!K|ZbPUi`kvn?Zac7a1HKNPanYamL@*X@3?_Ow$(1 zBoct!D-2?zAYA{ljmcriiwqNfONK$eT_Gef4@nG7`!*5{L;-#$_KoM}(q85kXUluD z%pS5sAI$>KyawwPXLkCT}8DemOb$7ofyp3}#3;YJYl8hPkj9g62xv=2kVhPhB< zEV2gF3^>B|=ynSpv-z|KQ}P!fDcX0 zoPG5|)1*NDna;banx0q2dV0a9X(pL!q++4{u+!v>RcNu&40tr|+En1zJm83LV7%3hmr5wQ|qfvm>?F8_sQdHLq>8UVL3<8w2MGxRmK-ZI%JR85#^Q) z7=0x!R*Vz^hjilWB{^ysf`W=0Z+B{7E^k+512D;v);UNxXUay(h;-%>lRc>C=Bm%v zF)fr-Bfi?%M}0p;I4|;`SWa*EAro~-UAsqNS*@YV%_Acgh(Bnbw<0|FntHJ)6KLYu zS%KH=vAt&TvDIJG{j}c_pPzdt%!lotl)Ue>p6$Qlko}PggO)J3=9|9^(tooWxylSo zx{QDsFrQ3)lWzVlL8C4=EJSvdJ0 z72lyLpOGUOeEf!0SY%k_oUL#)}ax04ut~;rCA@w#*3pLMTB`T!+L@IyVu@d+A30_kJx= z&CQ4&aV|IN91O)A_--)kKixp~9GR74R|IeZ=i3jg(fE_^LF(nI@_WNf;It9qaSvabPw$=W+fRvi}N6J=G4q&^~jUFScs z`J4%Owd{m*zTd-wq)uQZ;Sv501J7=54TNmmZ+46Hzot^RLWld4ub1{jM;=0X**3Ss zEgByI@eUN&C0g}0LOgG8a&=C4f50C-SIcR1*%azX`%CKFlPOVVkM`5Qg> z);P(!Y4PT@lWkN%b)R^swWG9i^eP_e`5U+Ahw=sZh?! zy`l4b%A?{Qi3ojB%+MrbiBqn(tdY{dtdLgHpkncoRTRcniteNb++HUzQ5{HDCsr;hozra?vwQyfOjhak?_b6@$nq0 z7wdqCuDb&~dJQ^$fKVAUixylzu zn{Y#xT`JUhnhsfArbCAMi{4j2CK^>B22FbM+kPR`9Aqs3sM^}#l;!jeHxWa$^~Nv* zp%tF&P?nxn;76(;y9`85o2{9Gtfhxj3U)xbMCX3ZrzEHLVAAATz?|Xvto^Lsr?U1L z(?1PVAQceWyfZA|Z2AvL0Y{(*&*fC5N#fPmb-4>6U((e{1{85l&2lYBQ(o@Q?X3;c zL=bgSMcp3u&VPg=3HmlZ2XM|)$kg1=#kj2|Uw8v}6Y%XLeQ3_SpyW>L+24^n8pLU) z)q8xxs^3G!X1b#-C_d%1+q4M+WO;dH?CE;4E<$asMM-egF#3|vf$+*Y{-?QV8lXA^ zt1nKIctuz~kH#69npDZ$4khZoi`ougc#^VbSZkAi%?GJ;t6Yx zw7a%JW}uEKcKY%+Y2osn80Yv0V`6H^seAoambuGch+ReufcW9>w+CE;2s{9hpiOQG3% z6$hkGoeM1mz=u6O!%o-a9gl@Z<*&v)j_jRJzfmG2^xLz91`ki}vq_=CPR!H%rp8gP z@(bnXjKKGswtraW*=Ic%Mwasszxstob8(}CO!zfm9~AZ`2Hn(eZxbNXeGiZ!J+k@g zt#aG;xK9&k(E1gL^MlGZ?ct(-n{S_V5We>5HiIsUUEK(MhOhSECY7}vecx#>0rJPd z;dGB+S7_L+Jn=s^onc~_2rj9+u%2@;3H&pbl+561_Bl(8YpED>hJBBp%t|auSCGDV zeuQgu%c}cPdM*1I^Nn13CtgkhnHMPN z|K{>XV6UI%$7xTqyeK2GB2j8pV? ze#pq8ReMuBqC=1zK#z}A#+Q08+|$I#IPEY1Y%qT3N$*@dhEQBV)%WNd=Ldc+3zGgd zn|A;gx%H39*<(<@+;cR43n(mmPXuiNA<^Dwck%-1k3yUDB9p>S>qSb>uxU+y?#kty z>J!vEf}k+GUE15RAl|C|t0kI}moRCb1Q&Sp`idqv`Xvyo_x<3UT9>*cmex z+gTG2&+i2zaG2y1%7@ZTE{DhJxrZVT+EPAPuFFZOhhK}rinn|qEB*vfnJ^es!>SBI>-a7{tIJA-wodVH6TNR+3xJS>fQ4IvI zWSdzq4BDJDyA@V*5o-8yd2$=~3YO?#hF7uMYJtRDmCHg4N{@|kK7_}htnfp}pN1Uz zro!8tAho``tGcUMp_hx($g{PRoAe6o5iPI@zRzj`B`XAf^RnzAXPb!j$l#6}F9_HH z&pf0a!ZF-FL4xMA9jI!B()#w@o`i~1V#p(AdB0jv^@w(hn=)oKqg#?5Jc~F~xD&2* zakkzE*9$-V+U<07V!CQ4w^RTa&bf{X_(ZkK2iP}pvHqK6$#?816 z^E0NtR9P&6Rg3U)MZ&F@MA^J`F^~uU`8l>C)B9T87*uDdiZ&ibVsff&RmX~eo;T0iKe2pv43?Y{ zy4=>tI&r(wG~5$GZZoSs>s81P6KLKp7b;=BrKVd@&OZzF5Fhmx`>%ZxW!Q~@iz;Oq zkyfo<+yb3{8mj$p)?9eYY0zt`ZHpZhD;q$!pJ)?*H8UwjXCsfjKde|f&{)K6_Xj!! z*0^u%*=vaBf1LYE^XG<9*nEAu5!vzwTA*swQ>WN`C!3*NON4Qr#KpDK+Ef?(b#74r zL05hHQTou?gbSV}^bDkBLH&?&ae+~Ry5f93ef=&wYN{T&dSjqb?ywxGP(=^B74B5d z$ym@?Jre@|t#U`qY`A`l_Nd!_@bX>m>qGyIr<;SCNVCV)@38zlsJPPb$|_s*r7Cb( zhe|r_kVH7EZg{tb{DubNkDjWNM$DDYTw;1V7kh%{mqlt+$Ni3S0ij^@a$6YJ>Xhl?p*?h3*;{09af(eew{EEwyGp`d19BbyI#1 z$r9L39oO=5N11><)cD|5IIY)p*@L1IXaR}J@P1Yb$dO9u)=<5L;tb9CxfTb5KQQ(o zKe;mmDZ|)>tSkLBQHKVeF>m??UWJ-#24urRp!@F8N zr{Ff@oULCo_Bh_YZu3dE?TF)-xgiBCI|c-m*$0%`UjC+(kr)r&$9J#>5XV})G`gd0rrp@`=!q=N#UsX&aMI(aL}l#^D_Rc8CHu^(!Fw7LUZWa#pZ-1VkQdbQl+L+-bmf$7Vyw|}kKnMV254fH>8PDVO8NR-v@l0lLhuyajOMalJ`@}8Tu6Oq%-Y4 z??d%K+;Ms&tbjZl0ygG1{4z%7ul^3`asFm#?eLdSPH(LUV69U*6>roC*v;(Hno(l1EQ7r^VdK z9BnNRm_WrVjWxU$90=2IBv~{xrse-DkuRwv8I1qio4EaA+SSEyvEa+Xf=Q=9V}Ag6 zk1uE}b}r=b*kgFdVNu@Jdr)-^3B1*DDYpX2@8?Y9$bCNU>xCT)Y-O9{lBz6gJ-kuO zSj99xDFP51IZ1+VR(+)gbeTx(j-ej=gzXM_?;wE(0yUQHV_ZvaRP8@wI<9V7FybnC zP~rk6nc@+!ySG0*o6oe>nY^tA^%CTwT2w6D90*w5@^7y@YLOo$ZHP=(@lRZe!=?}X zX~$lc)(C(kE0BrUkGCIB@^dqGU1n6q(>JkP8(uPo28D~9Nlj`^A4`3OaJzgy^0~<2 zTe*RT3otf${WS0%DiUu!`lFfrBdh6%cfJ6h4H+y?8UZ!fddZ`%w{nY3>DE%NZVEZ^L zpte6(SUySP1a8wkJLWHc%&B*(bAzg9M>_eYo?sM&WG0{gG z6y;H67IS+R5}gGTia%xgn~aaIfaZBTKXNe!7sXIjQb#Do*CjW#!aoO6RMkNt{?yCj zkibi0`|~^&Dr`2e9^`PAk|#jH)p4BfOnMsn#vOQ0+YP|%z(|8%fG?HjTlblF?k^A0 zS5_7$`2e{s{3Cju+<;6>u0xJN75z{bjiK9FkAB!7#R3z#+OTl;NOHN1>VBHZ_Ji6B z@z$PyKi8?qIili83v^9pyZTq*| zRc6pP+4r5U*Fb~)z6conAyqNHqEAOlyit|kU-y{g;L#%1 z=)c+RlYZQ+@7?;(#N%I}j4u3dppX{zo!2)0Z=g(NkA{$j^kK&sPU$|yU6Fvw@AfJe7ljk7DbIj@<=S3TP^9So7(QO2*p5|;?E7_F7x#*G8|08tEg zSeNgihv#f!W4`gkNIEuu(W`;s1wic2lucXKVw#wZ+MI<~6&Wzn<-tiQ4!ibhL4vLU zmf(Gn&Kq_Y{i4oUA5lEJ6_V5Ru-4fo6nOtDelQ@>ywRB;zZd~K7tY??o!8}EHw&LS zt&?3zWh}|aj@A)uabL{6THap7iLSluqlXAR5?y7+);3=JMCc&fg?%foC0w;Lysdt~ z1)Oj+zFmgtoI$-gp&B0BN;Erq;5wb!xZEPrA*vI$w>nhft(FbpxjaZc3j-yuecE;! z1E1_p-HZP+_2H^w0AIRS)M)cn7FeODa-RV*we}*@@L#ecH6>pC6FbaH39C^k!~2+; z13yC&M3?TdlsP9otJu@M;1~a6@L) zmI`h3akBFk_K}xk-QJV?VUedTzVX@nUn2>Z28)gv(m8*{A?E(+Q1pfN+wOQjo;nq- zhxd~vFs9CiTs?t{N29~_I$ui@{1id6c>@jYC)ZbLfnMmi_#Bn+5(nE`u7+UObTfxb z47U1I(4~*&b_1|;yFnio@+S60)xB=hk$C5m$Igb+X3F3-`sI7ln-lDtRzi^k&gqW# zu*7@U^}4Bj`fu9O!G3Npd8V^pl4YY$?YSU%VedVV^Ep z!qCHl3m*=`Q`d!xCDO^Hi`$J|prAY4!5PfUSY6bP$Aa_Dji!c|ihcTu*ny!H>+ETP ze=2Sy6_8@%-}>sDEm)i*yFcV#%`8|T3B#p!Pl?1~^x| zo}~Jmeokab>}0zX_(C%}kuNT1@dRMK^qEV!I+nOeox489_8t*#g@+$6dsghj^}i$k zFu_VEcPNJUiTg`?tTt^}o_uBuqu*g?gQG|0;cW(NRXi$F84KQHrueoo3=2E15(Iu^ zD?w#ptWMx0w5|}?5MJCtc5uQ6*9kcNn(!$4>Xn5It-I#;Ej&%0`>K7>0}24REJI5L z*|#L0!{00M?`*ANzwa<*Tg(gS=%42=BtO5x&P!Bta4iTc<;xdshuvgHC6|}=#<6(9 z_T+O2LJh1S@=<-n_V<*eJ?bnML}F@;~hV|4S5dj;1=YcvT@iaKLPtnNiBOJ@YjPY54MMx71lD# zq%r)3JuSJ&jRh!*;_Eq;y9 zzFz}%&Jhg|*NqZH*mB~Bb?FP&|11;IV*&8M|A5jAs$EJyOY5;)ByWnN$>p?WC-px{ zTv~@yp~@v}!LFMr}j#h-AD`@WInsOOsP%y@dhbxMW)gqY@FhYe{W5 zOlNErc+PwkRXa;{k6Bs-bH8XefyXYR^>XLIuk3T0IrB7$^^X7txvqd3b)9$1-o0Gj>Z~SfBEIM_g@soVW zvq2vZMSPFiy1qcfib}zv(h);`k}>RomiR^_j|Tb5`^t+KI^1>bU&fazFH9>u?tZ<- z%^X|y&3!Z*cazUmFfZ_YH-7xq_8}ABwWdb2By>X1aLt>~QV>XA9& zx7!J|G{ueiEb*4v4I*O%TT#$WMx(s)Hel99#ifi4@8>w13l%%Mwvg>kQaws6-#K>Q zVZgmc@+DY2Ol<|wV(%z>?jn@=nZS%P( zVzlUDLS3x!ndI?aNCQkaYP2fNddrsVmApQMntAxuB(YgjeUVFj##_7 zyRxeHi!aS^M2?i04#64qrwdVy2qz}8CnUI_y6u6#4VSz z1sSW|Rm5_j52y)?zv9o!Mz;>$Y8c-?3^0wSMs(NYo0&9U9O+SdHupS#FL6IkdhCMp z-R~#*pl7-LOZFH(mta-r-jyH!l<3kC#Cx3MYXX2Yyz%wd3Vkz=*zZBESJBsv=O(G= zR4j=TzPjFpy0&oQ^YiTD2N1I{uhLAp?|1HNI|x}o4A>+yd~e_B>l`$l2`bThC9`!t zvt+=A%@w@yF(s(9m!=_FEyQ`cL6jzLV%* z-8R$bXxnsjS1VOU%2q+~3G>YO zZnW6lxRIpoe>KFQ?Ar)Ndjxz2H#$SgFy`q2I#^KP^F{MZTjvfo)S{#Or|-#eBo`3D zTfA91Z)l@sDf2colGmKr)$%3@Cfy-e#eCjrOW!k+<0mHdHfnM59~|gK2fB1@F4L*y zf~90|t`QcEV zjDGF7D`BTscAei!Vr!DEl;V|ZqOkiJ(X@RExqzh~Dgcz)X{dGNy|g=ehgn+?l-$!W zKlNaEqD~k2yWz9bonDHOFOiG|6I6F5EPGHd$T<*y^*A;Lb(w8EC-Cow5qRV7^A!hgp290&6@S^WL|x!Y%s zmcY*TBSKDh#Kj#yoD(H~<-CaB@Ix*clXESFA;p9`@3IEhxUp{;F^Cmt3~r1?Y`X5p z;O7aE!A5(3djdVvI*I3*{7NuHKS%5^3{3iWsAnK?Rho#wm)0SgsAAb@q?++>?F;#(*0~!-H7E z**76+Qfxf8IAnZ05*SZO7G%p_KTeZ6xdkqVM13v)G7EgrJB1dg$D6ZVz3ud(q?*o| z{Yf!{Rz$dSFF#|&qr;4xgSB9|YlW1j&B)Px;#i=c;3ICugqtaV(rtMYOEp>D(AR8j zGesKnHan{7@%X`3iba~ucgRJ$UZoe6lJTmh4Jpj78&zcH7N9#=T%0QKDdoO%e8p*p zerKvTC|q@DNCYuZdyc!+auP&|*alBNdJ!V#V!(E&44@KIDiQQ>oQ7zq1s5mJl|%?RHaGwHV9RBfK!#`ZCH7r` zz%f%wQ(9fo0^ZU&@UVhFdtRF)e<=mqaK{|VBmbSA+qYS0bpXCodoywNdN0! zHPJ!w2mzoG{sUD{&ne7o=h|?NJ#I|xGN==IkCZ`$lcB&kWBcTe__lp(`Ai0f8ug0D6m~~t&SnduNGIc}neA@u z4tkNzn&>f7-oh)zh~kgRTVMjB$QRR-JcUhqN0LX9`%ROcEz~^1bszN);Z0x}UJbO| zBuf5@CMMOs*M3<3rzb;`CzWjg*C46AeHM~3Bz+Kj;L_6F#JOA$)g3n)c=0D6@`X^* z7xvdU;@8+o*=c(pl$wZR0=6yuGIkhjDtseOv%2vbwuALb$eBm3oVS(7x8hsw`Sqa* zbsr;ma$AyQewBF}E5FOrk`9Qf}`7x0oWNhx&Xc+rQ<~U~DcQ zzt>r?TNod50tAj%!*!%1{XiZd%baXMD&pz-_kzY|Ux^tscJVjolkFzBfhSKH#@a3~ zOuq{fao3-{Lg^E($~e^Ic+KgGH@nU4#5h{e@j~k^)ok0zFs!I z^3133v8DLLkjO?OeAxTmuZqtrHeAmS>wh6X{I1@x$X6QZ-o4Q&P==W`GMgzPn?2~z zC`y|!ZZDDm4=nvGB?}R*ix@AvvvwSRQR|70!(_G9nK)0lhlY$_2A!a++Tj>la%@gY zo|EQZvP?Dy&A;_HOZ3MVL8eU9+@sGy0#w5jg@{f2bV4}&LK$^rj;w=C=!%A+N>5Hf zHOX}^=1;5jSsw3=W}g%H=?)w`W_u+*-tAa!TE$_UOb|@K`=|>>h6hx|-4+1j<^lQx z+Q++EOk{${4W1<`(+FB91*Qzx7Z#8}4Q9j-X+@qg{m#ZPL6IuqQ6akr_1X1!BiURU zf~NC8fEi{7v6u{4jTrQU(qyGKIcV#A8=P*_|Gwjs_C5K2xc(r~z6j#YDNZ7B-L(g9Bo4RU+Kt8bBwd%5jJd7b_$rbB!v zWt#ooqYTxFaAQ(}!9a@iUKzWMVyc6-2~5kKVrPP~CcCO3EV-#EG9-8~!_n zfzvHBSFSyN7TD9>8+}}_-4&WVu^9FhF?6j18D~&0VPyy?8I6_&?iSTR413aPPR;&= z(%|Cjk}&?{TTT{&D&r6GOgp4`C{>gmN(iK==CYb~DdYIYUhz&|zgTKiGl?m0Vr1Nj z@XT%ZJV9>O_Upb-tqd>I>kOIuyn9^)tys+YF#ctP>HKth4km}yKsu)EEz}C@-YISJ z;M8=AjG>=hx#Udl_|BGRWoOwUL#OKSyf`B;~R zYVn)=D6ZgY5^b&Okyd;34NZ5XHx=(k&6+V=>p_YQ9lL+V&GwR@tDFCZq#!w})A&{E z4fmFpr&2hv#@JEzMS@A=psarnFa3wujc>Z}M}$V<^GafI3`txjy^@tYrAe#6cHM#j z%BWbgYP>N>^3`eHK=$)6WSRqw>y!X9UEv?xLaOw_AGQ0p%t-|~eWd$7^hj5dZq~+^ z2#feZISYz^QaZxdrGz!#C9Mr9FLUlP9oF`=SOTh?h<4=o9idQdKo=x%e^Dvi?@-V1 zD#;xL5!Uu4gxiv5SE@JoR|llMyCjVnVC{oUQdpmCf=!EUFSezpwJX0@nB9wgs$GRv zC_07TC&psh#`MS6J|Izc>F}L%msTFy4+a$BgDSHvf3dz_%M4S8ta^^jx^c{P6*DRR zf0EB9{a>{~rs{11g8(LVTf3umyq$gb+esRTA z?R}U1Fz1EQUupusqa59NYb5+wcrt9OyJZR5eI0U>Y(_s*vguY#%n2#cr%xbrOJI9O z00Ar{pFrNn{c!ukcISox)#<)Vvmj*x*;N%KX}_+|NnolTy_5n8l0`v5Le50odZm%hz!VeQ)fuvm&z=x)= z6EGX1DMSuuT<7OHP6D-~p%v&Uj4z?G3B__NUEZEGJP@GV_r0FzpunL0;v(RaJ8A zj*w*!FFSg@d1EN+DA@6G{WI_Bn&;_MM?ovz05G0)Y`*_Ubs>+~;5Rj1OMJfU`2m_} zvZh);5l?X_bnLlj0N51>kGEFfcscf#u_xRME8M&?PF2RM}YX)Zk8OOzbX^{2xFEGQ++h^n|EuXRBf?UX(t=fA*Jvh zOz!Ch8I7iK!o(|}nw7%dGS9)<~ z_VCsIry+1*8GV;3hDu+Xs|!U{6%JOgxve5l}ub z<-4OX^~aO~gH1(6m0tf$W#ap|SGoTt8vAP?uI0|c)lmb6rV~xdB~HjK2S?9;M{EeLE~mT7vlz;3VbCYq<59{vRkTvzsDZ;SCSGzzPJ5 z3`skkL{$iYWz$A#30Xs@QVqhhH226qscv%J?Idi4%Zc3p@@h&@t!k96!CRnHPwq|Y z;%c__1)(H&;C@0a)=4LfdyOL>R+x z?Rf5pNZ>{DPwh7@RGu@x%NGgQj=}u&ChGuJ)6;L*(}N(C~8ZaEO_uw2G{Sxq>%yqdKI^)i4v2>z5quZW7q}!$5KmQVT(|VH{6w=p?P6~HjJQ95D z^82mwi8;Jlus`^{%Si^{;p>p=>J9dn#GJ4_DgbO)N@MqU-Ca%*n=DHQbiL(>Za%;tpx(NGBqZ<|)QP9_+8F(7? zn@9-5Onh6x6QJff&LE!Z=EerV*xyre=>j0qyl{)mQh@rj4^@v@Y=z>EfzHyT)-E~6p3LZ>MtClcLdq!TC5 zA(aeSHMb#wRu`l-XOq9CzSEd6>=66ZGx@|D!7=>`-SIf9Dbc@9!=(AiD}hMNtCv32 z*9XoAG6epl$E|dDHb3T}?EATGHS-@h%P)SL!Ua|iiag?wcw)4vlP`r%KE4DP!NaOP z@8V%;-rCzIdT*R{9*lld*OBOoD!WtL9b3gyD%GF#DKt_re42 zz-yT0?u6|#Cgc6vx7>~4PP^xi=^=-1TI zYv?2jbr7yYh|YFW!imisc*O1G5D)Hj_o=>u3Pjzn!xRd4>|r0Dy?Wux<8^-P;ZL!9 zV>Fq=-gI=>o_KU0_HAF+mWSGC;TZO`x)!i;03QtwMS3zGK0zhdQjS8qH!?nEU^)3M zNOQ7+x(s7Z_m1i=3)AMwtMSh^aYu{RRginzu&G~~Dtyi#hT4EFf)U)%pE;@PcMR7! zo(aEwt^cgxMS*+K>&EZRo>eLVXRi=GXN9Zhqeok4sdtta;l6Nrg*em#rQ1vU8IgY7 z$7RCKpRY`%i3R)06~hspu77`WdA7-5xEL@Cdq1R>#1Qw29JRX0O#b-m8cs@S3KuVm zP)^#JrVN5O>@fG?Kz}M7?~7=F=)}z24#n5pBfyL<(i|J#NQV>^MMRax*3D59W((tVT&iaFR<)17Q1aH=C=C#t;_7UDpRtwg?d5YDa_%lX3AsdpcYPU2E-D zP7%cp*VcNl9r2@}eX5=k3E>e#z4}fQXd;g(%`7{;lsaGx2uxCCw=;Hn=XCSRG9!{NGs3DdUNejYt@Kjq^m<@qbDFD85?Lo zxAS){Epx~H6j;ey zatA(g9Yt*Dg;AyzB%2(IufL{**H?bXQD%j`-h$*(=6xtsF1zy)q?1L0u|cgSklAEP z?90WRxQ1GO79kdBSs@56cym>jN(122Ddf(v;z;0S9ORcifRk$O zRn_{$>I;v0M+6G-E$@ctt|i0OPyXZK{<6p_>rz*16p|`Nk~%C2sXg9D4QCPGj~r|` zn>+R5fHMG`x=)%U85e%tfi3i=4{-t!S0dDZxPy=8Zm0&h%52;Oz?N|Ug6@!~ zzTKaai;G_1#x~VV>}o|bd$XoBihD|;k%6XhA zopRslQf4vDsZROL`23%FONS=rBMam6UlvqV0`O;M1SyrB#qg@C&7HgKcVDqTzDUA} zo2|WU=zYe?nN^f+y}X(`NN*D_6X5i-%(*;&T_pwdEVZ$ljkEa?4esu(3y7%4j6&M` zgZrl-C;bWkJw|GTAeWS7d}rHe}HDkh%Ds^CCb* zYKQGEh>M!5v&+zK7`?IyVZadcH2eAeXVy&^b&a%L;Z#nL%-y}b;F6dS$LM%frmIX^ z;BSVPD=bR;Ej?_EXi)USE?uw3jO0NOaR;e&!p6z3egwQ92-flA3F;3t(4e zO;Dp}*-*?RNA}9nCz1y9xr<7efRNcP_e3hlX{yTt8ge)-I97Fb&kL`|haQGV62Dc8 zNa(2MYdRw{B#oR7fmSYxkT-WY zbK{id7tWSeJ~S749UgtJ^+Eb2L@Ge2qwmyi%1#|}>nw(V&yov&p^h~-WY-U#k1FPP zzX%PH=>hMgzfVkxO^RiqB01th|2kK7A@eN?fDCjwBzdYJU|&lCa?w(-*|PYA7nOp9 zL^BrS-TCHF9B_NO53&YSPcNwpY>j@Oc=HY?3WpY3&_ihEojt-~HX|4BaM7eG#Bb`@ zzxjRNJ59shLj%z=BhvtGr8>SztDdF6j0zu>^3P?s>?^QoV+8mUI~yjcjo$oS%$pMq$if ziWTRsF~|}g$mCBEb_IGxrWs9tAbu zTylzqBt&HaG=W;j1Z41hP@xAj?>0i}Yt}zUyfMgL>1<~zIMkJ8Xf_ev9r8yeLZ- zF!B9;mIRSl(XnTi!t8C94qXatm6!2fXmLR=wh@`3;^>3kU9n9OXh$a1tMngQnaQw%B-frB#(gjTH65vIte?))gK@?z5~|2vcoZs^A_W6b8I zD8A1NS4)HQMj{gN38(Gh<6Os_o_4N_(nHp9XWZ}p#N_fR6bdtur2d+-D=I$ij&}XH z|E10<=qIj1{iw$nCN(sBOY)=o(fHli)igfwqYLnF%G=>hCh0Q!FKpE1=icZjW80It zww?z%O+Wp4@43>_4uMt@kCU;1uCKpSg*c%H9UG$;#%xlEVlwa z;hZ#(|H-_X9ovQG4tX0O_5;Hy8Xz1v z?Hb^adYgWr?ngn%+B<>csCyN1w^vce8}uGsmg*c#+z(DzqWj;Fh!`gs+JO&Q&BLP!@2?r9n~63K*3ApNi93+$lmG7 zit2HcA3jVZj-1SX>@4}a85I&5ymZ!=9B(6KP~u*PY>8p>KpD>|1$sS&D*~e#1AF1x ze^YfS6Af8gPqOZcIS~Y7629D*n#Rz%l#K3#uBfpE-j>&mdF@$CCCE}w50z2cUxU}j zbt)ym{+M3d&C;x8p&mBS5vN(2WI2fwY}a5~w2M~&;)`C_)QtY4$1E=G`@7LaJk zds|!jLm506RSs_z`DYlrh-cEaNp7u4%7-~PBK>5~i`bzOS|oyznTnZeBnen~vaE}A zD!HNOn1fCD?Qzik5`0W+wN&1%5};8En_W{qfo0M!#_3<H)`;PPb6);BnX#qg9 z0&+_(;HfO4vqJ9yJ}=qB6?-S@f4d4**94p<#qw}dtp>y+zb=Tp%)Tyud63_xF0<;b zZ;9BTgb1vD9$)c{43dg_-UW;!unodx;*emt&@XjKKpxcnoAbO}4JTJqEULB^F7HCS z_zqj!s`Ktn)b|j*)zwpyU_^HGu_WDNr|RGD@7*uf$k&B&{m~PHOABTLt8?x%dIMd0 zXzp?AO^(-zS^(jcSif(z*!NH$;5swQ>hqU8W6i6^ebZ-Q%e%VCu(ZPfWgg_=REmgX zgdB?fx8>5Js7X=xlN%2QyNMd_p#dG?R!fsp!KdSuOIPih)D~G!hohRD7YEKaD!mJ8 z1<<0^`1H{gt;~D-Z_xeBn2rQ_y~(`EaExD$Qn-A4T|z$CJU4vytoad_|66@6A!0OO zI)Dvg+@8f27d?uPa+KN<-=L%7y3?*C4^Sen(?bjLnP}iWIZGT#_EicJLGKJAS=@u= zpie+FvCqCok&ny=ah8tyYb!WCC|q1V_=zR`jD8}ygALomtIh?)7i&LIb5@BO`8V<* z{Q&nq(w3G!GT{OAAo}N#>d&d`6l?^UgvMgNkn{9n*hl7cBI{hy-+EB35CM752XE|c zPN`v~0tCK>R$Z>7`ZA1atb&L-U(~qyynRbS^iGgi|Xp?@wRe!v_<842xArH7T72s>rN zF=;ihxNwrR5uldw=`z$H79m<54>fqJcg0zjN;=6x(fnOtz*U6bBgLWhZw^DPgHkUZ zp!{-5YK(0QJ8h!pn^pyA`DrzouF^oyWGE1MgZ7eoMPhI;M=O(Ez}vCbA+Jr9;Dskb z64lwJzFmt1$G@4!1{tLeNZ9vhAlF5-Gv6GQ_9TrX3z;S7^s zH9HmQ+>@R~vAV0}T#bJoWoq_KaXQ1}z_okC=1tq9vd)69kndu)l(ERi)1bOjKo49)>$F6p-U{-M$pZaHYB`gZ|A1J7CQq}O>vawFz z5|l}KZ8OK!#L8f~)R(P#M_7%n?$}J4Wsm&|RJl(1Bm|fS?0p5Kh9!`cweO`KLD_MP zB@a4ojlOgP9op;CEhk=PTd_OAXd(~}<D+8@CR{}H=$rGb6?%Y3-VQfuewDCw|f^4?pwTY)+XaD8I zBtxAyaGMTDr?Vv?YfxA@VxoZ*afHB3*ILn9=-iz;wr+*hH?(dnSpDFMlz4Kh$T2b$ zt2%Rn30Ze8qYO~#NF8y64VHrscP5Y;v(KypNZR&U033j_hR;O+XP2WdNWo9Ou;h;O zY_s~*x?t-t#!Gz}2Pg&sXdpaD_oCE^}B7%618@$-(3mCnt9ECn`u-)#WHJkh<%x zS(u$G*NcXE50|Ca3nj%0^Wz$R^xM^|wstT7($ij=={H{f(fbl$3la<>Ij_Uo6X&Rv>FW`^*>}n-fHglTDt4(8Y9aaPDy|M>1Yi=;Apr2PRRAI z#72+>L-8+{)H(z)MQ4O4QtXbs1{lOMVfi`^An!Z=WqnRfzQ9j`0RL;Wmv}kALcoZ8 zxDTrM>NMXH(`Xe?;{qHIU>6i!stveS`5XiC!8|O1#QOb-e%Q`a=@GzH_cD%by!;Q% z{Vtl}z~Z%0Tw%Z1?p_R=ix#J>Bj0Gc2@rLi3 z=_|ikw5X{XnQeL(u8Ib9M8zyk3gB1yJ+)`^)ZEYRXr7+7v}VfNSGuBUzQe05{zHo0 zm$ACRQ_YwuiL$2P|4PxLoVw5R_5

`w-3zq?p#sn{97HoiiZ>L+vTrGgIC67f5P z&QUmWJqW2%~6(nygH6)H+7t| z!&3umK&T1hb}mu{{o1bR%3{8scrl|a3z2KGqjUF!HT2?_Ej!rbis0CLpv#N{k%FXw zC(y1%(eh~IB$Y6Y(sq!2lkYh@N3T&jERQmkbbJeEM<1dCcDkVH^49D0xlTkZH_%b6 zlOB^Tp|v0w$k-JVE9%>NlSu;bk7Xc^Rdj>(!Wl4h-8mLED9bP=`H>#_qKwBz!lvMz zw^Bg=+x3go+dUH^f4GZC@tyUw;&qC}FpsIl8IHX&^fqAmrF}8gYM2A7G}Cin0Gm=+ z72H=<`6VFg_;p~pII6a;1Z(vk`QjpqIcbCwa%&>oCB|=GoHT@QBTr7PTuS!49zS9i za2+F;?|I!yuSvG-?wQ<_Pnrzk6XyOo+!gmwI6@;rw+FSXoYA||c#jyta5t&i*f!e~ z;~ky-v!X6QyR@zo8*qy0-DPuCzhHlfqDvfPE6U6DKk_vB0up_4&w89(M;|EV{2UNM zKH73FIO|tI0lx2OM?vWc+5rhm&#af6%f~FV#Upzl19F2*jNdhv3TmSUPG`l<0==7@ z+fSF<&FP|Z4|Yp=*+QgM(gSP%k@61;Z_CS~1hT6mZ4~N0fEMkX2V%ZkQmGHUwYUG> z#Co(%cdyVNTsk2zza_w1PZv4#i6X+_{v%R z(UVCypYI9FykKCpZ|v8zgkVTDU0BpwaLwbJPA9_~R&AyGNuL+`eEo6B158-Sfs~tH z#GfRJG9h#T-hayxEhRv3J&$rVgAK=P!2asJB< zVM*UxZfBJrK?na$P7#s7OW+R%6jc(>e3`E*z=w8HOV6ep?X!6v?tC2uc#WH zGM0vwjkjjywD}^gpL~rJ878uAeF3S1$BA!1&|M;(EtQt8Yw-!`#y}-Nnrav^&&dK| zCnfx}Z#eJ4^J8Nzuo@Gg#Fq`Xtc|+IJypv2{>pX}_gqB2)m$flD?WOyOS8?*heqGg z(5P8h!h0B(l3$CiSv?U>p5UdONU{cLy`RVQYV=NfkvR5tIThu8BxD(KdG_+qSWywwLvXIUbH`|y4CR~# z#ZVJccHlqIY)c_wt)siYDmu9N9jD*s8`K6J2Dc7njxivH5Vmq4?V(1{jiLHBLX)Wu zxuoqh7ccSQl%A# z+lF2>wrQV#zr`J2W0+rUC4dv0xs<-7=}C5zqi*+c7ci{Hf$95VwUd9tEiphM{cQ-> zlQP*Q;``ZKIkzrt_hYDSp2iOd2)(ZmwV*k@1BB+e0T*yr^bNJC5w1GLFo1FiwzfO5 z6d0RZwtp+kMd=r#uCXu!Zt#%I8io*HLx{)3;W+9^4~KYk&C9_iN^!xrPDQMi@=j)A z_$*K+4Ta%)O^Riii1e!KGoRm3sHoNs-L-(NbxPp0 zWbp}@5KPKPA#Y|qt|Re0gWPPdV`Bn$^pW)FcRRsd5MG|*5&)WTv5osmfQK3t4Pa<6 zYE1!|1}NE8QpW=`X6(iy&my$r<_19Do9pV=7*)#IYEMXPg#N*Q(ubIYkq@QXp?&Hy z0x^KA2S^bxAj*p_b9o#N6!jX{p``>$H&KI2H=XV&kC%wREx_+D7MIQqSx8VONn3=y zQi(k79ONB5NW0fy+OdOasolbgXIO<$b|*RJ#H(4eL}=-TOKDg1pH9_f2UzaU&9TKQ zd{R8!*5RU*u=Ix2Jq8!&?4yNUv;6K($&SgvFr;DR`2M!mS^J;Nb6U$xg;5fX1;5i@ zBhr^T@p;?Dm7!};$auLADo`TL2k_kwp*iI2?#^L=3`RXL9-ku(%gqNm@vX~KKd+;m zE>5>mJEohJ2DWS0%}H8R(_J%2&ay=8M|IFThep)1AZTc>)W5bsu~xtq0D$bdei8cR z@9?p(=MhSu>R26e)o3@=mC!El=Gcmtp|u?ES%j4+tju&|n!Z za?(4#(s%moZW4!x>s(FXzS4RJnkDPkN7HP~g!X@11fZ%}l)p;R zSh$#OH<~dLHBXC}>~iWTC7aT2+zF5ODZvSe+?)yN@(K=a1x+68LUFL$?B`rI4~b8Avg`HMOg%bg*zpNM$5c%Jat{a?Eu(D6K{H3B@~@inxYSCRES zwc*t^SysJ}1a6dA+lhfRfF*YO)gn##S2C5!**tNv@BO0J&VdRA02<0zX$W!h3q1`< zaf5NvmKt;pJw~Qyk0_>qH?KN`iJGtYIx&61ICw4i!TKM64TgEzs=s0^RIIjB34Y=P zUv4IOn--s|j8Db{L z>!K^}VKlPDV`HsBk1RA7bd^z$V;RB|NS}}6+ls4l(m0Tfi%3S7n$@tA@QiPJd;%S`X6ly{Y)8wbg!znU9mZ>F)ztV;?Nby+)pNt_D=A`j zr3gU95kIbrH0#c!=p^SYoo6K6*_lZ zjVNzkmy-NbO_Q_7hZSnDH-H5Xlah(ZqOs5GB!*`Na$HRcMuX{`e%YfKgyHwA+<@}O zF(S0rhA~ytqRzvFDz@AN4YGIw*}xXCF+C#fb;!0vW*^$`9H1KLr@3)~vHw`B$+GJI z)>we{67UJ++*tM#HriW7PUHjntHCkuV#rDOgHy0I=>AJ^h|` zTrlt7KKF}mg!U-qzLDA+qv|f3in)v*n;QXqy3cl4D2m@VAvw5WC@y(4t+?66V@1W< z*w|0vhLg;cqL8`23Be~U0VW~=AExO4F$uUE`gEC)XM(ofA0l}2GPn9go@K?s$KL?1 zKD##K{CX%VedMHPc@ytv|J4=!wf9^V%yIV3pWu8T`V7^&M$`$|%N#(6=>HRRD5*mOR@$isUKgis^ zQuMaIep^lY#x8C2Q%bx(vHr;h&Du<)=SEbU=HT!jUp&{wjpf?PPD=!!t=B-Q(RfJ& zCu|9H=7cFr=VV&$NNDhW{tpMQGR=82QTw^jme=^z1mhJo+=aBDI1wFaLU`1}G|-`# z?>~UAj2Wt-zav$Xcg}rYkV;k!RL9kDA-zQ9@l}_vM&o>9{^iepf6WS*sJQyQ{`uAY zq}y@dLDq%<(+jkJy!+@@Z{k*{E?l6R%uarefO{xl>*_M{!mL$=ue<4(c7_m$oR*LwT9s*lyMo9j~3sKdTD#j?gHcP0qVU3X3aG(=LS60%mO{} zQIpF$IG!J7bTii>rwsCVDpm5=gM*r3w;}+9?bCbGAgyr<`{A95HX$zN?IcLS5Wnpf zwXto|jKZTM3Vy1Uzt!NjHZp8OSmquZ0ssHFC-fyy#sqgutnf|-nBFS9^*KC()mdsz zNNL)YIIc`_C7r~=!k#jE#c@UfxuoE$1E}RLI;rKrE4*qGwy zT;)mC##JS1pM`wuAIiL+9gL>7Rg}IJ3wC7bw4aJaPa=o4Q#sSjTx8fuz+!`8t!fae zuuu6z3hxx{lTVKdmH8jok0^7_<`ljNs%N!&xho?U zlF@gHb3zAdM<$*$9n4f$Ex}87s~a4W@n88D{{LuV)&(^U!<*uRIbQ#-!cLCiUuaha z2AJ47n$f`jMgO%)nX9AYxynnB|2x8=C<$fpkk8i9K{!U=z_&GIc#^m@)u-^Lq2afe zkX5X*fIrDpsGW9*P?CoDHj@(YmD759L;{WY&LPi1G%{6bTPhg23bZ-g7Mo~WuFZhB z(P2_*?*)*YE6kQUa}Oe!P=(}vv@rGw7s_j3m@JN7psw?R9Lkwo7fEN`P9MGje)*H|Suc%*VH-O<7!@{*wF~GhR$LLUa z04FlwbI&$Vo#8!CfEczZ)^DIWP#U*M-CPL_`qE_f4RCBbmi$!Oz&hpVS(j5ooKcWo z3CM!RJE@Vs(6GMsdiP#U8+mEl8Ny(lA)=SwhkL{K0YINS08Hl)B{X!vzH=iMpVwNm zNU5#=hes$V(E#UQ^1<|-EBb~Kwq-F2slf2u(bKVe^35mC^Crz1XI`>+EsrdD8o=)Q z;zGm-(W_UaK1x}K_C?Y4TY7IRQM($XnXdURLAn^92fS^ksQJgaLQ9!-K_s5WH`=Ln zwYn%4kIsV6PJ3k?9%`P6+R!Nl_3w8BLkH{x1p^vnk?gwd*NHouvb``2mYW)1*yYqb z3;SUcjWQ$6(jSm_5AWrk?f$CSiaK?uXBo|Nrayjvj7Wt)@rCDJ77Hc&4tuD!X8&)S zTI_f;0Biid4=3Cazf}`(5=;8GZ6@xvDB2Le-eGCc#fD)yz;F@h4>F*;GmW~#%wiBe zJ9iOF>L;N~^I5w&pjE&(w47X2vkn4bUY~hZwXQ%z)h<$NcxNU(G~pY?^&3da6J=FfpB? zNIG#bUHamnw%9rxh1^oPW286vdsTv!a@SgJs*Tuv2hCH{kBpAaOL1rZVlSs{v_IR+ zdcSizqjC5u&5?g7qA-DNYsN!8tszPMv}eo0oO}}q?TBX_`L?5945jGV?iX|4aLSsP zyc?wRH)9k3{2IKyqu2HEme$1^F6$2wAKW0JXD82!$S`>5T5`dOnq=SKVG__EZw&Du z#Xja{Rtls!lWn&(tMR1q`+BZXP*jR%v7`ven`~>$GKSJ_o^q6d1vhb_5^_&h=sotC zV##7-ZXlJ7m#Z>h00JU7l5t5jvSP?hoW?CBeUmD(KR4^cp#%O{XzEI@ONp+AEp6rN z8=m^DE~MwfA9cl?z6H;*06y{2%7?6rFcs$tM-+-a)ly>D|B6l+2Ell=$RZ^$B8Z?w z=$h(p8!Nej=F~@O&!Z>0^7^(6g&O^?;2P>5UG}^Za2D)=8vEYb>)!OGMnu?VDqxmk z+^O+XnF0e#k)79Y6(}f2R&e_N*rwsdtYEuqs%t@Z!=|iOuH|2_0Ztc>`7Nb1I8GpX z`@U<6*Pc?U2KD>rua5L$g*|=0RHZ*yD2(C;=?~M1lB=q13M6n{LDvkIAQ8Jx^>f8_ z+p0_+xua?NkxC|)?QvJddooqG!RxRX5gg5HGk0qC!{ zLP@MT2^WCb<_Rq3QZAoHmChfmpldO5$S&jt6X;iM)(7i4+d?s=xBHRNn=!uxFD<(b zBLhUIH(i2LxwC&ErIy;pu^!vyT3d5 ztJyzmSbyCq_$NeAEtTaB?$@Jgs&0njs{*pm9{i-caWb$_Y-Bb^FB$x+cpnav$a1Jx zxIO*VlsttFB}sM=L8$;WZEXW<26TPjc${+qRjkZ2i_Rb1&TAuj+Oo5sWY1j8zDLBb z4$&3k!yFucS9=K1`YW81pS74!zZLVOSck)@FEyAUFAXcit2$l|&+~PaAux{QcEid^ zKmT!`4C)sW8OUwDh)YgT_*`FJ^goA^;G0;fk*}oBUJHDOXBmu~)YZS;+c8q-f*U3X>w5-G(##0o%{m?=GX&R)-%mwi+^6cKy^s`#25G{ zybQ4`znkoBJPKR|65{D~nM0boCn zHwoHe$>nys8^#O_Mx=1lU} zf5&KM>S$Ba@_mRUs@iY4!BrXh)rG%?x?~Xpm?}J~)yTla=UsdKze0*h2l_B(6XQ*} zemU{vHkPxw44uyZ^lG+mX=Z$Madc5KCQE=yJD$TOp1|VQ$bua}r9awY(Qf>Dy+zN- z)|OcmxBG&Hc2=6UUE9K=%alQBKbK_tUD zVO;djA4B@HLRH`@shHD_=h~~FP1~g#iN~)mG{l6G(nqHRKZuU@b9HyD<4-Q+$0rAI z0Va0c_(c0$bK`)C(PwN8Nhl?e`tij#rSGE8<+AgqfPt!}_Kw2VXf`G=3n1DMUqZA57uJo~; zUH|L+L+#B)+A=a*#WNt46yrumqlly^f%?NGwvnV?<}#-nG_-2aPGG=(z&q+uif70% z#6gF+D7mX2!dKuT^yCLa!y^GJyEjAYR}=C_);}{B(^E3BCg$-|eiXA1ean@ig85HO z{iZ#m=KYb_x!A~ByEP1oA`%DQm045r77N>U;PFXT8Q)j1_J_jWU zHn$OXn0?A2dKn`Pgq^>b=@B=;Sy1WvO&c)WkyqdCGT?Qlv_0!(z+?hm*4Ans`oFTt zOl6)9oC=!4mTlY%Wq2K4`2|##rX6>6w=*A=(f4w!O zcK?@1&fauvORX_i*rB<{`uFm|*Qs4zYZ|WLFW!NNX;Jl9e&_ml1ppo*7&H`H8gQTC zGS+}!-tT$Db$aQ*KdfDb$<)RnkBho=h_bj+#3iD$C3TDCJ7@R^+iF>qYv-FrMjp?rh{uK4-Nno?O@=8k%Oz)Xvi8X$C)xNf4RuND=b_?h6V48NL zl`gB?$O&DcwK6mX6B|{O*IN4dUAkrTC+*joQ>9sn#$K@c>#PHQQhMvBp%c^7 z2y0Nw0r@r%(c%@2y5+i4tAgZX&55b`Ju&NYo=Z4?gr5TwoqAm+9~0|&xnA91DKA4Q zj0MAZ*T{GpX%-r~Io{%jp-C%R|AzjRJztW7lj3fL>>e?X1xd4NqJvEa4hL=d5LfF3 zm&EBh(%s^u3CZfUjtMXTdZ@#eHscC1<*)Kp@ZT=8wzQFeVak`hAxt6%Du=bsfBQ)B0gA$Z~=A*Ue_|BfH7M^x8pfRA zevd)C+cFHSC6HfniFXWo=-0n1wdm~geJ66ZkJOq{hzDn|OGZ}?pO=uRVbEm0qyZU@sbfRqaoYDVtfE7*y^JdUpD{46CqLu?$#Wo!&8Elr(0oF&fk8a0Nm`4K zi}3bS>J3w1?TeGjJ`GVnYieAYvftkb9U_=oqIJI#83}lZ3Tj@MC?wJsT8w-GW`4@? z0iAKY>S3kitj*x*0XO-(VRLfO!e-juFR@L#S)egQbpEq+c)^|?3;^RNEf-@BIp5c^ zapPZZuByDb zRI8q!CxgQpm9CQ>GZVQZc{V6D&%#O=glOx0aH72l%fUtWK4-`f{X)Uh$TDZ|gX=e; z^al;`U0WMEb3lgzV#(f#E#NRf$I+4tDsmTu5=~foZ$fqSEbBQRuHocuX(n?}&SDiY zAu$J*5Jq7aUW&}ZVpv~1vQJ~gfS%~Qp4wSE)I@jE4*}itryE@oaU!1b8#}K)LJG$B zfl|4lv8ySAXAKj-{zos8Vli>RDKAqpGppFt{l|9vud;=R3}(Q-c=?*JyNT6S&;X_| z1|3rA902RsAf6Ci%P!YVGG31F+M`{Gxzc?hnm-j7I>DY<&jH1yhmJAS`SS2)N0Nsj zDVLshQkPsNX-Gbnj>~m!Zi8)Y0}cwi9{l}{oQ1O=F5{u-Og}DJC)wMPrz{a>#(;U6a#!B?|#6K zrm{x77IWvru_w$_Q@rP$`%7fOwZ@ZPI3u>z;(R-_GxfzVa$fcab_iYAWx%7%(?2ta zx?1+dOGdWbcrrX}cK;@gVcpZqL%7E)p-czwzQUxb0(XM6mfs@(`9ISnlq$r5IOzmPGOx0WsDi_=p*=ee?k@2x&!-<63|BMu`7R9e&)WM1^Bjj+|#w^HKzA( zt>OfOmU!YIGFK5l;a{VmJnj5S{#1dSz-KWlpP*VAfA2#>$vg`e0nv92Eds@MOE>^g z1&|R@)+5#Ld+~?FyZg>k5pvL*&?NmfDphxlgKl42otsvm6vPFm!2f~;B&wFK@mijv z2!7SMDCDEr_h;uF``eKxYgXvym#1?_BkkKxQVSAB>WZsxA&VXv76KmO?|qlhiu!ib zl<~5X#6Eg*pCA=VzgV<4FJYjlU*RVxmVFqJmJ>5_rsCCZ^jvh;EXHA*Zh8H#`CF_= z*muMS1MlV1G#RbEtybWl;{R@+oS$8RL|}jZgxO7h2$xhdHms~PMtE<^J z`pqq+B-_JE?)#d0e?wGtKR_&t>6QHI$7bI*KgWK1+cIFFdOsBPoZxbYt0pWqU%Tg( zP&{x0>Ynua>^RY;L%WkOSE~@J)!>D^DeBg)cO2+teKnUWD_6O3g*rlnk1JzLYs}d{ z&k8vIm!PyO;PG3-b z2$L6-1o4tH=n_Hooz2v3LGs1^+P9EMTRmUVP7W8hQ3;06Y2-^2>?JSj8_exM!XQ}P zWn*`BH0DBq>5ZC#uO`W*Q$!9guGG|ct`n1`-_Bi5u8WQ-;``aV5AZOAEKxYHb5Vtu zo)W1Pa2e!I-$40%O#HQ?|M$)h_Q9{}{836w+u*fO3$w7hWOA{a9POWxhlYlvU$Y-& zPv>}4!qmduc)J{$9Q#cTZUFp#>%+YT{9N7DU>)s0?OFm5zHKSBvbsI&tE1HjEbrUS9ZlLEE(Y4S-9$ z+6pw`j$~@ZhOW7_zVED1n6)#zgcxa>{JnHFY`&Zl$FAW%7d7rj3;8LT!($yX&P@L+ zb;kRv|b-+vkX_LQey?N-ZH`U~;STO}6LZ{YrRU67hBy}HoFF7;%waT$a# zF_cGuo>+HZ$s^(fQXD0c9J7l??TVS?kL@@OeN?pmXjvYl z$>0!y&WVsuT*4SWUeQQ;p;1lGPRf}~=qT)$z~ef!9FxkaZ<{n8CVr#%jqP>L#Fqs)AM5u? z`MWuVj}%CD&J{Aad~i-`-pE80n4D(>?Yup=n?OcLkyUzwz-*&sw9p41v8=8|k)0wV zq=x7Ll=2>{&f)>F;0Q7Dc#EeS7Q4Je*8>OuSookbwlSJXJF-=cT$|Qcmmn6SkcIDA zRyvDSg-_?y_@k`6U|YwK;+Hn$pSV^^*o*p@B{)*a?><;i*`x4uzN|2f*nYv{rfw1@ z^_8Hr@p%mY{26AYBC0NKuTXhEzp6_YXHVZHkU<~1*IXjBcyS@A+yqNi{6j>IDNq)b z++v81l%i8-DiAwtJAj!Gqp-ieccCw^&;;{)i_prXQ9`8Oon9e6v?+*uQ~v*`ddsk= zyX}8?W~iZCKpH6l2}!A;q*G8pNf8N=l#UrXL_p~VQCdO}L}G@JE=5XWhDJcTnRtf# z{+)CF&-J}7-}z>+U)#U@=Q>wPa2f1( zw6u=LDt&lpa2|OZrkPa4_e3yNmUj0c`-?63{dRNWFwQPqh=YeG2|0{Comdb&k2%w1 z_wUhKVH|n5uk~z~IqieDxzbVUUM8O)E7?2%LEPQdGSg!n<_-drtIIIPbibiF9KvgD zI|E(^y30GUM&1kENiqMi>y_X`<=z+q#;%u{fOb-A(*YeqnyQruBz2Y8hhN7-YWbfd zn?#M(T>Hb0hN`x8UmphEY;&K$bB^Xo*Yn3=Z4o7kR6K>;1MWg83$MwmtFE0WI#8T8 zVmyvsbB8;Y=mL0mXs~58T=sZXt;BK*(U&!{J@9tyM`r(aPM0b~dYG1Za@t&7{GK29v4e|4*R#{>e_WUM8uY(^|LVFGxc&l)CAeOy ztVSDZLkv@N%E3=XlpR+^hglg;&t{1@yLs9;bMD^XhdclR{w~}!AZf1eZzT#{qb*utpjxABdby+|sS}#D#{d}RS_h4BLzi};Wem(ob;NdOPz|f7hp=X% ze(1P99C+*vZ0ofxnLF#|#K^6r2fo zFq-@He?y4w^{qBfz@8ooAXG%ZVoIgw(ciqgK6e;e&rg5%?Scw{e#x{RL1OpIDbA7c z5Z$&SE=;)#_=0QLu@7Q^d3y=m5QX$uHnh|D2X{Yc@a&GLPSwv|$2EuseX*5CPn6(9 z6T(A92tF(e0cQ%CcaA1qFKr#fO0l8{N_Fl3Q0Co;76+BkmM{QMUJ?CX%*f0Fl%;bq z*O4lo8D0WN$xo?}i=n!xIGNQgez_3uPGr@Za)T`C@xO)yIB6?7v#S~b8iu(&ho#aWS#3YHxBxyzWX4P>0cXLsZTQQrf-wPk){; z=ww1q|DXkvu{Y4~rU`=*R;c3(`GZ1>io;Y*K@53~V=>`~Ysoujm+yC#cF$>t>ZSGR zboz`F-``AF#{EyW0{DZn|Fu%x1$p({EB5#-o>QPeJw@=QB-eTHr$P`k>nO8LV^R{= zCwH+@2c?<&d_-+v8g3UF2R~hVwWZv!S7o4H7i&-Uh-Ar{Pi5y_%2v-FOcJ}hxv?9M z7h;L;!ME?>W^X9mc??7`q@1qhL2PjLa&6ySgvhdNOab_&eSUHAUq+(MLFKUz;lhu@ z9c3v!PEas-FPAL>8G&_ItF0qIsPD&>94rzWvk@+KdLZsppESXur$a7(Y-6)NH-i~k z!(V8(veWs1zbLg4>&L-nCYgc~Czrrs_nBe|(8PkrWvPgJeIU(6Dw-Q~?846_QPHmC z3Z~~GMo_B7od!YR>STvDTIzuBDg5X$>3D5PU>!}VZ``ao3>|TJ@h$J7GBDAe{oitz z`A@lfmDbFp3?%lp|110HKZklL(uE^fJmP!bg}c&$7@@fi*wkkKP%l|?+t6l6v7M_L zmyw)RJhuMB1cLfc;Q|I-qQo(=%mS)Y$B@J6)G5Le!0Q!5Y@)?X{&LzLZ7bRac{a84 zXy>qR5-M&)ExrdO`O1N#p0&>I@~j^N97*47`!0C~3zTixkfkg*DQr06dhM-LPt*Os zkzba9;3pGixQ&RNm3wEK!Bg$n4-kFTTx?pqT)0jp3j`l2=iKqbLWchWY7MDK#EeRJ zL{xx`Se<5Lik(Eo!J7A|OA}Gqqa`Radj#YtiIU8DcbpYSbDsRRwQQerXbwoT8#@mc z=P~T!f~r~X){7gY0ar%VP&ay%=iC!orA3|Yuq3(j=!0{>M1D(p9n8+;>_+r?; z-fex&iUG0P_P+Oyd^ww*kkrmKhIAu7UMCiaGA{geyzWAc|LH<~*P5mY4!#iALNRQUa$rOnSTUfj=eJC{U}HbQIV(e-lQ;SpdpB=|eg9M@^Rsrorzo_Au?wg|lZpUS!S-^wXUd0jbO%H73+ zt}Ey7|5i?eF&;E>?Ltg}20ZBRfAPD!`k@mUT?be7c$7FYR*HcL_8j+p9vVIX&B6q) z75+7*VRIm&2?H$u{Vp=bQJyIC_C{q;>49}mcLm{i8iWy0a0TfpdtZRvYnZ4tg%e~E zMPo>Q4d}PuO02ccQssj^&lCc^LT?O9#>ITg+t0W*%Ksljz)0|unVopc?U6ihi|>kZ zHK6>Lk{VHXIUu#|o2c)ayD8{j{ zQRj+}p?cSafT;U3vzfP+wg~V}aeb5<%3RYAARFTzr4{gwA !Pc*>^=NY*!y#KIJ zgLL2Eu!1na*I?S{Jz+|$n=VYc|3y*mKlthea_Q)9xV9De68t% z`|!D578>Gyw!+OZf9aKuaDs=A0Tjl7fL=Ospxt*6sz?9HKVb>~bcm=25?mv9rbpkW z)x^~eN9y;KN?8<2gIl|jX!es$p6?k@5yv_>vrdyG&0wZX3OG)>_b3}h^Hv7iX}&$v zK{i;qid{{FVkx3m>eyIsm~?Zu1(pMt<)n+jDwai05v(8tkr43f=bFqUt=sK2L8G#H z66xkwciVC^0JhRbuf{o+cHq^wfhxM>V*J;G;&=37?OgTM>%(scv!(8tYxs-S0LFP7 z71YWB!2JT+ZI3l`!g^D3j?@(YisWH*GM7alC;3jeuTJKa!D;4yeE`4#OM(5HACrtU zduxZEc3@J?x*Q!ku@t38TNY{*~@s8yKX! zRDRwzZGQ7*PEyd(+n>6zW*qV--;U&DF*$OZJwdo9ZVEgPMk$5XnNDjb2526$2dY6^ku=NTwJP~rLKiNQ( z4yf(y4uyoa8!m3XR#w@GeQgFhMy5LoYzE-5rLT9dL5TF?j`pv3XW666YRQqdWXF5< zz8CoS;K?y2MhxZ|5~C3doh?K;QRI7$1sTDuIoFHBdS-uc+y+6-ZF2ChZBhb^tDr#s zl~w5s*|?D*mW9N3y>C#T`M&H&wjUDuqin^vxOVF3Fn?JyFk1=)*7@THGF0(udy;cS zB?{{$2S6to0xG5(;EC@PL|Q)tVKR-hhw}qbpCbQ*M8t&q^unYDH*W|2$xtPJN^FqJ zJqVA7H zeQ#LP0rJFXo{L(V`!n(aqf8$OJwaumI>}Wl^?1>h=#A^DRDb@m9l}A7{A8hFRO;w7 z<3fH!=5}@Nlu5!jM0-Z>&x>q+vdBrDOn|%CY;8nSn!2yeVUHWvR)x&-Iob0L6($$gr(_ zPa>`J&J0%CaDsjpoIEHfr4tmX3ar!1RcE;sg;vr>@2yNC8?ZLGvX8KaL}A?dO*6qX z%fb+U;p^P0e?Kb{3T={)Qyk{0ff^uOblc#)SeN+SN-9{ap-3>9=?05;RhvRsqMhaUSjO5%{{g&ocn*&t#4PU-s>b z^-aX)Jr-#O1xRs4g+<|LwYX!732BI{(tXbfZYJI7TYXgscXv^VtQ@;Ms;0J6HH0VrxB)j72>4Qw!Wl?Y_`9N?6c6) zuIj3lR4{HAjkjG`9>Vn$n^7o+Exwpy(pdg-fVKy&A<{pgj?)}FnE}Xm#N$<)Jz*aN zRP7kCB_UrpAILh`>kL{jV5yT@raXdzJ(=vGh54Zd7)~zy`?9mLQPxcCG2Bc-O?xaI zZC1Cjj-o+-p&9R0&BC}66*cgU2;6D@S7>$pFMgP(k$N4@&b7KyDa%aTckjJoOxD7! zg(!}#1KZ0`a(k>y1jc_Xi8%TB)xrpH?Kz;9294@<2VW8#2F~8u+V6~Vim|8lv_1zo z?XGLyFI##NQ{U+&n+C+Uf@&CJAd(fNFDwjelc%Y8R_x7H=PzoNghp{9WHI8pFyt+< zTBp7-SJH9LwA3^9&v&LQWu7SvNh=CfCHGA}9C_S?=d!L(a^v;b)ZDB@%Ii{>^}o_b zqKz@twWiybKZ4Q$T|U!DDSs@!x)YmpUd~73Hm5s2lIHZ|Z=irY5sV6Rd}!-;HG7aO zb6-^)77){=a%hsuP_c92+{eB+8!@q5uY^YTf z)AX7>BjODp*5dr{_`33&*vF(i^ByW!9}{C&)YCTTd04?cc7Dzq{0I;cY;BuXUakF^ z85?7XLtdYH4asV0ITca-$ z7Zf1j(fdgq_P6QFXjrPXgh!oKH^GeZP2w85>mPmk4Acvm|N1E>0qL03c0=Cl`n9k| zck7V6{n}<+?KvGd@;Pqf+mY?%o6*qlJs6n^r@nA3)N38;$Lvo~#SDH-`?s}?U1E;! zzSsIR&#Jknw>U-q?I44~QZ#EZ*cj*uxV1usb1wsr^KdZ&9NqKpEe-6xPxG-go%}C{ zj%PE72^iOuB}(lD2h4jEdqScXt)ngp+_AHLdRXF@W-**k`M4I2b5!qRK7^NMLw;N^ zGLk8DIXxSEOA<@B62-#&bkE|}prq0FoP*i3_zBbHzKGLSmuua8^34f74R+Oti&R)pxZj`T-Q2w#>Iq0f3S-<_lP};- zmuEElXERI4k{UL0L~-G0QpVWk@_vGVe{{ghTKE6pCdv|ZA95#;$=vQAWoXUQuu$KV zgn~zqWf-_^nCvEJu9_ zuf9_DsES-J3+bX&<~J;!(>)GvtrGez7DTw;Yz&USCJMjEvI8p5ZR~ZYVgQ)H_M>f$ z`U~Z!ki1Mf1khYEp7hsRhzH!d>skiGeQkdwSADU4%s`RXQ-W?#J4sflljxRup;#jG@0i59|!%TCLST9?8UWuBWqqw17no9T*y{ED17amtrwz zd51b0Mh4RompY5zy$l{HWOn_3I=K5iFezhB+2A@(|Kd0Dl=JFENEPG7+)i1FW|F=Y zg~++_U+isL!Ssk5T7?W^g|6f4KS8gsYAhee{uzjraD)c5FVtW;? zfo3q_Q{i+8<%69_*KV2%R_AiJJiND*jb~5)MxS-N?1#1D$yPbZ>n?9t(2ZS@n|O=p za~K}Z9`nwxiEITs4PP=`N*aViOvfp0+_ z%3TbH+7qOr4aIJ^q+7j02k?9Qh!-rDYfV`+(Vct7qv6T!Uw}LbdVJM$f9W91iuEfH z!fnNe7)1g2V6KD#;L8>&1{q40wOfiv$gl9?K2T{e_|$^(Q5RNX6nHDD-zo~rgARU) zy3r7!Y9$2JonRcwS`*M+W5?&loU)_=@D8oJ2c|vdahP#)5aKJ5>)%_E34kB$>iTvM zYnIk2XFJj!6_$0H-+5ePk75(QemGz~Q{RK1qNL=_x<{rR75;X6cS?^qvmV_(cFIwM zmXhJ9<6MI+&zO(~m84nw4Y5VuWT$c`4$a6H==mT1nYO05+0MvL^rosDnw$tIev{_M zA?HLvT9+%^ur5*8LlQ02F5VMwN*Jtk$>a!IPmnvweM!~fcl;Bzt-%O<4BQdkq=&yD zKs3`}{RfQxM%GRoCEEP;?>8@{EB-J4htH6rC6KfPI4@a0_ylN-$;>`TK)l@C5FVd1 zZ_(-720f(6>VSGnouBuXbcXo&>>mc)oCdpdnFSY)dPa;JDcm74%oG!2ns9ewCKFrQ zh2IO{JLm3WF2(HbQ_~&_fG;fMH<@(SV6sG97e`PZ@p+9;s;!5KZUvTs;HzMM8?{9v zK7;^Ex9q?WYgo?t-FnVTUBLGJ&jf=hj;88Vm0Wg8A_B&)=Knq1#OrDx$y29P9-i3M4PyGTg zq{RkQ8Q)+=NVH;wh;)mTHm-QzwIFRT-!-irk2%IUZS_dB^re{iIV6BkU;$_j8qza? zR~Mz)4@2m%wntX}<595N*KH(?+5Z+0uBKfdd zAobS7vND!t@4_vxyPSiweOlglT<&1BK5A=>G+;fe2e3BP50%y40rbGm+m?%iti z^#>8OjOPPR$(kzW@RLoc4wJzhJs?G?=2EGpIXTWX@T6*`Yg8V-|C`AlJ7#cRRtv5{ z(3O^Mj>=!HDIaQxm19G(p?9<*n6wxr6J|GCsCmpmaClsHYx1GSMrvvbR z>z@5%lF_RX$?K_@Mh$$(C>iYbEI(cS4Tk* zt<9teGJyXnrx*W$=yPnr+B7HrX^!2wgqV>c%)J0s@D6$DpCLc|@@rOwN@o{m{{f=^ znL2Jsa4E^)BWiV=X}R7kM4l?c_|?lxc5a*!z7BtxwDP9KS8LRnpxBZK)}GjM+m75% zn-7o}XZ=Hu^kbutKT6La0v`_@_oL41ebF8ul7O_B6ApMx>?x&E@U%ZfQ3iDo2Smpw zfnKstr7iT+t`_=H9mc@BEyCiQsQZT$DhX3ErFbicAr*97Bufq1XBRud_Lha7bB*|c zsQ8~g=l&k~T%f3HDB*t&aLe0r)`$$(m54uo=!EFZ&yg|uGLg*;XzIDn@;ySfv)lN6 zwedg0pN{hHWJzL=N@8iMYN(diykIM{9AnN{kCw+PKC_Tmll)JwKOgP2V6Pe!xKU-< zI9kF}p#Jw}ufsFGJPcz4)Ps<@{tCj;_NENyAD3)Q79gUM=uEU9S1TxbSy39?B+*p% zzXDg_L7{#3VG(DF*PI=NQu=K6*CY5$&)BHlKKte;SpqjMid=VZDb$1u)uczdJco{OjTG)()2QalW*`1AJN6&)bw2F&4{oDonm zKt%Wtl@^+MhP#~xD1fBI;4e96k0rP5?%CrX zW_H3G0M%iA695>G&(k>t@!6j|r7eAnq9}dJ^t7rOCypTrCA-)w0-SIC7)4Q2*)9!3 z4~}iOwDJ!6AW0;c5*uJmk$#+jUdngn!oCH zEh--SGOzqWU)bwQ;E_eO2uKumwC>m3iV%XGfgrb=MHhB~qM9aNWa0EwR1xynrzBlu$0-Y_x%>KpbRhA&nUYHGSwdrktqm30B`Bw21dDa*p)AzsBe6Yg@7?6S?p9-ZBpGv88#LMQVZHA`;ird@RkYw&{y^2s7 ziagrusZW!zsn5u+$Yy3M0Y3z7Kd|q$YG*{~+>)qD)O)BXifMfl-3r+3Hg(xjNQjj>J{Cg5y3K7fq^~3$Y91h+HbK0juZE{*4 zTj1-sD{-1uNeW_n@wTZkADn-9XmC*QKCu^4W(TWqiwN%)E6_``v^>@6T?ziUSCwTQ z?DW4^W(1!}x<4N=MOW1Dn>s>X4X~J>Jj)pS)ZgjyA;66uQX~zi9*=kea$l13AUC?q zb$d4Ct1l}Mc`u@|54d_SQRs$u1ID%f1EXW#9dR#e8cqBSbQggU9lAGBoOp@j1!7Uy zdkWacM4KTOGaIP$cV9k33Ilt&#?Gsb519URuK=Lhza;E9NVr;`c|1E_g-}w>g>-S0 z5!QVos5VWYr7Kv&tJR%C@d^&S0owq$-&5{Ni6kH>`_zaRJY-CNv@Gm`SBNwH(#NMf zpPX$+xGkEUGsU-x%s1igFBb|F*w&e6zECy{xSYmI%&~H1G2UEJ&^Bz9V1Rjm-}~d5 zno)XGW5hAfxG>sCM`;^!ALywaSa_Zy8G}#4%3@eAxfxP;DdrVN1K@ojZ?FhaDR{@6upfx_Oh-uBXlgcCwq@j^_}wq@@~ zP{oN7@equ5O0y?|`Ev(Q%GEM|0b!j*HdHUt;`2;Mx%SRqA0HGRELtDd(n8d)Wlc!N zDN@{FskCI)t=%#|{$Z4P>IL8xXIbaA%pIioe!+FIJkv0Fu}{bxKzH+LZdhy7iK*?M zi0p`tliTM4!^oOCGs3K}`12xqEVKY^drLVO{H9UZv)R3Yp^qhO^gW|$p|7&vh4r2b z!O}ZL6P?-KG3?e+z+Kxy?Xk}ly|hbof{DCr?MWD^zhbTAtvmazS9|wx?Q+|DzR>(Y z$e6#Rm7&Cya)LweYTA5l z;PJoqIxI%NBbL*`*SqIAfvscs7dg+D?4q}N?6X>j_|Uq~84`Ig9p@h(gI9cI_bY8{ zk>OlR;_Ih$tt|HV& zt-Dw>oe zT*U*av0lm@^D`ymZA2rSB>?8P(>iwIrflTKEOy2cDT(H8&V9R!0Sc?&w4)q+I2M*`@yO!SQdDDR-d;EOOZ2~926{qLF=4W%|DEEtT((0b zPe;T9XfS^8OFy_F?oOpLQ%K{nBy86&Gsuq~;+G}tw`2UllB61~;^`tBjhJ||)%Lix z3VC4dSFul>EZxNfE1Bfx3bFmLBt;Y5*Du$r%GFG;$!y1Wtiaupk;VLnKGqh+Zu`Cv z+CzVsv)Fdtx%(%F=qCerI>6dj5VYzTT3_*(9r3MmrZF7v|IWs8HmJj8>LPe#a~B>s@_CU8 zqJpX%vTsjcDv_n)_R*YOO1eNo+{H0a7q+}3ra#X6pcuSg^ZPyF*R2(-;|-mk0$%M<1Kd z72P7BVnq~?#zuyH(u@i=4(lOGU?UOi9DRq`Q86k&s|O52!s$@Wff@xqspp3|eMY7r zIWX-O;j`kqf2jvQbCcwpkcxd-Yw)s>mU)b=5J%bS<1g`8M7UMnM0InXiABCY zccYuD_7c*2if4x|0#?3{~sxy^L6+HI4vHNtOi7Qy;ls!WAjC0g~6T%hy1yS zCKJF;-3mN@pluL$$8R9{fYDg6RjnaJPqXZSX~<9}!!uDfVyn1dAxCX?Jvs7+L|h)E zb?o%dIFh85TMe=f+d}j7&hG?_Bo`B&%eS{{qJhg)^>Bgr_&!iqrb~Va@?7f^c(m=! zizxE3%bV^B>Qk8y@To!pYS*10Jx`^yLU?#kaiuUGc*O@*g{~V|^HP>(Fz$}9j*uVu zyS|#X&2m{B8w_eQCch%-*?GM)3kp>ed6RS6P*PjU!lzPwWOWv630PAX0et1w8P4>6!bG z^Q>JXq^YQg^M%m1tH`IcpLw=VyKA8Lrj3+QG&lS&_;?aMX*tJE@ei+1MJJ8@LP-35 zRG}(YS&`=rg$o+J-#a|0Js$L)>iL=KNk>vd97%{{5DgVQZs%B$c;@o|)P5Wi_!TLf zKMA_M7k2Ji+PWfF=%2plnh?l;(5Wn<(qu#@R202IMW9=SK|a#1LoaU4#ke^rb_voA z^`u06+Bj>pbHW8g3Wvr%Svr>;UjC!*1?7wlU!)R$ZgfA1JDwJYJG4S6{lws7rE%I~$*4CvDyKC)dvsL+YXi^!QLHe-sHZcm&&~ zc3Xv7$P}`ne^$q>AGm3nWr~4B}0874Yi_3Qu|H*_qNTJu+bN;wsECpzCv(HN44^ z`px)!6ucWale_lfcANboA-s7qf`*^#!FpY!UheChF>d33I9DQeH-S4a-7b)2Ja z|F>o=w2-ghw%|FZ!xX0tnlH!oXSAwzQW?qkV?|8t03^qEn@j$?0N^C;gx>REr>xk( zT|txDz4Wjk!qZ{wEqydHdm&*P)3$D;2eTf&;-p0)fG7nHAbyvCuOLbJv`~@UFp4Q?B*C(|n+$eQwGjOn?ey2X`i)gwF&!Zzz&blCurlFK=5trv9S>`{< zjMh_B#+;wXe0X5T6R7`=MS88}p%!}`-}Fs_lRY7lO5;5*b^qfv1$5}_=pilZm^@cO z3kxu0ouB9;c>dAZCdWzefg2ddI=^}J^NRS49|HS`6pkF|<#)mz5Qr-$QAT7^xl_9v zHIXzs$x*I4!>B;EESyxzQST9E(J)z(faMNB@Ty27`F`0WT#^qeGu=Q960w8isqfsTpJ_i^QS)BuSe(Ay51IP!s1L^fkW{X?6>k%JAN*-H3MjS2 z?{uj14P{+iTFU z0I{tTAj&QhrDoB_jR@gpbGq4+&G`s|hf(fzwOy$Dol(zXpf7@6>`!)Ql6Vvo&ZuuP z)yU$kx3DQM0DENWn`hPVU(S_uuuGA`K)e4)Hgc1I0~%nve46!;BKpXC5`=f7>Sxj) zG8fmYWlKG)+@DHcVNu|TD&kfoV`q%oAqrpWzD#7z^Jeww381*GpT$cDyn{}Teu_}+ z+^`&b>#5uMAv!l42$f_R7XH-$r0wc}e~QDF((In?QWLlKuoN6Tq|?{Iu!pUX3j#Y- z*>wSSM-7Z$3j6}uR+3@$^1F^8)d+T}zL&&!ZxW3|74ptUon#^9g zz-f+AD*ikGz&zgvK|4)E)xvG}IWRXDbRL`lso!Pc2+>`FI0;i*#fNGa~9>>F9KXzD#yI>L-EwLj&SPzM_@3sXQw3-U56;+ zqi)H)2q$H8n+XQA!KWkt>^d_*z}eOl4WeDR?s7!%I%=x|z&U+dp+jW~&6We-p~xc( zzd!@lzBL1i0G_YzzN#5(iue8PZJ50CG3IF+(<1LSUomXvgK}&K9m?s(V-e}Gs7^Mb6-z3u5Zdfa zQ*x4#VzVWW`{V%h&98fK3%7K5?mmI1sN@CfehNGiv;-}d4K(v0I`^DzfF@G)A($9L zUNU^6&ejgJn|qccc{n?q`UV~_M2c5OY^VHnwZQwp^R6Yzc`91Mc|d{|WBl5I*5TZ5 zh{+1Ijyi_Z0nsD8b4KkCvF(?4(Wgc!=yw-Bq^jB$TJ}HZe^8r3NnaY%j^S>d_Zfx*szG;#)nwm`6nbpl_^tgd5K)NE zhq|~lhmArr-A#q=s_Ze)(7`KfpxaU)0){L@zC>-vcf+qXiVt`aKpR9)smPe4?-}+bp?o)2)-lt&2K9 z0paE)^)-^m&ZESF;_~(UK1>O&aNpU;HfCkTZmniBHWMn@dA^E#q_d(4@N7n%NBEHy zi#SNG2IwpG0ULKkHlrP$iXLoC6$j7$oxsI}kuDye8H3OeMWNbCA6JjE1oO8yRd@ug zZUgB8sjQ@)6yBZ%H(7qpS#8K0%Xsv+!5+nO%~X!T8ku(91|3wC6?jezPoLn!{eDG{ z*ty<|h7RF5Ak5U0n6B@kRWt?P{omrudz`4&Lg2}nCliMt9#+F=u=F91a`KUSd5_O@ z%P(j$N;b_FGnDrB1k31N#m&=dSP>zVUGP@K;cZNkvzytt?AGR9j{f#dyC%wi`EwPD zSL7uT=EO|8e}H{GgGtKhAcQt;e@s1j>)a%_o#n<6`JsB0V zNqdyk^46Z<);DB?SUi%Ds@R3y8hdyF?|Xc(VGk;bp?&elh*)KTOJ#@P6U>n2iYHXQ74a&@ zPw!is*hCEJ^I8^o^>FH8JKTpIzv6cbF|LZb3&!)N0ZK=dlJ431PK)1PjWWf=10?r& z4s07o6MP>gPSrHGY;a1Q(JEFEP$!V_oo54NG}^uHb!nfO@05{0#7Upedat(b!BKnD z$yyF%si;2Tzs;I@{2`MVquC=rSS2pav-3k}#Hy_?E_jIa0oL9(Zq@b+^z3SgMy|6V zDlYraN%M~7)n{R(YEh&LN%)Hx6&l;>Rn)G`Yb^44bTn?h zV2Q_mE%mavlbXu(;_{zypVM9F-0uH;Vzu=K~eHnSn>;Lhlbd1P#m*qd!IP?#(Mpu z@T$E!B{_%PzVU^;_T4I=gV`1B`IlniTO>);)hGu@*9tH*z;D=;k#{vwy6*{faVHQ& z*i4)lMBhkIM~=AcECHTj~ z=d>5n5g?^uuqt+&byqvl2p|7f8C8AYh@WWJuh3+Zli zmv0XoNqCx?>C%17qp}hc)aMYRQ3Xvr`wBV20&v{e3pPPx7pTdR6I~ps#d8&Vu!!Z% zryG4DO*66^(mD<^-StE&#K1LCnez*w!w~;;mnIsl9-`hZLdIwS#|Dj)#u<(JRgvtR zm>)vE2NR;0%5l(P&>_baW|FL~x|Blt)L*xJ4Vw8mf17I@e?JhxB;hG^GM_S-O$UX- zA?okNic90fKh&NF zmQ1hX_&mPE$`SP8^*wTQ8?1;VQ-QKqckyoTJ$QT0O9?FrrHHvm6y7+0;QnRtzNKiK zGGWSHVku_lAi{1ywWCX3BJU1%~ID1=@yJ=_nC!zqs`--3=- zg-NkKJgfY>cjP4BV5RNh z4HYA@k=Cp|A4yx@3@`PGKkTtVbsnC2lN} zi~ZOQAtb?o!;_}d-k2)ih;=3TTK-~Xg{i#vXwlX8t9d-m>W^}a+cO;oX`JfGJq;|i zQ}Cp~5qlQ!mf0Dx{jkv=+{Opaw*|mm-t!+qj_=K__YbmH1FNPNrvI%l&19hEGv4v) zuNt{M@ORh}l4us1K$@3FC6(A6g@+hapVd|33vHTN(|J}NqJ;wUNLKAlnO<{77uRSQpOqE-iJ;#P<%`cq;{V_>GAedoXS(dEvI zdb1F|kK7dQea92nm(0%Qve`*5a#q-7^^TUy6rhJu!YpB2VL)liqALAG*3GzCjP-GWkFh!?Hg4#w+=+)TmIrL;MVNLZ(s|p|TL!NnA|E1u?DrEyz z(a9HV<&fW!oo&WG{CN~nPVR5~D#Kp;W3x5sQL!JOw>iwi*m%GBInOiw`A+rs1@A4$ zP}Y>=rH=jW9~eIx{DKMXSH3loi2GnGq7}z%jmJj1ult8(f3YN3PUISPA=?ridYhgS z-PnaJpULK)zb4WD=CV^;j%6Z7xJGv}Hv{U%B<1?1zEvaQ4%?f~Lq1i&}T^iqlnj%_;SkD>d=>shTkQ@iwQK z>{O~NC*-M3=GZG;S;If0m^&gDXPV9zKCA4JwNp1Vf|_A+Hz-(&c5&uj&?PzWJ@PFa zg>E*WhJ8J;o_4H=_X!}wjeW;_j^;uulI0x>G5^V)$>S3oX$%3QVN_d8U;85_&ZGq{ z^yEG-qBe4KW6mMBhm11xA=aGk((UyUliZuR!e=3zG9MLpvsr*OmS4j5aQrw>S@)Gj7(jLupb_TUI3DGK9bT*K{syJThCD z$F_My^NRzQEmmT}J;YX}tKN~_2>ec_*VBqM2V>tKF!?%qt$|+0lXLb!MMCn5^7CGQ zuw6#R|GpU49l9qf2`Hvt+x9clAHel4LsECumN{(AaP^nerYe+xi+uqr$kOk`tAvQf zK!Qbvrry9e-z-SNsX*+6HuQv6YOnYBhIyxWu@6tCsS=~`fo`O~fd!qr7t0AQcNEsy z((S-1GO8{2^rE!hZP^+|HB}CCt%uD@2&Y%X=zSDIUnYNh^l32TgIYJBJY{^!C&NSF z*UR2lLIeO1f0H()E9-{ZVSmDaa^V{B+au;xEK zpp6*2MQ7r#lRXmr4Vq%~fDzawAu)g(bXEz`x`Wr+;uzlBJO{7^r=3)NIw}9nJ%8Ww z!8_l6Hb|OrU$SP(YI*(i?;tMro(>K8V=mR5yEh##dlvnxvJNkQZcvF$GuhL_JPl)3 zroAnS1z(U(-MGoh;XPzovL$wa>y^u;LwfnCRXq=@eQfY*L@W3g=uHN}1mkw+ID_-= zRmqSpA7{WSIgV%S3fh7@8}KxEy=CBA(z02C0a%keZSo!Ynn|e?+8@>Tei5O+^MVZ<@hDGE2b_YY9M~UiVId{MOOkyN&HQuI<5?iuu1Pqb_mMw?! z9mdtpoW2yc$d84nch0~0CV;y8DV&39FJ1}ly_{?eOd}QNdj*FR;-r$!)mdT2?~&Q+ zT}TYJ5}P~aVHNm;fA+pS_!Yi9?03<4zQyo1n^cAV{BEAt%-zpRd{aZPo|@Y>Up29w zT?7n`$9+5na19HEQ1iT03Hn3~U}nApTLehDs>_(EI=Av6ENgbv&#P{*H?R`ICD}yR z-(``q^1~()YLkUjJXJz0*vl%jBJ&cSNg)6TI`>t*#NzIeqqijL(UY!`;d|Y zYqMiHd+Vc|GiVaA@n`*zoWx|M)LmKRz2^JE9rZ2Ed5h|r@`gF(;Pq(n@{1d7h6D+Z zA~it+0e)w})mrdQALaF_y%i|YSnS!%gW<~lxBHZS#`3fk=@M@6b~9^KW{A3VMoX4$ zO@{5zvkSj4CMY#G*N;hjV{A(lt|7$o+;Za22)&o%Z}EwdM0%IE*)HnsD`Vr1@3jB4 z2He3m=vFBHe>A;iSQG5~KfKYMN~e@cgGdOB5>S!u4rvgO&Qa2-NJvXaN_UJ#>24U^ zH5yhA_xJaI-tFae?AWgB{N$;2jh(e(!o29}_V$!VMen@~JHn*!H4%Ud)B5mFd&OO5 zFk@vHR;S2Iw`iZ+bMDdkArM8-6a{L)nqY)p4qDoDLil7Y&P$_V%=5pW5uXeTUY@Qz zhFhqwTrH2Z^PgyK%sRSI6q|Fq+jvXu*mBjA#v=z~1b=rGI~9Ui+gte)>#;RJ=6tXQ z>=0i0qqrb7{?J`2G%3>+J+mU79V&AtM>c-tnjx*>{LO zeQj)cDu~H{ans8BkM0?C8fCd#UqeDozDey>ZM5s5~v*X`|BpSpSoZFYQc|(9n|J%#M!=8H1^d2 z&9FUa{cNqT@j^zD$|m`Av+{d~J^o*-Daj_PZ^m~}%yab+0A(<#&|EX*{d2Dg{Pe5j z$p=Ab2(^gAj%}+6>u|9!)FUDT`jrujDNJS%;6uc4=J_jLg%9IdRfGIi#%EppbzftU2* zX&=tqz+((dPvdUPtCN<6`xmaW70bd z4a_o6x`~W-M%3Gnmyo2;O}pu}lHcoJPB;CwK4eL1cZ}uy#<_(-2$y1z@fYMl~vP_tKTCbL5?y5n0NnhVJe1H zC#F-1^I98t)^dRr>mi>1n1vr(2=BecbX~%UgU!s3hMRC>4>_$|;;4G?MBq$uAwX*{ zT!C>scp;-)XIb&e^W!Jy9er&^PoKL4h(p%diDjsL+n8TMV-x`gM)8b>En*~O1L+pT zD*gd%fhU+H1~vCdm1{qajty_TLv|oolrp^YXB%jC(>|_XdKOANkIS0}J04#lu6~o6{u}SD``t zS2+J2GM*E~032qCLOzXceflj+gzyb52J5}8!<$TIfkftHJ|ckljOsm>{1Y6R;@9uyeWY6jcMF!3bWIv;{6Q z^XOP~kNu8Va3*Gt+>b)({R}VLWEEdKH!^;yMGH8FEz&2OpR}x{ z(t@yr7^qd7&&}e#KeuwKl;|sgA`@dZUMJd=v)q;QvuFo}rd+=<*I-98rN(?Rxkh!P z>gk+VyZf7Sd@VkWy7pc3;?d%jC-sTenUlRClaQ>xBT_aJ&Q7x=h)J@g+5C1I(>yzm zBjc`RjQOb>OHAX-3;C|N&FrHwJ1ZtqyOyU|d*3>?V=?iXDU}&xYdL&ZBcFTZcw_NsP01#T$i4y|0Z3!cX2>Rc~0wJs;^wCIUzo|%JRSJrG zaefKSXN0)Pm>+z+N#AA+&X4Tbj@-H<;%FS{Q3N&bah>bZ0&`y;ZfsR3B7Cm4)^Njx zyzi*2%y*R?B^qdr7W?ZZ3U4~q_HMpUVB`^N&2cUzJ_(q!2H*+u_M%r-g$=8rQB&>VO>|ASsBuC`^-l~aS2o!)VLDL%7WQt-;f3MC-M<_;DVj` zY1mE}zEL#2o&G;2f;v=&;=Sy<7@6+^a_`Fw108_MJns-}FG%sr9=e`!Aj@47XX^|= zMqK!>E8)ym6KY|;0(@P+cphr{*3h&lN;}{UV*Ys1rg17~#5J>S!Q~kY3Vid%U9bQf z9ol?|I&IOdrTv4?L)p3gIq33>jnfpd@oRg61uXm?;t}P{-#;(j*I9Df{lpn9oYF1( z!7O|$dlhK|pu?E_5}S{LgeK^evO0Yu_F{3B-YjX3yrR7Mm#${1C3>kUf}z;m1+#we zs%%G_crKbQQEv^_j6QU`RZ<130D5VIQUH#8hAVJbYYQDPuIm669$$B>J=mI`{ml z##-#~sS%ZVU&TaYQbui`vcpx3b=~0lo2n3qzymcAkkk0o4Gkiw=wCOxB;rmQ z7hd~+SEDg07KX)Zya*q%_a93}Vnt$Ula-|a_Y_xRqFhJ82T@JeVc^`oxaD`6u!|kP`bs)VQMB}7s&0)Ar4Yagg;XNt!VcBQ? zEp-!oy48kKr45_)(uy!--A31Be0ZhU!xMXw1GD!d#+NWDT>&DXoLs~!`uJwC9htC5 zWtYW@guSm6=(S$-n=`&f!D$SM!4G7pu0BCVCVgzSQd)T->|FplC4~D$H zU-4HlX~2GS?S`Pfi}$cML?M=#G9)^w?S?L#c<<3|O!>ZZ-7tlcbjyEDmGhikFX#wA zOEFw9Ib&9^J_K5w7x8ej1*`i5C^j?q%qk`LO^1dQz*7|K&R@2U)e=mjJT2_l|DESy zK|=?CmA4`-=pT(>dd@E9%Xa28QScl0Mmqz@`_DSL{1@ay;I* zjRM~yK5UOC{Vl=IO9mAo{W#FO;~7rZs%n1@$nN?^Tq~z%hp}aEul{>W*Ph@xDOi5| ziot&$c5A4BWaSfl;xJBZ`eWU@s7l);y45yYiD{k#mF%i0fv1}bqcD~&+#@9!3cD>| z<99oH1{GpDXv#~_zpc`_G?NE#BW(#~NUgxKS61g$^R{Skd@D$9CI=3WOtR>6Of={P zn2!VrPRpu@we9fun1&ri_xH{CXt-JTAsE={7=^f=l znSiHL$h^_f_;#pS0kU1H`Q;s0tyJ_hcWi>Hgg7tlg$(hgvh-k>3iG=wmOGPi{e>I5 z35sQ<*Z(F(y#f2<544)P(4ggV%+TM|4UDE~) zH8rp^XpZp$mbhuUR5Dct0vy{jMbrY`z<#COV`_^+HOogao)2I+7X`ZYlSaS)NA}$D zebqk}vI^Xs97n<)Cw$>cp*O^u5idTnJ58yi7dMvbn_Pv+aXG;Tl--5&mB~o;Y;3? zx|l{QiuE&M#_Z!)KNZ$LnP(~$ykYzE!PJ2^X02!4ox>=qKhp3@cj^I!xQ*hDM&3c& z`tPG2`MYXxd2;~mXu6vknk*GbQuY6L0URO2XtyvwpbW3lfOA`SozheYIK%w!&2Yan z`9}RXDl$|_-`TSkDDf9l%pf+rfSWN&s$Wd+#JlurtJE;eHglMk5K{R26q{d()HWdk zfYf^Dw{Ko!kibRfK@^t`TwOCSp}yt9&gCT4;UAj&eAW#Ev`lB<>ceSQKO?GGkJFHt zs<>ihs;fenFw&&ZeKXm+alZhUaBdu90l)%I;oIP+)#IL|q$@;K6^i8%ra}My*ylPA zzMH|N|Jqp4CL>h}>fBb0-f!4rL3J!PoSxO)AgP;~*R`R&Xrazhg>ZIe!j4@%=jV15 zlEt3Imp>0;?{}?fx17BVg4$H5!MLpJDRV843xuO3`5Gnvla^`8)mqza((fYn)OFy&~qH5KucZX>Sh&cyVSQn z`7*(aVv;K%U_j4I-VMq?g9rKbqJiDq@?;)K8cWKC=Zx3+ERSi^141a^3p|oxa zrNU{eSt<{~lCgWf3gbu4vm$_Ee}(_>EO|mp^5xw#F_zgoOWA?E#a((PS+Td$YX+-!hZmR3+FQrd)Rcozus~PBxyL zkksRqV+Zax?KZ8O(^!(qykU@5OTUXBriluXlYoF}Sse&zaE{pzC;fuc&$^$N7aE1t z71o1w0$*?Mk8Idqf8W&(CjW_Nm9A_QAb-pC9Z!TvjA3GKvU+KaPS0qIJgKWynpq3V zMrf9)m9*VT?yr%Bko|ft!X#7`-4m+;a4J{10Uiw^pb9y%4l{<&hxm3#F(}wFH z!NJ#yXJfa|BrV-o^Q%O_xA!0kdSIV4CI2$^PdafWM<1^Fm3iICQ`!F^VxvbUI#;!? zhBc+`rWYs>5+Yo3PC(Vsw?mDV2f$I-wPs?57e0C_Q53i zXhBVIJy82rNu(2k-Q5^Q-jw;c8zMDw*2A!8WRAWUkaXvb2EQI}r3ZifY~@i6w3=Y; z0qK-u6R+>TgVgZK6xblAdua6Yf1Ms+*d``9F`HjLGF_PRZy9hN(Q(Ai-OXI|F5~2k z7eb@~$!(Tt)lNQi8*_?wtMh`XI}b{cE+`}lHC#Hf9)B{`~Rko(DKV_ZZ%UQRJip+tbk`0rFyYy+5+ zAC`|6BFNglVwLt?YclH%)L^bWOn9tbW<`2ep~(qjm6R!@-z=A%cH{XdNZdZ;*03Z$ zx*zxi0y5WK2CMSDR@wfOQ+)VY07B%M;SR#hnwB!0!F{r1iezJk5^3VWbRGi0gk%&b z7~cYxL3N@98&<`K#2SBOEyH3=aH`qj#__UT^+y)SlTsT$3N9bf^CQ% z7+v@aj=S`nX^LUT-35KR^6d$+=t}%jc5zF~CjW|kv?SS(vDd&ZEG~Akn-w#gVVj={M%@ z#@3jwXIqk|7nq}p0~BRYNX$KbbfrZk89WUGOBH5F75NJQR@k6nJ|yoTZis;$B3ngn ze|My(LXI}+MV5!?7@x@a!Q`Ki2Lg;q#XIJ?rI7DaD0Q|1D0@n_C?lb`_h+U%s<&T^ zx!70+8?7bd9zllLUzEF8>Q(n;A5pf7B&mvqdfaZrqxT8 zbdaol>uWZU4AetjC2`jRH;)7Z)((lCNk1^`5!jt(0MT}4m6_d_Qp2Tf<;t5{6hoW0 z8X`*0`cd8&DsNQ9p7yv^l0*DdmjVX7T?QISZ?0}>RYjBzXK1eIg>lbV-a!e*y&f^2 zQ8!@X8<;qxswjx}*6JkJ=X68#b7x$r_CZtp(B0)(nKK{zmlu@?P!u@o4EyTW4ZtP| zb*x#kEAS=N!j<$jR=Cf22Wk?w_91dO??YsYbo!fPH#JM?&J7zgaKES)>7D7TJlZTa z^Zq(V)xi?M6oW_!$*loL$)7v#CxuvFo!mk;13#qWxOb{4&^%eEhzn*leB$0HI7Vwm z=oG;-f#<42<684`#-P)p`6Dv(>H}%XCy4>|3g)da*3UFPb=!Ll6q;~dlfamhmS6C< zLrCknax`!}7*hv{h31vyC)(SZ5;aI}l;{1#H$Tvt-nwj|o%;SDdgZWRambpv zW_F9a@neugqa(PvZ!@D`oUi{dyU--0itfnTl56*WbTz$=qFs+JK(gP#4B?<2HJD0^ z`Rym$lsS)uhaxYn+j9~O7iug^SwA56tJsjwE5@cCYSAA%f2p2mbMgIT*b5s*I+?3PR($x7)iGr2!}EQ7xb zM8T*Tw~q|FKT=WtG!J21Sg^z)6vhQ3Mni-cV*#)_abvYZ@zN^;oIV<-MjSP&;lAFi|IL1@oz6`a@lTfS2QCfYyvjMiDN*P;$?mxR# z+lCNeD$2QlCe^aN%#{UsR$l%~~y-(lt7j?P#JXX{2dL%oVtGgqUNihC?;n^37v;B*q+fyrwj(Grz^lbqc_y6))gZ@e2 z5-q!*BMFas?7Dt>YpcT3US-W;_KaDbv?do(sa9K)qiNg zWxIxtWZ%Gt{$6-Bw|H;E$7|NmWR}bYE)G~SD?~S{Whm*mcxUZz;#5@;b_AuRZt;j6 z9&ZDkwSj={iU!ZYWNDkv76e-C5>H-|l=^g0V^rve*gky5%MK2#&$Pv=p^Q$uvcfhR z3z{#l<#z`Sw0U|zp2zR#UTX*dC8w&6H|9f;(l*FO`AKL8@*7$R zFhm8Ef2WL|lFAuc;fkb4k^^4UM!yS{yOUSRWyuE7FzF?d(J*(fON3-Jm=ldRg$$Ay zlD?_t6fkUguhD9fTK)>ox4zgl)JY9uk2`Tmw-bSCXGNGxyKsiNU@lx_(VgTNIs<6~ zUMG%ArrQqOdpWh>ke~e4I*#z!&c#T?&cg7dsjoaIizxW{y3x^>(q?P!T zplzq!wmSw%^A5Hb%d5)1xP>^A^~8XM5T74z+=U%}CxvK8HN#~+TkA}CQxIxi=WRNk z@I6-5&$UZR@&LzmdM`*M8kj7s!bSYFLBd!4S{nUX2MTA4Lw4f@`y3=D zU#O~hT+#F+c89q-@1|=2BH^e4$#av>67?oxlOC`3>DDeMKnsTuw*8itZHe$#|2l=hSGlLxhtHQl zlkN=)f>1AD{67I-uSC@r?i^7q7ijUgF{_Vle8dEk{N3XYILc36cL^HlGxhv^@PWr3 zwk?B7r5V?%n64AbY3X>+xyq(pCip>vx?kzZN(Ace!VB7n;6k1%M?Yhf`{wN^?V78$ z@m&L>UOaonh>`vrlL_Xez#M+4vZCbBJ2;H<5Jek3ZGHXk7R1G_+C*%Daa_?LiAd$ps+DA322^drEW5i`y9;9`;E`WrX|bf=xK*^v|K zFj-+2yf+D!N*FNi7CY+2+V@xCyyh9i>=C1LatqX?0gjselpY2$fjfhotkvW2{fB0)RfZ z?opfCrS&#j{}a#D#`{tr*&HeZi{mO5r>n#dKyBcNrh{kJ(2yIoS$8#CSe{jUKSKPU zD~?H4hUn1Sr9_x1hnec!T1wftM;X7=Q2l*>??q=Hg(-fi;uuNtH~NTh(i`?P9A%I< zQ;v>*cvd)dU((>W6PX#P$*G=qK40jky{8N>%ou|qa{@p=G9@kw#S-{9Yq5>gNKQ@3 znX~-<+2cw_1BO8=z}Szpb3F+v&E6~rr;(=&XGA!Wf7NW1$img1#E?33Q5}boyFNNO zsY2Q60s8G$hn@4F5}fZ=JP69j^D5TRQk&UjxnYZ*_Ru~E+23}|y9l~VVcjzVULWC@ zS1*?}GO{{Y1;a{g&~N;91OUNjS*UN_-yAjsbC>X|hTcXtnJTVY8Vif94q0@3auO#= zF&{p^sK=egBV1XAS{)7TuUj+(q6v?s`N{=}f|IeHe}iYn<-Z|AzylO^|IyG0L)W@~ zK~zFC$R36+#j*1&=v44H4y_5q)a8a4?X6l7VkTG_dZ^7Qcl47@5G^30YqUZ7@uG9YISwN+2#-nCIPA3Ic`HYnNL;TLU-H-Q&Y$V-eOu|RX84V`-FDk z@diti8XmK(M2ncgL#nt*7-+m5VMLz84JGB1631Mwi2R#pUG}vqm;{?8SBb!#_s*{I z2q-KEO!yIi<8?iF=dy);^;S(+>@wtY^RWQ5;`S%sR_d_O38MY8X)D*xP6J;6F3bA- zLW?&wMo?E;OS_lB^IzwNrsMVb(rKio-GfV?Uzph@MQ3Yqv0eIMLMtc_fFXb0+;0l(p+8{ToF?KOzSb z?!AhM7hITmYBiOS++&iFpSe!fY~P_wW-?vK;efZcYVC6{ZK`u7CBsIMep%b~*MCbK zRw97{OCil`<%iCNsPC4fEKz86w5@}y*_V8oOn zPie@Y0LJs0-NqR6T0m8B(~hC&p8OxFE5=d(XG?wVam#y4KI$irf}KiC{TfIrN@AYw zzJOP127xO8;3S;@gp>*@4qK1V=vaeuWnDARaSC)99gzw+fO~j~9DndP3eUGwpahu7 z-v_zVG~mUy#ij}WE(HMx4+fbh;1hr+6N%=c*?JSvEWNvxUA~Bcq{VfepgA%83s?|n zyxaD(J8=5jw@Vo(n1>{s+WCnk-Eb?>=f5~&wnULzLHvPvagR6f_3kcWQeAcGYht<-?S1HXWjNC&{wp%qsWK=0~yqruNsQzviG@i~0qq zcr^11J@o=k=xf-@rA~@0IySY^CojF&i{$2kj=~pqT=4Xow-`~@$EcQia8r8kHFHB=j)f?ux zG5P9~Sb%(u1yO?APoh_rAXI3nO|=i`9D=+)vpu#cCB^@FkGkMMApTt=VYp`X2lKB~ z(kTlEvfGi@L6-(84l@~t9mCsFyDWafAUjXiL_-AS6Hi61&acsHYE{A`zk-KK4@r|ZRH)!T zh?Ao}<7K`cfzJBSBT8@LEksLdd$2SPxm8BLf6~GjVQ9+$pMXl=!nXut&RziO0!HjU zihmdH?JxTKe7pf#!%dFWY2DnUTb9Ty@JB?&VBpntC{TU;{B*;6wp%PUU*uV5zu5ev zlI6}L57a?1Ss4%q0}IjS!j030kd3JBjk&ZIyX*rBGz^ z@72+wtgrO*37YLE0cJDZ5Bnm|2!!oFc2uH?LPm+4Nob=cb!q73ADk3Hi&!SijrVZgYIN7{!9)%t7Z9$BV0JMJV6*P6@Sf2e4SpGgGE88%6seY92HWz z@q{xNUSy5eEGj_*ppi9_8LIo;qR8RbCCq+zdk&ZMB264cMUc^v>5;N<OWjK_8wdGYWD&jnkUGZ z%M!gTw>HPhw|T!=AppSZwO(M)r892Neawpnk|3L+zo*=HwVM_&F+~J0p2ayj>lA80 zI+ft8Zp4b%Tb`8ydo+*IzviAjpw2ZhE0$)OCo;Ohhza^(lau5`d}-gh+yCT zGl(`UFm12U4Lp-UbWm$m>iEp-A zl}=Do3vEBR{AhZ~>onDvADDQs=PBMf(P-e92zcy+2#{7GyrNoQb^r+v-PxqkNS_v{ zf(gbXzPhy#gto>tNE0a%V@1T1&?S$aX9!CFd*LFmx6^vTv_@d1LOf%-AmBDSc)Qig zKj7L+lZ2o2r_|d+c{kAW?p7ZiM9B$I=AWB^$k|m<c%H6?b?I&NJVuaLNrd@6#l`Ym4SZi0b(Z{{5r11EeQM$FJGHWz5heL`OnoT8CiqL-H7Y5_;hv!wFyEv`HTybTqvi|A z2a3>loU(}>lgqeSrU^KYekT`01?IZv&p-Z<9;V039`?W2?&XT-MckcP{QUz${GwZ7NqBliXY+WNJ|rVvZ{YgW zakTC=G^64e&UMOD1UAcF-EfPd#G_s3pv=ss)M*%{QTT2dy>rXb7gj1~OkVNJ#Bo!hSLOp?oJ{nz{WjjDL*FWrXR=J}prW}LPdJ5w zAX<|Ik6CmqIVkPb+sZa&l-Z8D#^HDn7?A~KLHrXh0@;*^WyLoSEtslxQ4W2*A1M(F zj2gs|sf;Id2E5A6bU@O-0}Jn3EiC6!Ya_S(&!wwq8%*DL5+;^tzDIrxt|V`zaV3fnpc$o4JfKYn z1|FsUc{*B=MjN3X^8h!gpoIj92&&3yMI1|8(VTF>T*)ytx>-=zoL29NV*wXhjt5Kk zRp*@`d364%_9F}Yv7ItW4062meaPF_1&GBU zlkMNclEnPbubYuOzhv>otS{NV*Q>SLG*i-6spDQ%Hi6@{g>LSqCt3m}%I5VoH&nZu zpZ-UXcu6tqjR95;>yAOziq*%G8W0un`ZHQgH$*O#A@6+q?^k^K_{myRdL?~?Pc$~c z5en$=cgHkGJ;Ke4Jf)jHpjiak)vN9SZ6jJXo@R9sLoTz;K!%dKsJ=Nv7S<8#7BPZD z$~>F?i@lx~%gU^9%BGmLV5u|NQu$|aB+&7bALk%f+DO-qM#XxFAj9OgqG!;m#^gIv z$=XDti1lxYRBf}X{i-ytrn@ryZ*a+!3?)$_ND!yLHry9jK-%Er!)CPV+eEnDjVYhN=V3d*EWFNlD*xAJ7FVsj^9 z1r9!xHh2+4DR#GtNp&w-k9(d>uIKt^|9JM`*RDg*uy1$r1~HA{J;C%*tC!|k9~4kP zifprs&%+Ov65rKVwx$*Jj}-7v0HDd=yi8v^p@wV1gyM30i0q^g&+x2Jjb}6|bOkd? z&~IMHj^BGwv%v-7(!L^8NJk=V5)fQ=_KhEz3P1<#of_C!N>pYh-scC}@{sdei8I-1 z8)@Z?gRGcS5E4G0O9Lvxz5Xl7vkKZ_eWs$LkAy@}V-;?(bno=_tnwt2Ak?xaMT(QOf<>4w3?&M90-`UVJ0LIzzEHMtOMjiB7QvY|1!Vd z!wFa}PF;E-^SlTsGhfyrJ%^6mR}-J3**lU}Dtxv+sTdqpjQd?)QMvRC+uXzyG(Uls zLb+_17+IM-?bLC*33qgrm*S6kC0iI6?HdqIpLXDd-9GOTLG?Ol(mEsd-sFMz>wh_` z4{uIs%U4kgkHRp`|AgVD$LacDpAmHMmIfS7O}oZ=mpM>%sIXpRy3U1CAv0pl*IZ&Y z1Skhf9;$H$|1iX^3pRNBiGHW*p)pNs?B(OmtZprEzTi_E- zw7Vmk0)2|)=M56~Jjz-6uc0CnD+IAb?DmW_nyqN9W}Gop`PbiO2Lweg7hQ|iYPOIv zYIP6fb5%m;9|eMG#mSu$ca!T255t#VN+II88+e7Q^MN@gX7wg+=ya4Sve;RrEXj5n4w~lZti0HZOFPL8=iYR4eCD40YCeW3zk7|`U~LKy9<6=V-Wm&OX8v< zx?6H4f90Z)1`NuKKNC#{fec@cMgnYz1}B5IPh6oNcP(i#zs`VcF`i_n3M~xxg9)3G?TnE1Tb{`^NylnNA&Ol;?AzqDNg4toFZ`mBYg4bSu#|^2w%W- z(&dot_oZw8cwX_7qo7!|FDF83tvS9a-)~NwVVE^e^N-~gE}Gwc2f4$=OAuCnFx$iG zb17-U(cR{Tj3laMzRW~@*W@@1I089T0wlT?N?mS0`B~c?0u7tm?Oy2@z?_?JX3m+P z*4EhNh6@m6HEjB8_;=SzohRf&^%xD+$F;*C|1Lq{2i@dcHBZ;oC|gf=LpH({{rrWu zB8ojvYIm&-_YGA4AF(EmCl)1fdn&VDuD;Rl7)|piz6fW#%|{OK=B`N&sz&UBaUlQ= zS~L_EF}`P6Oa>}V!VC2T(oCU#ec5pXo4P6D_j0Ga*uLDVs++2ss)@7gQT&$J2Mt8^ zFPLe-K;iq~YNlQQP2DXd3&VWXiKBAa-2C!?mWHlJGraNV#lE<<;8(1tS|SqBXmfxJ zA_5ys1K<(>H0$Qpo-so~0qVretL2K3kph5SJHU*xBJM2HH-r%x2rlW35u#o3(-GmM z9~htFTP9C!|GSS|Q~P;z55@BZZIM;l!pQKbzQ~35J0|#dPh%Ho9a^}o8ii!Hm_Mcy zm;+q%MElsZ@%H>8Q}j7yT9d*}u(?HD@p>MKC;{0NmU61o95k)t#`O37%1mq*wRd|g4?P7s36GuH;uScgE4u}=rELvh& zw_>95!4Miaddgzoavpb-K8SB|h)X#v$V7#(0Q_A~evwxkYn4^-G7LXY5rABa43Yjc zJVbK1Au9IEm3|nu9Otf7?SN>a8D$o{{i$1amb>w~4=wG59xr;B1n7}&TsCdzpy~Xx z|CopMgv)Q_R+07kplTnBUU>l@9&EmDgX8zC_;TF%g!2S|@9!|mt6$sY5I)H_>Ajs# z`-g?8$TiBKNOW-Yf(yVytM{SsKnSo~GIMJn{T}fc|Jfjlf8vZ|M{iD4=QegzoYV?$ z){XzkB`RJCTzlz`)Zhk&J$t2=NvDkH^}PBNETB0mF@91O#LpM&xTN2SeTsa^xu3?( zz54*tH$u~?0LWp?8(`WqI%D-hTY+$4XJe;9rCFkD3PXdcBcapF%Qde~SS;UJOFFa& zD)&E(SUt^G`lVaWtkW*Yw2kKpuzom0)ul5^0h-`1b!iZ-lX%_=N<_~_ncVL&fM1-D zo>>AVb#CDFxFEq~_T8oWzkfL|hxh~XLyH>k*J|~3mmucfj0EtX!*YADCIERGukeCs zF|p|#xmjvXxc@v5Hng?1{D%^&g1g@SdQSG$Od`3Riq)Q~vq3>k;7x}r-M=6;Oxs5n z*x$6fH099hD%%o!Ey)qtn&)$dH|c?hHZr*fMw+-KjAe|b=P+pKdGcSq_jKRD>J7SM zB7VgqTC~6O!^sQX5I=2)%s4zG1pjC%(*ih*DQsPYV%>SsRV-I}Y*fu`&q?vY@u;tb zpx-GzD)%i;lbO}g)KvOdf;1zf?0pWBB@VGWXu48X`rn~qIzwtWQ;rz3NWmy71*Ng~ z;$d(9x-Y{cjAs2@3dVLH(*K31^^BsT7IP-t@~)Ul-NV<`{{g78-!krvEejEC>JE{6 z^F-#qAMiAu{sO`>&(apO%5oQaJ4zn7wrrK#Y*eBoz=~rVr%H1mwFVi#TVw0|C}t6G zWbN^8`%N+9GAr`8;J>*cShfn^pqE?1-P9GrnXg?V1eycQhi03ZJv=?1k3qE_J1*F@ zD&$V4!7{A1%=BUdAXY5E?CYAKxJvT@*yu05e@!1hnA}<{xMEYPwNbjKV_p!ea+Fz| zW`}Os*olo+TL=Np_5%vPT{97%a_ewy2|l^hfA-n;9q6^T?fyf91yQiS{Aw=3v#-O( z7^bskl}#xIOB#OERrnCT2ylXTC6X4!x0a}JM(wyC7Ej;m%GWhC^t3ve@jmr-CpA!0 z*{l3lam;XS#%WK}lgC)hI`2s{w{Ba!0beXv=y~f}z4X>I$_{(^L6u!v+pmU5Jbp{K zXDGxR;h@^CW&CVFCWrNeKLYjYA}s=KIY}g4TQNqE>@dYLTh2PweET+t;DPFEn>t^K zv8CB8`o+3<=srlBFu2~07QiKh_e+w}a0c<#VPbXpzek-O8|bDfz?*4^9kZ#lDH4US zai-ddV&f>&*do1lz+;GJi2em6T!BrpYU)?!xL1W!U}-TI1R-Dea+#CP*y9S{2#!~O z84KDsDnD^Z+apO81TWTC)c#?6s4^ zlh^4_>s!T8w>n{ddd=kO8odm)>Dip^#xqxp(YriNCn4JE)~i%`5>yowuEh{(*Cbwt zse6JsL-9ayi6K6deSq8j*O&_V1euz*$vFryq+6;ur?XEyyk?J?{3mFohokz=|Dz+S zm#q-~Tc~Y9EDs9*EdW@jRG~_`wp|XuCG$~6-_F`>9N%?Zhu27VYiBL}e>}bQLsakg z#d~JxlA*gLq*GErkPxJ$yIVjyXFxg)x={(~?rv#8xH%cz)}w(($wp^K+p;FIraGD5Ct!6MN- zR7RwzUuF%r{2)rNrZX8rB*xxZc)@Zi$FHs#{IfO4C>bff@vXT*nd0TB)X2yYpXkA} zv7`qMp=YISdz3%y^hPB&J=}-lG~g*fbIVGFB<7awTPCdh%WSAg{Pi~@_H$@Hf)N>_ z*r#A-ahf=ZsM*Kl0B&wQ>CPEA&Sgn!6Fy(&IH?rZEW6b$Sc`Qk>I#`*&&{0DQGMH- zlgha#o`poCnIw|PA72eXjD+MykzEOIE&t;0Nl_f$KqFC4gM^lBA9_rJh3gwCuM<|S zlaxuGM_MEg&6f%uzaa5ddw zc6hO?LeyWP2F4o4Y9Ck1SwFzq;IW<*hJinuna2E9!*A&#w4wdJy!EyF2?oeNCb3tN znx?}ixueyeh;I!`GN!qbDUYw|_#CV)M7zDsu)42_iU$*9$t}ow=W=>J9oeGg6tx+ecmu~2cvJP`+sj-hep7HJP`A{9! zc!hu<26T2pzV>K8?3>Y7OKD;FRVijQ*m7Qbmr(9jo?7-+`# zGAdTv=n|X3Ou^Z#oI4$pX!2*;icWECY zOg+nt%VRpaAg*g3$IGEGx*`*A{auWl+3HN+G#5;RIR1Vbo@C*_NYoq!1YCRL*p4k~<=$K7n|x^MYd0fogV6IDQGrMvWPe=>qaW(>^x&^IsVr z4uLf)ZkT8XV$pA=4ScUim%$yK8ccf!{+X3n!jOnA^}w)?IP~3KA?O{)^qi%FT&zmI znNCAHOP(3_4V@Wjh&quybz#ENy6{Goq+mc>G?%)Jn?G{EA#tFm*8tZ?cI7}utEHox{*+Hp-uC>j4mE=uo$odloXmG`XmE=gZ)*D9+V zF?Qb6My|GZNrt}KP~RYoHTOLsTw~3wJzWjY&{=0d_(PCatjNkkB2$aQgupKN?^?>0 z+gi%iuHE(I@O^sfWpL*K`YCM)0l>o;8vIgaeB>&+AVQh)KHLU{YMof2P9>5zbk^yI zo;?Z-=UCuIq;H~q%?bv~4=nAEuoQoK3y&1iOertK&4kzB37^iUKXuZ{w7RIMm1Nw| z>NK24J;xImt{O`9Iv8?(4);GklLwdPNhUl{nXR4lU!tU%H(0*Afxk4%Ry(ERYOpwg zQtZT=Ya@o;k_@{DU2(|*NulEk&|e6u1tQbpWLy!o6_M={e_-=~fRDmW;2L;!NTKZ|`Q1^*bp^iH8Z zR6N`h)}79w;CGyz#p?S#LIr?#eESgLyRkmv9a zUWtGsBU&V3|A>ACO89=$**}RP%ghe8?h*TIUxYF;fpCpj`Kd}@LW%mJt@I#0p1pC% zx?auC;nnN%X;W*w#|&Q3zvyOkB>GAQGr~B9YX2h7#2sEPP(FLdf5GLr^vD`!<#Noo z(&UW_ewIAewhZwh?6=!7CRGbv^K7#Z?3bf``zWq@X<~~8anrG%X7yR_h(>xdUMJE; z!Flos$sqJ@(@0%K|1mv)dnaMgB3NO4(Duu&8_W$=d5y!Q*BLEJaw~tzy z3>+(c*tQ=jH^M{?&f%&rq1%Lpu)rumTBI*6bQ8dt;4uLfsVR$v|8qY)dtw6VW9HIZ zVKK)iBIv(VsPfs7Dr7NCzr^>ns{=d4iyR;?#kG;U47fo2rDfHDo6W<8##P;qWs!5I z9Lw?AkLC9W$=*ljc(P@t#I-2+I4@&ElP&)AF4k?n^PZ6>^u+PoowXaMCcgfA`umV$ zWjdd>#wGt!RKj0Uy#qU+>F2h}pQVCS37VwdU<+%b04$yN=!rKk8GWMQd<+AiYBAO$ zk266GmP8-omv0q|h1{Z_-$go?-vj|DKpm2K(sI05LBI((lWO+W#B=$g10Hhh-fvn2 zo+FY%780GtrixFqO)Hia;@)`0)p=0>LJl`#c!%9__$)w%WIDoQ5^c>S#y2BG6j5i- zXDuORr4IxQqMPy81=~6~J|_N?A^}qv3RP`zyHm7IRil+{88lDLI> zt@!D9wAzh)wjy-PB|$x>r-SW0yD#>cJ!ib>!XOA&#yG_{?b$?d~sm-m9e6b}WZ7~0bdu4l++A?l>mM}TR*Ek?BEEHXjgCZRcd!xw^ z_vWu0|GsA9+S0`;r#rzZnVXg%&S4lyGQGqQt(DvS=fJ@Q0BC4x^jw7=!&zx8+I<`? z9%5XYKa=K2ZBsS=R(Ct;pd?lfQ2eQ{r}bmO68ZT)VyL5rM1Uxyd+oL0!SRLuarZ&9 z6$+?D0sk>{9{oeX-d8hi@o>v+i{oipX`c)3Ski~_suLfVes46C+;EV(dx%^P5l8qO zpne1$sih?hG->Ul?&uL{I304)KA_`kkLl{D*6yn^!oBZ$-qV=BX)^gMwwy58CXw3F z#3|j0 z0>*+`#w5i=#g+e7pYtQ|UVOuk`kNFKlyS2h{yX<|r&Kpmti4T= zhlh>c&8l{)oojVh=yi(yur=);R}&5rXMTe&U1LX*gYPbk|JfWe<~VqCSfvIZQ#;s4 z9NR}5>Dn-ReF_BLZI~jet%D+Sf?=(Qj8jhaCB% zbZkMK%PE_pX<6;R`@Sx;sJBWQ;_=gl4>56lMW&Sp%$fG5sWbOIL!$Cwu))HTtkAS?AZ++##=KToMSC-p90dtYthuuTTOa;?_ji(iff&~3$6yw;0 zdns&yt7!P~naihYh;Z_Bf!vdseF03){zQIFC@gZ$87XNaib7h~^k#YS9+^*RE8z(CY{k3k^`u@u&I{_JKYjv^2#Fa7$A^V+Dz@7{9E0C zDNkaKRs%;Zhj+nA6#pL!AW<`j`MwZ>WW5z22aa!qB{9+r<((GIhYogwk13vTp^T`{ zWq8E$v)^XklTfYtxV|qgQJ}q-QoK!a-S=0NuJb6@cE>`1LdQET$F{fE^M3f4G&C!({CH+g4E| z-_(`4Fr`_AX1^oo=R9J)hWlSW?Qf$4;d)m)zKeF%YS5dbpp-qE__(!gQ6OuBIi^i^m9kf%)vC^E}gE@--N5Dk%85 z3ErE9%JIg2Oq3S%Z@44aT0-qSLZDmj8QzbaXVmgI&`&x|=t!5d^4~6-+Jqvw5L*+*rk|aM93;`^x(Jcxo!vq$AeBuJtm2YcQL%vo+yw~ z9v2tszWo9tjeD1j_-&TY+c4K3dGZ=w>;B`Sv_hKb5z&3 zs*dVGQvGv}69S$lOkcTY9wSs|MW;M^sS#UH=^FLsgyti%;|tS69n;F$RVE+_L6;l< zFtru>S-`Q0=jOq1tM_L`(fzXH|6GQYsE=$^0kwBBeSChAsdE(-s7l>}=k)J1Y`NL@ z2#Xc-nhJipKlm6pGaY#+xYIEf6-KZvJi#i;D4rw&ZJ{#lOUWRg?iF}Xi=NmjUdUTn zsHN+$N^BW?!vVi;7Zj?=aGiANxE_$OTI*pl$jtnmALDrrc9X{##C1JDs8kCx2oEu; zPvdt=PAL35L7~m}3ebMwsmGWuG!!RCQfXt5$2@Hf+M5hjyuBIQ(<|YB1Cg5aA3zhg zrkYGC*C0=#Yb8X&ym0xtR2s|A1A+M0nb59mli2=cYn~?3ItFOsExs2Yp*KoD;8u^0 zQPtUJGs9@n>aP1q8b#PSsVT6Vrf00-*`3g)?r5Tt3a*-&ng5WyyBd8^d zWiIkQ-JhTKct~|gsGAB6n!HAPN&VB^KO6SPWV-D){SY@Q9%}QcUJt>5w1vEt50wQi z9$P|iVv`5Dq-01JHW}e&A?q~h^@%($Xj{OE0VY{sr|oR%?C`h6e*pUQ z%uL^kS7Nd-NHI7;v0_0Q2Gn`KTa?BZKx1^J&Uf)+ysl*`03PZLui7k}k2T{Rix zR&QeE<1+r{cbVF%!2Rt&X1vTZ+tBohD={8Cg}9=j&9jjUw0P2Co4NfY6_cixzuY-V zz7&3|*0a^`$lA>zuDMSl0Zf|8@SnotPu`2_>7ZM}`)#UO+oiKF?|_Sr1XGx6EK(9N zPeWc!ezjR7728&-Z&oUZGF&Vx^lNKgL(kvX{xpH)?duSu5AVCM$JcuX^r)wX5&X8U1!;3DhuBi)yi6(j}(i9e5SmYL6ali1ACAGqM( za_~Re0XycYc0E>r>7wHCrwOT~(=V7`dHa+f9sl8?1i7`+p~IhF4k+HaP`?vxPYBz4 zH@x%IZg>d}-4MifQz_mxbm618VuGDGAAZavxRopp&=DlpKHLk9HsB!|WAZNu(%&dO z_Cb~It--|h_8P}LOr!EZlAGhVSenHsKjZL=*2b?frq$?g z6U@-5Rn;FN)=UFjf23PHy0q8CoQb^qf`I}Uu?kUy=ABh^PMuktO5)r^Z$ds{(QE9T zRj`TQ6pxz$OBMa5vR8C7Z{pT#XlHgFPASnFzVM$&Qx5{4U7bxfO9WI)-PMAnVR4et zmP8D#OKD{NbLtO88hzyyv;3yTTB!nuqc#&YzH~eSBY}wD08He-?Qf3%qc`nJ#fQhk zDF@fv+;p=eXv(Vx(;cf!DYtX;s}fsp+2KAW`11qid+%EnP1Exg0v-*+^yc>+ytOl+nNR`PUjcg-6OxD4(`WTO5tc-laszJtkMUB#3NU)xrPJ4>gyK15_Lz6XYlNXRi zfvu%>O8;TB*ooTlIjLFgzO4KMh*(yCp>U0s>ffE|sl4sb4s4yn7Jot|c^h^n%C(~d z-)_mKo)BUGc_s8!0*IqcOviT}%YPwv0ThA)leh-oe!xRm-Jj48jgtt9a zMkn(mGyY%6;+cS%NOq-dO5Xt_CO{=lrj?YjjkUw&8x@E3`cU_6XqGjm)B7M(eD079eIb_}fvZPC7s_Q^b1p z#30NkcsDvGZ|k)JFEk=Kdljd>z$nMXCYE&Mx(j4mFZJdgzbxA0f~9vM!pZwij1<`* z+Gj!bb@j|36^K8O+28Sb$@vl5fn)4d>fMCtN3gq~NZE0M zXqcskdf-bR;ze zn$VbWcyf+bRL1pILDp$NwY@R7cFns2u5WnFoV56Bg@Lawnose<|8v8965pXH*&dkn zx--wnnH?GS2;Z)28+@G;+Tpg0{}}9pj9lZPfPP>_fyp%}R*);0^AYSBy(lEKKyTuVUm8KO09u$mVky7xiONpf6^+`(a!`V`%Wpo zswHe)=+zj%OFLpfTSm!uSYAS7r;4uhGtq7M!5+{|4 z4a!E=9=U=TO27$J!hBC)cg2f2W0~N@bB(yL!_0m{J9Ef<^)?0?l{{Cc`8(BrRb67p z=9Z#^%bzbH2u=JzbgS~>9d|kt4u5v7@tt7|>3p)Pfa?h|RYPJs+nL-#9D*!{pKQ>K zBev#lJpWo;7+xAN-kCh!!t0P$n74RieB>XoFAl6KVH6RO!P@hK@H53q1;VdE7)tR+ z;>MSTQSF``Gt1X(c|5Xtv2Qmx;!wI#^}4Cm6}g|{N+=pFuvf@G1{99~b>RD_PAVj0 zj66ZPpBc$lO7SbUpAbq>X%lttwu{$nyim=k6Q}qVL_e` znp!v`q)=LNH2z`uq=8=wXB_ripizuZ6x(>xyw%~FO8zbJeZ4h#+@ZR8%{lbH_o&5> zOKQlgY;^ds0{bHUhVteIsVMolNBC1dhQV>f?Rz+qW`k$9lZF#J@iyWL8s`wDhN*qU zle$ISLGE64%AOV4LGp!L#M0WMz)h+fEiW9gv?+!1rG=TkP5CDp&I5C#A+Fy_h_3#{ zvGEgm&>izRAMy>aplN<^FK%y~f2!>HNgyE{!bi!+5h}GehoeFp8mEwv#Pm2v75Byg z6NNsK=6$XLtD>|y5c>po>tG)<{5-X2_KBu4c;>NgpGR{UTz34Gy(NeFYB(npiCSxf znVXVu0mcmh^K`AF!!DIYDr|2>HLpeGk=wjL?PJ0Ru0!*JcwRt}?W!tI+Gj#L>$D!< zB12C0aoFllkr1Ik8S@M;;E;gq0dh4Ro)pUBHikQIn@R8EFnY+35pKcB&RU4srCI=0 z07`glY&S7etjmZ-PhjuWt9#7{Qj|k8I~>c%ORvGXolMMrNd?50g%AA!OJtTSx{}JQ z?T;>ulvhg7&>xh*9)q)a`yJf=P;D3)g8*-4@b+%F%gzCVIsqw;LT0F|i2) zZqH>i>q9`%iuJD*0?S=xa*g%s*rN)*2PNLO2v&zx)X(scu`ExCW43xi zT=Pk?c_tIwHWe!|ao^f(e3!4DSNL85s&WDP3`9KISJ7c*}gBc z(EgSTjyjXLUM+n^w^`xv{xA7$@vIXHxzA5V2c#nM;9A3WM5zn&wC=8yJ3tZ>v$J1; zY+EU~vH&?u0ORjA8+3J$3((^CL$?bKmB*c>e|IE1?0|2H>26d;ieK=4%%$iE+tXlZ z?%1zvSwDzCZo#zub((8X46R$kKU9FL_mlb@5q^=zQ-(rVom|&`HrM9N)|C-+bLY$Q!#hTFoiAP0)oxkN?T) zldn8385Yxg>XVMcPszIhV!)vomN_@mclPfblsFq=A_SXLdEe|!1*+yKXEj@GLpx3b zIlLa5I5;>epf<)I6|}8-vu zCATOa?v(h79*em0v^I%UQudQt?{Zj>_*TAN4dAt0X5Lvte*q~`cTY>nTA#IT5pM?5 zO){PMBUnevyXK*~lqOU6QLfjy8o&~v*~xA_qd^{SKC!*ZmAiGZ$g+*UDC=upvaSwD zB;8bjm!`#eN|`CQbr%%Rz0v}j`_6_9#b_%5j;u_%1tzd^2i&+L8FoHx&rJ_cW(;5L zmX-vB{M2_r+Nj*T%GStX{3q4JFsoL8QFQ_hU6Ts#5`9B(8gmDUfCesjB6hBPr%fHA zIU%n);43*-@+yWX!T#XjX6ZeSmh|t^zg!7-Iy)`e4-p?#Mo6~v1hB7Z$`9z;7262- zhL@-4IOGPK=3&H08@;8jv6pIL1Kf5fh|t*?p+)VM^PNpXJ~x^T6or zZ|(deAHnF=#}9)7VY!@_2XxX0u#FC>ll7F1<>?{loy^bS@>?~6hmP*in5uqlFxw*? z!y0sS1<|wosn*BivkpoD>h<3OTFt=~%gluJa>EK_S`Sx4KpUTWnKQ39jVsO!pAL1bRqI1_}J| z@>b3DTWDa~Gsy^Y`9_4O)ktJRw$8siAJk`Yr}Jy-?7j52RN$HfdM|0gOtl&O+xl6y z_RHI+H5Eg#Tv6xwO!7ApXkYHWf8)GiYePr!>{(8`uzXc^R-h|&U6lW-b)Y|)*cF5l zwHWWTFK=^rMYdk`5D-7L=xJ+ffQWQ#25$r;w0lzxmRx4t8LQF3ZDFr5+_ z6O-VTfci?fZfvh?$_HPWyZLNdi$B4dO&=k1*m6|tf|*&noTu1(JQuC23SaVg0AKGP z;P;6FpH)IR^jA9m#xUl#Htyu21FWnSB@MntQo6=7#3w|k<(JlNYCPA$S9SCT@Vb5H ztLE86%VABPBSts#9EqK(d}q1ahFZA5Ic~_tU59MD%-1yOl(GvV39Nx=smor?La1`L zB-geAXDP)Kn2z!5&X)8~@yV1H<>9%W6UiW*7N0{@1|&IJ=TzT^`?Jf}B5?mIa5C>A$+5d`t0qij zJ)P9>*meOXFB`T2=7n?l;@$Od?Zt*YC3RaQd^nKUPyAm3=E>cQmEjwRUHAkzY7=N# z3>-<6SJ@II813Q$y<{$G+C~BV`AY086`t$ozg6Km5t{l>z&^TPLNJ100?0RlN`#1$8FS(Fr*!{{G zf1F>DYPbkamOH_btPI~tsr;`CVzh0-h{RKeR{?A%eX$4@%W5 zY22qfCSE&=2IoE-%a{qwstiGExGc9I9Q9D0;2S~*2RX{uTlGoFpz1_V$DiN^)+OjF zLNT)83FlOQ=k{#>Nhu~5-c&I!63|m=!Gy^s3qG#+`4%~!QNGmq6=YPA2p*!u^zX=)sQvC{OuBBSqWRwn8o*n`@Ehh^1C7wscTj4Ni3gMp|mMIu8t_d@o)#PY_BzvuA zbBM2Q(Ktq5YL^G`gK%)IahCQr9xNie56#*>;hcLqfhGpfzU#0(fkc%1VUu^0Q6B@4 zO0Ub;I}Bak1LSd*7Qa`J)(Kp1a}6+pJCt=m6XsW|uD*HRB@-L6;Rcn#@)&Cw1|^R~ zW?#L3VBS` z%YzGZzTd1|vr@EjHI&~j;z1Ry!+uPW>HsBk_oyc3T@#E;Z>hxQj~x^&BSv(U&iBs` zI~0;5X8p*hzBUrfQBHjekc2E@A_$FETh(RDTPBq7MQY^~6RaftzqxagA;a0CNWlnW( zQ|>;=R9pr`%ShwdC3X=ff6(nn=U?MKtK9xNEKLuM!;KM;>LD8FqHtYv!lbp1 zNTqgIkQeDVtR)C2u3sW=Y3&n9uZ#S%(zk>m&ROUFf&;nbo3ghU*eK5y15JLy$5PUN zcMTKh}n9%y))t$t$Z{U z82EQFeWiOcX}TGR6gCUqTjVeVHS)3jUUr;+DYo(L$17=><@aOy4a=)Z^&gG=bXP_k zGcIYRbKjMmyw*LjCd09qHf>+gshF)Gczy8uz)2vd-2c#ftw}RTH4qzgwzT@(RP;_Z z%5fq_32SXXfdz3~n6zT|xIK0!0naL+Sy{iqLEw3Feo1TkPlscd zUzWw+fy$DUqYn)AeAyDKzVwORvD0Ej?930yVc#7LodS1B-!#2nEr$YXK{J0>P=ooy zKLSCd$>s!Ww<0fX7TyEzWuR=J_r>dJlAP$BBuQxcATv~4xFI>3w6%2qw_zxo!~rcc zUnM5e0G!B1Ef3Z^NC7d!OiuO5<8ej0q^dXH_aDplMJ)J-^~qit--`AtL|IOfRO(aE z(C?y80qfvJC#^IYtpy+CEPsBC%pWcyqU}hE)uWJ)!DyXe%0gM`ll%>!r(E&1?iag?IEfM&C{eY8pmDNm6wpX?4qk5=!pgg6w^owT13uP+eBr-_-`oekjhU$ znU>mA-7H}G!}5FD%!Kn<^w&OI)@xhaer-lRI)gd)26}O zR@wqMkNUggp|y}T=U|JBo8R5?r1xzVC2{URHGKkB1(`omKaBDQ%RBl8iB*EY=|+~- z0_wZ?Xn>ZIPoWokQ}3df*B4O02o7~grukv_OfmKa88)@b$FnDyr^@Ap3M1f5t3j(h z7b3#$x;7`G^QXDh7h!iu;h>BFna46iJ+=t^e9URc(h zRtdQ*a_^phb7=Iv#pV8|cOi?1L(uy6-;00+2avHu7T!WM3Nh)?U}7UzrJ^bE&kRAO ze;dL4W=8A`Yl_{dmeV>6D%ANsBvwacaI960ZR$EUEYn`hBHMM({^`092|z#tjJn`c zrjmfMH-3)N9n)Spqh$SAosd6KS=9!MRQwi}&FfLBmzeR6SN)R~BYrt>nHeb&FfD5+_xtzsMyuh{GV59-uBWLLRRqbA}tr6n;lLjS0yI))4Z;lbyt!91_xPF44nR0w zKE-8tRW|9P1fzqcbH6i}i?E*#L(+&3jeRq#b(aDM8Frb9T;odaWpysR6)bfEKN?c8 zC|OG*UBCKSW)6>H{^~1h7Kz11>vUp0s#&G8yod^qRnEf3uAQ46S-n9h5^J=Kx~2!EhrxTIs4qqDF)Y)6W!BKt!} z(h07)hygJq2M5yp+o7Q5xtz<8kC;?q6)qYKM?Lo2Lna2hR}qtRz1t74-^GO(eL4iYal5Wj*)VS8gNGCKi31KR7Zz+0@2$5< zpZ?&DXpygcy%>VOq@^W1uA~$;Tu-FH>@P)#9vf7Cm#Y&wJSVoGV13HncC`=+5YXBB za8p{kB1Oz}kA6z-+Qi(a=E>I^64mq_g=WtV)G1`i$U#lCywSHFxrgGns-PXl+Q(4) z0c}{kG(HO|GjUxX-g~+7>O>nBa~)!5t<39`~gK@A*$Ni#3o`q*KUm3~{6uB+p3sQBHF0{m-SefUF&uL(u-yz4*)a zE871-3XPr11THAw9df**`f}p$SO0TW(sE`KZ)SqRq74HqTQ@EnTuR>@C^uz z9XT0+wSKomMH?ddIDpzE8xdrRe4bCn=|JA@B4(aotCY}xaQR|AH|VNQ>}X`x2g(va zdi%lYoK@s30LJfvu{5^w5Jl3qppwASk$i32(H{hr;QusrtfQkh-z8q#{q)vH^Q8Gu znl3mU{7#4JfUSg~U4rdDHaDYFSo$L(DUxZ`^sFDt#g$F3clMA71btxF{)3hdyfBb_ zBde|UcGo;T;9O*s7CI75DYg#M07CXq8QD=RuvB+5zhx3pcTiYv(Lw|HMe1XAcpE~^ zA2E?QpJX|O$QMr^6UM_7*z9OgEKBiC49{BE+;%R1ih81>Qjb037-4>4S*kJU5fSmL z#Xob#GR%8nJ64!>&-F+0cE^&fb-E&?jE2~u^qdII()F(@evbDf>zi?(YDsDRWG?I4 z@AEM#{Q7w6*;9#1=3>Z_532Em~_s`rH@;x2`x?j z2|`V#gP*KujOLmD-dPX)vWHIME%cV|L17ZGhUpua$e?&thWz2DS6rPj^`M=$R5pIc#Z8Ps(#<@mUZ?M5Zs49Lp^z;^4s`W|NnxxOma%#$` zQw}(tpZqWg+6O!z&hJoFc@YyNdS8bt1KR^LsYZ@#&L&<&N7^@1k*dB`?(W}q%_CN{nmlC=Jz&`m=r`kOriZdyCruEp8mfx zl}nob9TNd@6r-ljy;dqM6I=W#rP^(KBuxS#EbQ=&$gbeOzo0S1&D}igX>eybA^Lp9 zciWP{SfRX^9W?%`_t(5+qsy*TUw|Bq+ykx1$$tJoG}qU^0o*BF)RQ*so(ZKL886uA zF4+wMyZaNVIknI@Pd$JduM(iAvtSozu81%W4dMj7M>o6g;Fbh7(0s=s2mzY5zv3l_ zczvqeJzbgg@AZIMh=`%_z5xig=?eD8%m$m~MpM{@yZNaELaU!Sm->ZB<5tAP**O2X z2*6+&QSUYv{eGZ0BI`tB7T?LZqQBD(>BKd6iuHULct_~jAu=WmF43aR?QKlWXjRN=hkP;BK1 zrJ-c7$&&=kYPGc^%*Id(`(Idf=qwlICVtJorU_3Nt`R4D?V1YOB-2(ZYuLAP zJ)1wP9qDws*dX#hSRD42I!g-wC`7-^8iz`{A0lnjCoVgFDo-8l@1-N3$c6p(lM2QNU{7) zt#e23Rt3E7&LrP;iy_qbUnmPR5zTuzKzw~2Y-cl_f&eHu&D-SjA`7L=l1<38x%Qg> z7+jIcd^xZSoIUIZZOynLxe&kqeT$d^A+1Nzm}#zKBDpk@tscnV9-#-u9@w8=@uVTR zPcBQ?K&|U)zoC(b##=YS-WB__DKCpNnw_`4KusypL2{w?=JHia5Okd3D9LH(O+7GR!{P11O(H8Wn&h0rl1venkx)C95i0wC7((}Nl>ePGF2$KPIoy`~1VZo!K4Pmf7rjTK|wc0Uu zJ>Dy8^cts0F9!99U$PpSotfyN<2n&lA32xke(bK%CEm#|=v5TPvRw1C?Jbm-6N*jw zMTq__4N;L8juzr8E*c;DbZndU+8CjuB;v{&8Wakp0k{{~fYYwZH&`_vr-fa?J|xF+ ze9h0;gLokofh`qXAidWc>PFxH{S|{bj)vbGT4*q2YJ=a9OLypQN9|dJcL0p2yoGkh zt9=x?GYT|GI3ZaPjXbOGY1_(ajp8@|B_aMo_ijFSMD0pk-SVd*yRpnXLX>N9i)ukv zrluQJ=a)#@yN>6>2g4V1pOZiVypWiRlEi#jN%_cV_|}(fB61VQ;@MZ%&FB2I!h1CT zD-;dr1@wAtx=%-raFR*Ruc_a4`J<~oW14Ryvz(Dw`rYSPVW=CEZ}~|Q8B@igk`i_C z*e_+aU+t%nCXS_K&Ul`t4a3b@A`AB}S$%I~Qt z)s?ng{;xtTzXoEzCHF>483M5+2~V;{2gx&xtOZo3&qSz+r>Ygbe;S! z+K4(Z-H1!~nd!5K!Xv(cMc@rfFX3Nyt*T@8nuH=+qOAz@$3@D&hOHInDr}aw#NGH5 zIq2V5e4;8(mdaga{^6prdAU@YQgBd?^F`Q<5Vl|kEn6t8{xBp9dI7zKRo*w4nS06i zhGD_HP+$c}EoxqFb#NqIFcXO?v5{|r$-{>hKT6e)tuXar#y;bQ_nZ&hdlTW(&U4a9 zT;>$Kefpm567^`i^q)&6g3pb`pH_Dfv=Jd_MKJW z|J&NNGIy??RxxV4Wwd--pCRY4c;J~Z8t-e2bt*a_fca?_!FAsBB2x7T`xSCPNy;z_i3N?$a+q!pZq*WyrIQ{B36o|LstInl4N`lB2rE|4 zLNOnQ`~=&qOOy>sC_eQHiVMbCh0N1giBW{=@#f`Ep^WDxsAd&XJI47Vy_$rnQ8p$w zXCe)KQ8$lj1;K|m1A}@4mh1ovCUX1fs4nUH9Eeo(chH)<$+;JUGkN3Ppof~62UUP# z)d|IgGp&w_%@p1Hdqoj_@2nRw&=8KmAr}I5Za@b&oEB=uKwC-zTPit}v_JdUCG95h zMv;QQ@L7Qma)7Xt7q($^mZzax+tw%S$4Z+;0^C*5Fiy~Qv$E`E+564+i3j>8X4l1I znqqvoW)0o6k_EsA1~|AhLOP8ER(m}RDvNX(w?TOf0UcePZ`%hQ>wlHPjxt|aD5E0t z|9~28a1ZfQIuTpul-Fwn4{w5A-=1tjJlh6@Fjt&2FYGhvUYPOJF*^HFTlhO+B0pqI z>%Tk{i#{SnP_?FqZQ%)As{Uq_P9=4z`+u_8hIsG`-vHOIO( znyQs$)Wg{R7ucA8j;{**{6E+u+Akn>#K6fIBrB}$f8C~4>Hptt?r_q$41Wh)nR3ov zs~{!r66B9ErCuAd6a8!~WqdDoXIM?9%M4=)AuO^pjICzuJYa7&AHbex&w91O)8G@0@rIDVO9x$2NQV_ zbiY3I3eJYsdFK?q)a7#b3<=R>*MjN`>%OSNRagIQGn8iHa~%57sD1e4JSnZ_sX{5N zJG^7=4Ebz%a7j3Ji@EOacFJ3JZO-VO%J?3*tjwG9H}XYz54r9)s&4F!QH+4hrwNj2 z)b*4}fDxtioqDT}zVeRJ#&oF1z8@x+rE}38c6@XZi?~oK1>`fT$Pio4g?W=HN~Tky z@EW0h`42Pr>qwBu&F8=wj45p~Guma-9Tg#89BCbNtJdOIyB}5#X?&HogO!^I3k!Ww%Kz`5MK0&+ z7u^8eX3*Z?Do-tHL{L|`%!gVFjW7I`=KG2rd~Yyzb9u8jwB1H^V#bIMs!Vxh>Fw}a z5;2itn2(p63iFh(GWEPt)U_^*2svpGk`#l%j@cAj;wl=W?$TmcV9%Dyxi31X)ZfYB z!YDs=lv8wI(hmRoC);O{678)Bq*C$?GS%qUt<3GsFySU#n)%k|fW@@Bwdlx1H-7jk ze{}O+^qKJQ>yP6qmRe2zm?CpeBMyT)WY0s*nT$YXX4q|gM&kdW=_dN6Wog%MzU`ba=s)e1 zVoNfix{WktkK9e$UeQ`0Cg84LoJPrnD{V^`K(7JGSwQRwSNdjN`A{`Tjlq_@mQ>9VC_ly2n!QvHupN%KDQW@k32hZepz`~?H6cjvC>-eB*KHyqTOcQ4Ip;jQ%%5wdBx zXcI#6%G?v|Xre-Xht!X}6}$Rd{F(r28-Xt>t6@Jr)j1jYPXxJJ9$hgqz$ZK;T2qjU zuN_aL+`;Adr%~e{mKA^J%je4O9`y4dvK?@t+SV!^M((ew&<@Q<`*ZQ<`}LCR8o1Cw zS3)07hq*8(ep1m8G%7U znn0b2bQ^X3E_`Zml3%q0IuwOMOWfNcmt=%@%l*!{5QwSC7YbN5>TJm~6illZ#1|!`QcXS#TjfvAX<$vZ}@eUqpD9o&APPE!HL{D`=!Ow!EIOIg6ZLH zy9t{B`lWtyf$1U#rQ5L6K;uNrwb{8o$9fYBQKTs_evn)Nug9AghX4~lR4s5V-`iHu zw%W7^r>Wazk^|17UYn%!bKyP36JiC#P5(04AVCK*+}1jp;KoNgY4(Za=r4dM7W#*m z(;-m@;7?~AO}(sOwAd}V;1~%#r`tg^VQOt4)CQn}z&IkxQ_ur^_{{4vV*U0Pla=lU zLv~Xnsn656#y+!bcu;tf=o0|aw}H%UVM_iMv4I3>4g#}_WI>PRoixK)tk3_hmi}t9 z`a5ckxvA;eoO{nJcpL=A8ZW~%?2sJpf<9{pO-50y7((~{Z4 z>;Ac`@+y}DK7%Mmed!hml_4U~3|(JD`~_5jJ#9cVJ2GT7PO{`lU)T*keR^T|S@G@d zYjon3L1UIU_bTK8SgD!q?RVY~r_6P;!eK#@hDcVsI}t(t^`Wxzi}ACEWaBBHDZR{Q zP1=9Q=Mh{G8favU9l<|T;085(_&e=qWff3(gVQu4FdGAM$3l8j73JSu>ehf zd}ocUoSR1NPUrTA`8>Biy|wUghs|R=(|zoBq7LF&(LuXK8(nx^)u#oY8C~lv#Ic|) zX~*xmF|N@k-J@oY{k_#uOr1x~fh}C-)x85zhvhRb3p)V%WOC^{Dm+*-6rW#_I?hAn`FMiBi}ZqWpQt_SK4i*y5+&Gek? zt{{$TL7+5JV43XtyWeR}Y>D6FCjYj=!|)&nY4fAUPqsTYXq}eS*3izN=jYOO<}b`I z2`dsLO}qVgQ2uA;#@8#^OsOls6Z4G`aR0M7@5mMri&G&UAQM1$U$Ju4p$YhdY(CT& z&!3e|MbWS|GQayJll_lC5yzkfAJ{-nWA(I+*|Kq1SQzGtSNY6QZ_S)RXu(k>Ksk;m zrC3MS0Kf5L;eP%8K6aFXC)g0UZoYa4Bu47(EDf&tii{fqZiA0EyLCBL3!s6Dh@-}Y zecx>vv=H|#uOmx0z56R!6K!Jh%uq5K&m1p7S!inn{zM<4QZ^tXW*r`rU*(zs#6X!C*#XTi<*fEzl*u|vK6 z9ib=Vy9r=*VyYrn!B-^a6PZ_-+O~=@Y|oalUqv3sP{1Dfr%&Tb0Ce$x0Won>JITbi z0#`!nO(gVeW42F4`$rsiRZaf??fr{rG$tda7Q0MZqrVs8TBE%h5fq7k+NN^Er2gnE zBpV}hIu!An?a@=#PU)rV*HU8NnZ4?`=qt)aht~b4WoJuUtec|rHFv8YBf1#UT2wU^ z{=+9Etov03_}5oR&g&J8(^-Qxg?$0&$51_xJdg^pY_#0aEaxbD4u%77jA zN^v;5;*b4}AvEuesC}Bb;L~>u9JDs@8ZKDzTz5R^#t3Y7?pm#(dvAnF2DA=A2{n!< zndm~9B@M;SsM0r&2r}n&vrtA!+W@-Y&nsN0yksP zP!%Po2YAaV{W?YtD)V(}={wYrzpH-AREc0nN6OY%MACnCD}mDTh_15WDd7As@qyX) znUl`V6_%!0IG$HDl$uRA@a%NUN`zAn!T4eJ=kBJ@XF#HncjQ%eWnB#>g5WSVIY1vS zF}tvqhg zd#5wq)!Rhf_6Kzs8>aA#3!fewN2cMEZgYsmH?$5c%8ci_GUG!mxiOCKmyR8MzR!L# zWS2Z^&RC5@1W&5N#BV6gW!xbL<|H6Ep=bebA>Ol?4K;kjE9qNIIMs}836^{HoSPY( zh6rGUwBK``?0$Hj>^3KQew5oWlK41lv|+0ZX3N5jTTrcRON(>AOfg9;BqMN30Xg{{`;{Fo49 z)N_tyQwFwhy~7kblfj+F7q(jDKPrSjZ$yVP>~5~ujJ2tYy5xEIGk$is`r(jN)MG^b zP7pI-*yUe$r}nb$dqAUq*#1cb0@N80%vZ@X2Hj-^0*1q0>0|d&#neCl|`oZXPO#niDx6?;KY&jPE#`jXZzMDg*Vmi_iHbGo`qg$}?$L zv729-WG`r4o70>3bAiGYkgDHv3K&K91;2+QjC!~vF63Q6W1QI8XugGqD5{m=ff?=X z__Tf*>48{%0F`S#$UI8BAys%e9rx*TRgJAh;Eo&S zlRE6bBIqbk&Yk{7xUY@~B5@(^fLlP0nbT%t4L_rwT|{MobvwrBH~(Q!a&Q4sez7m~ z8)lyKAHcq34;lm)5C|sQL?7@G^*524`)3vgpw2foTsj46-ip2& z;!#E{;Ucfc1r&OEDr6twOw+ zJ~?%bB5AqP#Bhujp};Q%e99HiFpw#h-?mYr69pGbt-R!ip`gK{@np+Aqa#!OackUq z_Y98gc(Vjm1k2CQyRM2s+gb2BOn`V{IZvcfXJyM8I9kwE6L8fwuIK3EPNMs{knBA;#umXs`$GqvA{Rhbg|l9>VEV{|3E?8`cJHa$c+NMdLS(Oz z?=~vpAd{mn1Ce{`42VPLH0~9CkTE)D9=yB(7a!Orvp?*_V$mDUdxK|Ic$Uk4kNke6 zpXSh#?why~&V}?>{6u_eS_rq*_S?Y%6bKSgx!{XK?eecev-+%DWUnk!J2Z$DkM-FF znY?TDcVg%mC+z@L7Wy-9D!N}THaa8JgGO0OcCcIc%}OW5%YKtePs&&#W5^=tXq&hM zK~DJx;M`|FwG;?oW`K1wWLmiG=(HZzTsB2&?T4K(9mqIPXTK3k=K#oqyoe5k{o#9# zB28DDyU$q$z3)-r7?_Qp{I>)la&&+wpRL;Y%!08k-9xFKzXt$TR9yGl8W2qvLZH#v zO+4I*9EE=ReTms9K}6LdJ(`h?%Cw!5J77TDSPH-%svhpYkiHSN@mZ|RM7?X*+S4-) z_x9U7>V#5@*cUL56{{Xk{ANAu!mWZTUfpEJ=|*n1Q>Bw_*`R*_P#;DNCFe=mR%X6D$E zjyjJ(Eh3bnaTohUSleE@dq4i4_C>J(`>Vzh*&LcQ>(@0?yKP_C_LM#w6Tsfz#|||OQ86_{;mNKsDT_FY@WNDdW;yC1n3nXWg$l42x3XV z>>Fx8??GCZqM&HXSQ3n6b&E2zOp5&gTLT!cE|k@Hb?c=o*5BzOa^vsiUBtd z)ETeHQX96m33niR-0}t*uS3OOzdkL~403!JW?8GsFB_s=Jq%8ABzpvKbB#K78Cw?c z+iE(LCrbMP()Rf1k>Y;-j>4r`Gx%+%xu#UHRS0wW8udURX^bVZH?Ur{)9ujO;OAZY z)Xi2Pg=B_!J|xZ7#AM8QW%ydwu-)-O87hTi4@x9~1lsc@tH&1Q)0@R9y>o?m>Pk93hHV3@KZ>`)V~1o)t?c)tQwH5T#z$9Au3IW2 zyuPeS7J43n@>yNSY6PuJHo-9>C1;JgkPB!(fRiKn@%C(t2YWA^?qgXghewi5;z~O;ppyN^zz&!`|l0@Iv zBLg^n+E-2f3fCnl$|;_}a6;iE?B%zxrXm3t0f}gJC6;e4&b|XSM$Pgbk%@2)nI)W?Srz%Hyrh`$l9QGpVhFrmz&!65?0^AF;D6b z$<Sgt%w0h zqHh=Qvv6>P&vutYQ*p2kh=oQx^q)T-WYb-%6T!Tn=Lx0#w?)d?Y!IG{GmdSpZrLy8 znjASogIQvd-((TAWnJpB6>$e$sb2gOzM-`Bqv1l71vUY2%e))pU#gRrZlHBh11wr` zSRj*rWY5Dt-%E=d<2f+B=6)7}QNJxaGUpEboCITrrXL)YOpggX-C}-MG82ljcPwuj zD@$MdLJGpgp^k1kK6Jx!9iU|15@num`BJC7K3)Y-Vu)#d>{uD|L-!mmL9i!7zc;S6 zGJ|wLG+udW-$!(Z1=fw7os(RhRGUAd>uht>Q&-)5_(f{QGsIau738SoMzNzl=cQ@! z_3-ip&rm~)N23eLp4jr1DsGN>%j-y@!p>$w)fX+T^)oAjKtpf4x<}R+N>%LkUOe>dQ-u+_mbJvQZrr(LGTMm+vvMb+Ve+hp?>=0 zX3OUz@|AEQx>Bt2%I#y-Nz8@%ARE6Q6~gfn<;Nf^dPHNoiv&6r_9JFq5t%!P|Lxox0RPxlwYIs_m00M09{%@1DEqPuH@z_XUvlk;duIFF z^nl1xo3jk$G2W+sNrVAt;J&pq7{2of+0wZOw8B6HBoK~0(!p%RpnzTj+*tDex8(TACTuZ*joDj0bmQK=mI<> zx9lbEC(20(ZSF{3jsa=)#S3!?KN{y-s(j3r68|v%cye9K_u&;0prkGA^TRom)*rDFU|KJvH5IPnw}6r-8^ zP7x(zC){Ztg>5G6PkbRWu+SiOqF&Oz0Eyy2(ugX*|L7SXw(?v7lAbYn74lp9GM@;m zR~`kicfjob9ZM}4NKXU^JK1tyR)8)u()GcAeE_5-cDL1`BaywnUdp5Jo+>UxHGkmp z3-q)NLn8SBgBvpgoq=&F)7GM0NANEr-)e7YPfo5OP6+%B@Lo6v_j7>JnBM0P`AJj+ zyr|D#7uVLJFYI%X8)@n$h*}%S`pxr82?tZz9^zpYHUFv$LgD%Xi3s-~=-?0u4UY zMV7;BNbP~~hOaKixfvEdL|nO)?J97)&3O-B`QAJl20tI~S0vh?-x~q#;8OCh*AEf; zrEoB6E}X;(5%$Z$Ma}*usCfgPW^dMEJ3aN^hq59g%}eh;dA&A+IB-!4w!pkXTrk`e z*3?Ql6~&_8+#zT9Lm(T69SfC~-t>^|3Plfe=5x0DFt?6BRddL*YAJO?uNYj)3oc$`W2jcYj%oux3rvw#KItQ z!SQBB6c*L+gk&xcHZ^Ip}!K;{kn zC$q~t?>``$b%t5MiOa9+%D)t#Yf8GD<3OjlI>D^NrDLJ-s>3%gR0~vtOOoxFG7f7| z8DM4Kq4f_Me?NXT1xHEPd0=M*c~JcrfI9kay8E}k-;DbdE(wKy9`G2SsxlGm+oxx$TIs@j?Fupd%SV z;(@=&fmC+8ql5;tT_x)|Yd1gFiO$%uQJ3yjB*0d5!EVVV9zATdH`o9I|^{Yp8N?z%%GR zo#mY$s@>+z*MHx4`~Nplk%0mSCdiTjSoK83=+cw(eaF?2MLUxBqE^b|xbrP&tEV*g zEkpYeTZ2lLw3$MuqiAkOe>}qBWWkrQGYWc(d%_LBsuVni{?1rIv;b@X4#2uz)dAHy za^z?FVDO?lOn)jm1QB7>PtmEm6(?0Nl6?5i+fKV(6k1P3@}h7 zxJ@nn#@oNEizo%)(~qX&^RDiev=!J!#-1Yj^Ouvsa60+TC^sb=uBI4(2M8VW&`Ryp z@fBtbty6=f&FRYC*60vPcHd&^B|O0qfYp`Xb@S=-&^@>AXUd7KC#kF|eS55jd31LISH#D3oWWsRZxg;%TqKMo1yY6R(#$>Zt8 zgW~HADLO>|Hk}lOhJK+28FO_go?!ZyyRj@bkH0SM;yj+$+pYaKZl-JbVlRAvl#VT? zwT}Me*k@L!Q>UR9!kkBcc?Q=9mINcN2it#)D(cMd_OY~ow(?o92xkqan#cvW4?RKe|JO+Ic|I1x*hX@Bq|JZUa1)*Q`wREWI}TC zFD50v?a9B%I8L(=;CHX*-_yu2sVNKaGr!ZMOr;0zBXjRD0t7_S*8hF-O$6FFyLt|3 z`J11&4;}UBLC9goDv}(n6NfoGVXE&nC2E(!r=n>bq;- z5|^9OdNa+Mz_}$fr61n7{cUYBd^gtmK z#j(S_dCaN&F>2R`X5C!y;6!?zJ(wU~D zJQodq8FP(!g{W|cXVt+SN!5k_{(nk2X$JP> z_6%D8$17^-!$VC#M5X4}xg;ijTvpr@z9;oudcJC9N`-@qHN(9Af1Q#uM85E73DjiA z{OG5v*Tg3I*cKhFB0&LI>Ii?B({baXR3IC4zC!AxK*I0nc%-tk^Y7R`Mftt02gUAm z#Q^Z;b<6TSJjqq-b!*c|7o1L2lure|aJNPt#s@W|wy2IJmX6gm9vP)a{@A+{B5l;z z{Dd>M^z4lJ1xxb27UY>S(ap2Pi7g~7LjyUFKQuV#(^P;MAz_EFG_p}I8s&dHw~Squ zDPF`?W~E2|VAMp)AS6{T?rvO>5^sR@aZ}00%tSJ(s7_RZ=-WuuFMy7jb--bh|NU9h zuG!loITgcA%jz0bp$L6u*D#@*$TB9K;2DQqv=lV&vJSSp^TvRf?zbz9|0|A?$U_PN z3ryZ^hE_Z?V6(#;hj-HbQzmg2Zin^&gi8dt_pu;>nI&Gs_s@C7AcD=qWht^}qeWTt zo{c4I?1I7qTzy<%i4s5r;7cQHd#0Wgv@uID2G!y+yY}tgt>*l1r__pq{x6OT|CLV{ z>rfvW^q%|hyx+ogIkQ3=&ml{)EA+It8U^~}0fC|Gg;jBhE2UNSyOf_5)a2J;EEIZ!Tf@}pJ?NIMXP&aRkZTQ{uO2?X} zr20p^hZf<%Wo}>DP^q7^^IRJ5z!4i@X27L=bEG$Sm*XP^WwC@X13cNps2xLZcevh)aF+sa}xqiP?5&wOr4j?GH(U=?^5%& zwayTj@HO_^sl6J7(nq|lc@41HZ|r;fs_$1);k-FhPaPK(suvM@6|xbVsiQAL>x&W* z7l=PTgPynxcT3T6hu?vUy4UdXZ^U44^V*Iof}S&$?3bqSa)K-wQj z)JeZq`e00xvmPi+z@~G`_wB|7^GYZPHHLsS#TN}@@8q*YFn%Z=Af@3O6?cgpibi3I zYlCA-h*_yp$M-l%Z~3>UOa-xycGrS|;N3P5jCsLCII7YX+8T1cCi3>M&rKW#u1Rk; z`|i@uybc{yDDls86<48F#hdEh!QBwK0Zo*o#kW#Q4`)23_ee@(P#2)YqzJ<)tNIa@ ze5z)rlIl`a0m*O~1Qx|`^z!n|% zaVs(li}WQ>L6dbsO$OubASefRfTnaUT`+RHurr|1RBmZW9t7=Vdp9gF8)ti@Q^|sS_Ai%R!==29MT{gT7x_by_m69uxfH_MW3pb{gGtU@6+F%~<~- z5ldmN4~<+`3>6%P3@pX9$-ag@rulrS%>|E7TmywtYH$xWC$)-A6ZG5T{+ZkX%rmKy zULIKUU-i0hX3$?}Fq0R2SIp^1<$!jwlh*D9K|O>MF+!EQVE)RD9edpLv$h%FzQZ2n zQo!3%a!%oIEszudV+dgm1;6!wsG%n^FpircCW6V?ttugG7f}xD@QYZ=t&pXi$T}+= zbI;c8|0o_K^}(0Djm&vOS6($n7i8sW8N#qS$=13RJGdEIf)K&Z@zs+90@ezUpdxHq zC2%z(0u-8)xE0U@bwZtsHS46_jh>d{@y#9nyZI@nT)HvIW~(P>u!1-WvJe=3--dbm_x+Qt<$@moMMJ$tXt#d_T@Xfthr3R zG(+Dvb1?y`-As;pQNF*gPtLiYUH1%qet>dnhKG(hXGwC_%|B3rGbr^ku&5fpT6~={ zh5)vCx{yxurlw@*?`g{$tG;>He&EWcE+YM{Xx|25Lb1iQ#dGGBP+vpryF9wXgmLEW z1)#wlG7BE8Os9qxBY zM6~?$;Xg{;mP)|MlyKn(FcX_L+1m+fHaBz(Wv~hF%;k>!=a#`WFMq{?Hj0j7_DtXD zhr;L3|AuKH2K>lHJZO6NwK=bCI3bz(SOqM2}Bt64Ke; zH!Q|LB6un*VDrwY*?W5RzcOAXC%s)(By9r^&*%$@<%T%xy^;ea(DI##96etV@Aj2u zKwGi#1>E^|JLurqaZ`_@={_W4)o74bgh2sd#GE@<<+Vg%80T~ZCZJ2NR}T`$KlIO4 znVWqr5EDSH`(J?kx>TddnV^n=OLzY%IaA=8%k-Rbmfu&sLGz} zURB@%MnxR8OPdn)JCeihf7tSHS?0zd^w90FN&z;(k#9VU4*rNKDttlW-j^p8r`U|` z=Jkc6y~dO@NO>%~u5UW{iSLXaEQUErV$64a8vD8!2}^zCntyoduMHo2X?RkVeAvqO z!qXsn`o%)G`ftH*(kW%qcp->zY$yj7hWJ&}oLy8v=%-)q!(;$#%&V}zsE8*9MBtmZcyhD3rTL}3%S|$MxcoImFur8E z$gaBMCut8~Wktr^X`cyO-bzo6eH6z}a$r|(ljJOD%cx=RYVQI+lkp~17DQhg!=C^A zHETu}?aFRFlX{gD%_n_J_}(`I+~RdOT|kBTz=slmj7*6zRQvdlx`4v()R3Br>g#6l z;vRzuQXDs`x_lxgg1N^*^wB>R> z*dsyo)|j2|t{KD%_|N_5KS*uAQcJLw9i_$~5Qg$0Q{D00X_ViUEW4TUsf|Yga>#Lw z1C4H1n2dlY-Sm_oEJ22YtSBVq>xX#1A(ctgm!5a!ZN`D#EIVDakzYHU zv80Ee5ms{3rAtNzRm6Zm-!8#=9@!3WUM4FV0$|FBu?QVxwpL?3!ZxL2RZyE;uVqE#EP;f4`melTfa>cx*cKl~d zcgLCl&E^pS(v{yL2vl@oFV$u-^o*N}IjQqUZ-TxpAC^4gcdQ@u7umrop;Y)eLIoYN z0hUAWzE8^_XWW!&g&LLzbp&^7rA*$kt1ZzE%C}9!Z|f5zt_GFG1IG!D^|`5hZmGM2 zqxORD)61sqWKC8c7^0&WhMHJLhBLkxK%Ku!Hz}s;maAfMbw8Mga-eJ#yX!3#EC1^L zuPBdwhv*=E2`vv^ka907XaKvWCns=LiM1U6K8DP31V@J@p$T77G!K0^g>*-dGa-0! z{#x96<8=t_1-ph`|9A!c1gwONy`Hj1kuX-CHVNQ27E(r|Un6OxD66@2l&EMrYr_8{ zNurvbI`Z2=pI2tQ&VvHsLDE+HU3Z1^35J&TSaX{FZ6UNq&QKg7Q8x6xxd zY{1Z%GK!->OV#|aK?a=H|8V^r!W{Lla*;*^V`WGmkGS`MoZx4hucF%p={u4SWG1M^ z`mA%4pK3Ea3vTiSW6W;UoqsSPh_^$iT{spWoYC*Ym_I(;$$K{s_6M{*>^7}fjvEgR zrIx?Agf_Omj5=IbRr)FjKc*R%^4p~mYr=iLGpY--_ zsYRjhZCZmW8|0+x_bqdkFAa%CLD?6VZIZ039(Nv z;)Yoo{Po>&`F(vLjXiH_^Vr<`PD!imm;M?5kr;L-3p5vxi3(|$ZMwVd1I}mww&ySY zf>Q1Q(yygWE!0+Bv!#6DV(&I9zu@J3Mvv?Kwk(L*-r(#%Oj!}FY=8`9?Q5jHZm=~3 zLh8v8tR?&*VN}tYfJW=+iNKE;h|lnfS5QVZU^hliwxYz$shLyz7m2kPC#*b{o!E-X z&4oxju4lmZtIPAtI_9A7BB-fYQhv8c$&5)XaEEH%KD@#D2eKvyrr73nvqgWln*JS} z@xM#oOj+-Q&wlML3(&m0({f;~13aJRyA;=e#?X{r%y3-@8=JL=S#ZD-)}{Zh>cqbj zE!g`bCpCMNPLUAs-NV*_S*K9NeK+T)pcaPKL06tnRWTz1_P96Pzf>ctyK>xjN5`8U zUhBhf&hA_#RmOkFloFaB9!k|7JAerNZv9dueQzCohS*xArG8v}=eJeA_!niK`#{W< zLdzM?#^>nu>4xmQ>9OOE3V!tv$isSB3LvT6sf ze}bf;xRP&4W_W8ZbxbMp#2xtC!<_ULGAP2d{2|g)VVma{5wSDZ((mhP&ml3Tt`WGFaLoKm(x}Pc5!M*_pXzs)h8O7(0rd_a1Mm^<@dHiA^ zF-QyYje2sGP*&d?pHdH4P+coELmnd|Sl{Z$o5E{H2%nf^SoKjeL#u4LtY7D75)-C*WP8gz2?YCprH0du-z$p`hxCmP zAds6lVZKNxNKT(p4C~91bhaABd)(f}4tFbm_Wh57*MJOc4}H4=`fr$CEgKd{*_(Nv z<6{#sPm{K_Ct_k(L~1piJ>L5s%vVD86r3`0Pl%%r@18~wbuKUij$JV;5U5l17fcS= zy`!S#rq`uM*{NN@{Rro4p`L5%w}M1~qw6oC>f?RW*D$Y)tmu@3UL6P2c{Bb>p3R}48d*8Xn}H$ei)aNhss#a&kU zGB-E`NZVK-Qb$}}0|>7%V)`V1ncImQ7AdfEiv!Q7g6`ykd#M(56}0t$$WQLkV}AEi z1k0Fozo=g%h$w)hIP$_j=XMUr&mI$E`$iM(5%3kkcr5Y}GI@;!J z7JL9B@nb4I@*Mpa`AX3Kr>Rz|x+(LZIdI;Q_}l9>U>_oM_1{)U3LwP?Xjj;)AI1dk z+g#+;ar&(R$bra}@SZ@`aVonPSCb1tVe4d?N-M&!oXkoU5cZaI!zZ;MOYb3u8 zrtBiB<9$m{#maK=HLe{471(5vsXEf~Z56`4Xl534wyL|Mbs@`M;of>WJ9g*&107-y z5_=2A&g+yv{Jro!H4bSRasx!4UvYRn%tqLuFhAA8c*S!tAp%MgX_i!W?K)cZ_ik3! zIM%qNZ<1xKrcVN^e-tm*CS}!7wfV_C=cy(6o?pFn#Cnm?n;XZ8BP0V_cebQHJ`PXs zNql2vKDn9Vc{M5S^cnuzaN~})H@hyNn25P(-3(*!1z2iM0dgNMqBh&x8mhxiL5aDK zGeUnI{t-z6{yGAD?&dJfWjhLORQ|rLK{3^L>EpG`PK>}#CPOE2K(B1azL!G{=FO5= zEjjijZk=tZ4Y}e8SljWbNQ{$ZxR8}cpy&XO}!mvLtX`#e*V z3exTA@j8-utfK_dC6$$9*m5`M57sHGeMb13b=$E-}R)uKw4iX61JL#aB)5jqT&On@gveX4J8LlZX?@$`#Y? zfsWf2L@PN=nnEOvj`#6r8DQ5-{UJYw1V88!+_<@HE+<}G z;UUyJnJy}3jx4&?ElgAXrO8GIHUWaO&j7s?f zpz!x&vWk_#rJ&A6d7H;@4h>!J$SYnels9HX}!$(0QGe?{7Kj&L=1Sdk^Q?M3$6(mXnSq8 zip_mh<(Ok}ZiGYLYHT)ia1nR(t<~yPBna|QQh>zTjg&W^MR#1$NgwU7BFoLhzMi+3 z@HYVpejVmFb2(!m^~}A*srH}`D+>s4B|YVceG}>Hp7A#q=OaGW@VpXgV-VrG)D~`s z9H(AC+P~)ne+(83jUPVVEXp+>Ss7>ej&_8yq}Y;uGd#*azbwQk8sDyPBE#%P3#Y9= zmoyls_84S+C2bn1H}+ZCvqE`@WpV#^v0F=E(^-@D{Iie-H=a$^;w{l;RZ`HA-_(1% zhg~Mq0~K-kE~40x3Mw@OKDG`1Too>YJ6BZRAX{3aKh(rfEyqb13A!Fra>-?kenrX5 z^;AXYSBzZw%TV8Ot!!9K-@NA+V4TBhG{J+82Cb*Y&^t<^%7DVk;G*X33Kx1$4+~YC zps;lBH;#8b@l&R?Rw3Wn`r&$GW6v{h-0Ls07&jP3HED|!J}GAc57Fa%&@{-6R5rTW zl2#7QOl?Qx5qH?1ULFSk+vOV-O0G{BZXjQ?E^ILN*?;r(D%6&U!l%1p)yJ(3Twtms zN;++S;`MzOrKcTwpfBa`m(FE)W?VKF#IGmJO@RLRQKMRb(Y@RlU{iWI?n?l#7={&9 zNd+S85!DBIljSd5!w2WuEMyJdG+x0bBou@|D z4Hoe26?0pp$~W&< z$~AGU>Xqz!%IWytj|^K9u=eu6hgzc+m_Xe zc$ulnIjQ6WP>$dO0k$2F8iYsPnUn)=+v%deT@ zdq$~$m_KFJsPf-Fg=1tp_4yc%VQggAx3A%^CC&NmE7szBbI^NBlbBAVAg@MPa^!i| zVr(pA#{A%GS7|ZWJ+44YgVzv4ZoqfsNB3O56ct}*h*EBGsBN==5Vt|v!nj)9+$`{dRivopnp%Mt;led#-&HIq>{-=9`Arg=X6 zD*gnQpL$hI=GVK6Puq&0|5*!3U|$w&PPP9sImo8TiE@_q6#n2adp+BDf4CXBWnQ0p z+kgCI1_`@gAt1f6=j6;fMs)m+*;{QV1@onNciMgoUr9N&oe-^t;Z;LC;2~8p8@$-Hg!S9)tB$ zzi)*pD++_l`u0W{#_b&UEl6!4@)-Lr-TE0grg?a&%?za{X+Q()$oE+Ez@GY9s@f>0 zc#(zoyq}$SU7Fa$mFv;H=mXdsU@XNbYg|-jLa~6F)eHaGms@RR1Rg_lo9b zbAay@^YL`YZ3??@A>o$5c-_W%=rP)vQLG(hLQ_UbrUPB%J#9|W$BrWCqAzrZm{*%C zBt4>z#aS%WRwIxQ6W|Akvi+RemVk%PPqp}gB~xaV*Z>;2M~O-B$$OtL0t3X zV|w=bn#;wc-lD~^izjKeheiy9@Y$ML7JPz~*-cuTVV#GTz?4^Lvj&Zrj_+v)hEr&(#I)2XfFROzs0O0PpdXvIH$0jq#T;R`2d6?pqD03gqb4 zg-0CN0ix#^{zNFE82qf##+|;A?zHLmwp1OxbVen;8Emtg=u3}7c4letQt$FJf?VK1 zdIjmbnfl7xlWopm_GmM^xYn0q6J)(^<1yB3x!ZI$Kw1v}{>Q|odc|P7Pa6Fnp{rV##lBP%%8_xt;$&hCyfI>P2rNufbJccr61ak^RVY?n%5$NbV*4& zTktgKIxkS@9%KU66_fBYPz3U2=yJ~AygEA*IhSji`ehE3o`xj%`+r;aQyJ(us|Z7f z?`s;^>a5Sldh{Q=z>vZgXHC^<8PaL?BnEsK=AILkUYx$z?3R9MKrY&hLP3zTsWUG= zJL4m@_M$sI9uoefv%v9A#u^W1VD0UY9zdtG*Xh$?^<#aaKj1l&D@An3@-*CXE$}wE zOUg}05BL06jz1Qfh2y7S&$RCFcCth-2+2KK+7;XCXu9rms>EE6R1)!Z3(|vq^wQ_M zrOfMdQoO12$jpE5WhB!G{gK`;-;t_M^=<5>Zi5o@E7txxKj z7ll<)lIzn#!paCnto%?=Mx8rtAMX!oz1}+JIFi2D%>??tBRg`6m6W}U)`p&9Yt5^+h>f`5 zi^`!inX{?5L@vJ;f2RmU47+7=MPbv#PW9#I#uaH`W=N150bveS z*7(-(&BPF^&f~e`GL@8_`jjjr+4L8~6`zM_M_a}-|49Mc=km{DD8LVDiC-~5C>X76 z9@;F*Z2|1EX-6GbWTjEZ2FaGgzhS%_1gF0PnC1q$i}TJviW z5{pcYL7(}LRX)@@{r>vPhPztt!>8-aKPVGnVlvw+irJ$AcnUQw>W_Ob93tMXP^0%? zj|t@vGLOtX=;@%^y@o9K{Hpv#xrV(KVbT$Sv{j6D3VrRxu23{ZBiZa+1SC_?H4EcEi}UN&$X6*2GQ*)#_YABk%GLHD}Za=8SwYJ4#aP zmuB-hs@b6x!C2Z?VLW9K&_9$}M|Y3GtG2&qBK1HkwpK*yfA_ zhbL05=#1-Z84;q;FRgtR9+|?n{^>S~w%@AludB2$i2+#XlM$`bA@;KvIUDdkQN)V` z`Fc^Nq}|48B}bqzc9-CF4$sf}pC-gG%h=3U9EcE^;b--)uO?oP7xI+`lo1?8B@d;b zA0s!0QvYf9z-#O>GbFy1FPvxSjmuDAE>XV1+f-nhDg5@L(~y6%no!T8UamBw8oc6J zjS(^2_?WwPCT(FheSvw*sV$eIz58LTE8he$~k0fGIWWpwxW3Hy(8g=RwSe3 zhIX|Mr|1NSPN<7OfjK0?tXtR6&PA&iJMrF~{QI^18XB5d+MMW)sy`Ws(RE!NWUtm> z#DE%LLuP0S*ZQ0TM`Ijx&@%UJR(Ju`N4Opnu3VqPDTe_8L7JB;x(JmwsL=vviR*Py z*?0Q4N-oX>r!lf@WTe)NP0fOAyt?r3b}ovqggEVn!_n5j7G_BjFO**PJeA9|V|@-j zUFMG{uZPH{|~T0Prv1P$?Gq==DgoG=YT+?0Jxpcz>l+h(5FkE zSU>Nvh)_qE(pH-y;=IRR_j4~mIR6!jKVkh%DPu?$khD%soqaJUStUiTe#H@oN=@AOixwyAS*uKWZ$R$V+Q?lyI>VJDq zY$CF&zwjwj8~`q84{Jo(1ak0Qg15#tyn4sx=zW4fkT}Ox+>Qk(XaUD-_yGm|8FStQ zg3)2lTlUtehXcTcAp=#8!|(Fv)a%{??#1F2&w;S%=c@&8qbfjOS#~zI{YF3R%el}0 z6Urbg5PrdhKPNvS%W*?#Hi`gmVwMVdv-;O=o2fj+>r5V(hnLd!a^8BAwg3Snm?qs2 z0_Ed9?>6Nc%X+<#eSd4a$0Cqrxz>7V_niA}%Id%Sa4wO+8HlmtgJC%$BlP1utktIM z9kR;L7Jwc?MHhw(M=BEDHePkZsgC|DvuK4!3#?rfo5YI5l*h=xs%pRqe(6Q5PH0N{z zkQuSA50w2kXj0JOeiIGE`I%=f+{ehZLL2?5v%Pyf5jeG2~m)%S*Vv5;AmOur-BTkCf} zHa_`XNi;efZW+x1Dxo1Exq<&R-{YBTD_xpQ)u2BGN{}b?|EFbde(x=tWdn^Lf5vATHB9-%{ z{&Oz?K|iI?{N~)GaJzD!5v$p&`Iz5<;LQGOSJanN7?%k|hhsz+l>oWJ;#9`TOA>)| z`*7AtSNlT|$w{BKbmbo=>pA-nzs3pCbBN*`Wx(NRnVui7(zE9;((Ku1Y5nqLY9F!J zpUJedcZet5Z&G)EoO(M57&_7cTCwk+dV81^0s%qw9OTtwOpfu;y2AUh&YXhbQ@|U4 ziNH6*;`O2UZt3C^=nwT=({W_S8!hF0=>uswG z*McD0Y-gZj-#y>3ZT?OTd)dox-QRjVhXWqtg>F<<`k4&Fzr>v3{1WyTVV`X#Ew-D) zeZh-1{+(L`wwn;{C$}+S!Z0tffLr4{YsD(JRyMiMjG+n!pI7g{{ryl=jF-qJEL{!7 z=@p8*E4_~DHZ@x-xlxf596wm*?^kjw;vSUJz;dy)?2cY{19@zpwWk9Yggf!`@ z5b)bKl~O`dCngsi$B(!4hi6G2^_79OR`iKgXTt$1T+960mPZ-vp-nW7u9xm_sVDW@ zymD&}LdWNBu#s~nSCV7(A0c`EY%k3ZcTfbN7)C+84y7*iy-gU|F0Lz?cywymBHUXW z3$^yqQ^I_G4ec25>L|Uqw6lxF%OiYVe1xS7?n1J{_@qZ=PJCsUPEKF1#(O!}EpeVZ z{|*uLrSPTkXbn!b((a34`rhfv`V;XnunOqR);8>8r^wO;}kOkEZGPaFM=w_B4&Z z{rhS40^#B1w?ywldy0V3dooM?htt%1#PI=OqPr1Kl`lKwWHqwBg3p80^wGYrFniQ< zvm`2qaDo7S^;zmX|2g3RSz_##2XrJhS9^&=5ZJQmF8II0+u6T&I^YzR%b;SU`*c?Z@4HqPV%Pj-Q z7hL*QPus_{k}B~K^cj>861b?8!L3*A(Z&EP+?N%7w{ZC4-oruFlwX10I!dwF(@$8Q z^qjft8QBnZZZp9G1pD38+5ag+!}r!DydR8OSQk|Nr1`^6)p)6Z5#EjqytW z#I`G+#I&)WY-=|NZm zSXTicMxLa4{iOB2)WjmbkP!ae-*4T2Bf|Y1q5$}E=UMv6{#WVm4S$hd5N@Hp$LI2} zm4*)pySR^lh>+MO3}69id;_usO?q!35PT;jpvxGyjRK(W52pPNIJS5;PtRDmT78Lt zJ;t&Ida}DSOg|jW(trp6Km5TH*h8)0GJO`i;(oV)W-bD%oL?=D@wEjnqnRu`X$$47 zxs7JB4Q*SqEw5$B*z%FSd1RDD{&ljli82bz@ka3HVIkL)(ibe5Y9t@xdE3hym%8P7 z$?Gq==DgqE>vN3)VEe;gKH$@(PqMAFd+di_Fsz&_ZE#AP^VZG3Aj3GVKc@Io)-OsK zGayDFdKUhfst|yR`A-N;an37icvSD@MGv{=`SQe4O8a#Fr!ruM*=5f71%QYySyj~s zz#1!tv_MdUL2QM^0*n>rRk7-i=~W~ksBjhxR)MMyp&pucNKIVnH7-(es;%dLBLH|A z4G|JiO8}U)7ED}={hVuK2+H)ia;$(KeW~^n+cydW2bOV)-&o69 zCIA3H07*naR0(&ERT%IcIr(LU0Hq%NS)EQZ<}Snf8J^A+e-r?%0ps4oG63HYtq#{Q zP7bqKv%XM}JA9e}t2IZV*5Wyu|Hha)t|i;=`;cNh%8OP9)fkAcZE&ZHNpu$_O&0}$ zp8q@0qb}#Vz_EjEWDz#93ZUGpDYpj!3CUS`drvs?PSV7B4uXsVn9syqrk}9NsvVzs zuUl%&^CS=m<*W7D_Ei zfQn{F#sAOVoBYbwY>8bv`#kM!zW%*>^ezbIrIyW9ixVf^te^N-14fe%A(%pnu#iZT2D<)gaH89i2cm$6k5?B;;T0g&P4 z7i_P7Nx^)p9y#?o;?SN7J>-I5@|s^;FsxPz=%~9=iNfmvlLC z16Q%_7n>B;?_w}Ug&ojuJqKQ zO}bq9kB} z-NaWov%W6RD;~dm>$-ROlDBm0kJzS6%hyOD2lY%pgi5~|Osm6W=5-lQFXf); zdutF53IVA4%e-&%jL#@v;4qA;<*~v)qCcxfHl!>X4J)tb-&3<)nyyRdol!cD_8AA z@h} z0tB=kFblp~Axu>M-rpe_WMgm{H?&{%w1xA?m{fWH1h_m0kI~K!_3NX3H_!lJ2m##t zk2-RQ;>yZ@fkB?%x=TG!x)-fNIvmzN{;=zg004t;&?OrF)4Oi4=(VdMOrPhjufDag zv2`C#5BO)x>k9Hv|MZat6#w)u3Xy-6q_=*^oxuM>TEE!$}LTRgzIRK4b} z8-J}!5E6*>GCi?63D5_S7o-#Ac>flhZ;^GEmD0+8c+zGNAny5}&X_ncyfqV0$mq9wtgfJ5)m9B#`b$lK?4j(%?ES0S!@c0Cv$;IWB4h{#+8AzGNFdSM zZ3#4l4@zy@yYv^6czEB{hd3Ov&$GwgK2`gj-8v*l2#SPMMK{!}H%8lh`;`OcaY-Eb8m#(AS#=Xdq&t?JTu_!P5 zX6@F+%j&$Bf_$h>^fI5nbc>4^kLGLM$aK@{^vK8jA@ko906440cx6n)c$RX{=ZVAk zw^ZeK#Xrk%>}%^m_5M8niWQm)^~{zA9{Z$g9-9@L7MdVx0JOud1mE9J=yykm6O%ii zdo{t^Muj^%gZxGr=8a3&k@$iB_#ON{cm*`}KcSX}6$EJiYJdZ}cipzI<#`)hWP1x#G6k2c84}S*HYPt5px5NPnOATkg86(^l_5 z*zCJ?9_1G+{I1%=u!sCAjQt_(b(>FT5BV>2?EoKJzQE^h>vGGNTfbtP7xO{8_HzUR zQ|_Vvtwz~01h;f74YTZ6d;={N>)Um=1fD4MdFNl7WV>vufm0ImS%-G@@hZEy`oD9| zK4j*k0d_b%g`-<*-xM93Wc;bu<_E(&H|;(>DAO;?Uu*yrA%L3!+{UsDtwiPy=87N- zf>xm~V;-qn(S)&P{5~~uTbDQQ0l%Ssjg<2`jt4|2Z2}(>1S+r(e$_ z0C=w%8W(tSx^QoefTjB{OK{zmxS#^eW@Uyci*8dd%oL1-T%|;|pEe9|X2naeLEQJ6a=qv2>6_u;( zz3gSfrmL^TT_J(b{Jh&qxjn$h(GEtD6iTS3Dd9(b+-k5uYFk!-xE6s6HA80h9n`}) z%4MklK!PwBbJRgKh{{Sz5W2Ka{jVh}K}*uYa8!QkK%`Uz!)F(t--=o}p0ROtoWl6m zbI*OW!Ig45%Bb&YSD<;#?Z_YLjeDj?d36}q^^dRjoe{3xFwOU0a*i>*iSbkJuCDW5 zKIC=nGr!kT#NlhEF(w|;W&C9%<0!tIBS?qH(lDRQdNA}+7WbXNg5iXj58;4mw_XmYf=*Z>&5s9O7keYF8BQ$YZ$)cdU5NWW{<7iqm_eWMGo+?#~lrEXFX z5Z}nK?(Yn<`5$_i-!{G(-^Opsw`&1IuKxFdt3A}F`*0;Y5I0&I-({Q8lWjEEn?8(xPVqJ!%FUxNv%@qV6V>Mvp=4ujeZsMUpx;2ahuI1fS$NB}zbXwwi zV@?#H%TP6ZhbJrHc7f?K%JXp--$#LH2Q(tyRv5s_zpDK`j=A3Pq$_0b3-G&mUje`n z8vw(D3n748z0h!3V%uUleNcqgBzY9r0^H*~teui2nr)$mPu~aH2G7J9@%BP|C@cJy zE>In9qAfA8dhJnv_!e6iy4bi`j_7xc|Lu);s=e8;+C!sZNE-*jWeVh&19B_QTh`#C z$W9N(pUfL;xGN#R6m39{09-&9fYf4FNQdt#t)kJt&_Ja7-}(D~6utXXZe$I+p%F@4 z+yZci005zor$H=O#A<<8de9M578=eOK^}8GWqZIByy5mj@j;hWh9Vq%S7dN?KZ+7W zco&+$))_C-aJz!Mg0vH(S^)&3*avXdi@0+|Agq$w`2DYl|2KGf6?qnUE{6ig#y(E0wT`uZ8i=)j0CmPbfMpOf#$YWeUKLw^`e zk->xZ>OzP09@0^6zf{5=3|L)Tdo{mABMGb;NVUZ~?IxLddG#JP2RfV@u%I3V_euD9 zt)amaa3jY#srDI!D@Q?fj(GMt#40ZbDQf-MPsYiv;bY}rWNI31_NXY%8jN@xA7$md zk6&;MTAV9wopNYUvH6t7g|wj_4kBL}(Vi8yF2uw8>RKoeCk;?e7#TD_^$O#Igprqf zfxI)1*LG0+)b}j6zK&aYFVnd;DVc@{#m9E24;ZfbOfyVoKPYdrGya(T!T{en!V~YC zresJ}e)r{TZy{FkNrS+W8E?a|w|iRGhM?x!_iCuG1(EHRj#ix(=^-#sXuv%s-mcK# zJ*KPGL(TsX&9#7qd=~Ze{c%|8ZgEy`7yyhmkd4<_y%;AH0nh$+y&?ya3-KhXuG+nn)K%mqIgXYfFBi(7F;g674F15TtV$D zAo#TSzhIy962Oj?|2kg)dcfROWo|yLFvM6?hWS56MRK$lhS9$h2%#TG9G`PEuAV%7 zUVZxmXmJAd5-QppyEf!Fw!;xLrnkmiJOEny4=DB;;U|B^BwFoPnLD&(F-XR4a!wFns|H5h#jQ^|0K zh5(^?RZrDIwL$`)2?Sn0;}B~ibmIy+%%|frej=T;C}VYly5)F_j^x^Vbv%gfY-n^U z_qmQ$eddJH(PSr0245@u9?6&YHMZ!=ze0gAEA$}%a7@U&LtyQ}xbGkYP<>x!-=-h{ zXtVm_RuKv7Y+eWk=$cr8fx0fuQ;2{+K;55nn_F%|r|uy*pq%c`1dIRFA-aQaVtpa1 zwWf_33giWh4_@oO;g}Q=@RYu<`zeGnR>}hG$mmSM582TnGME}y%x{SRpbhii2fhy` zt?G-}0Y@Qm+#larX5$bsfY!&|8X$>5Z`K`T%x|)FZ`T9%n~cB1zX$+I9JpA)9Q_*b z!XW)IkY_6x3e@k*Bw1ax<+#s04#;=hEeLkmDI zPCP3j5yuYT@B-dxBU)?A$suzCFP>O1HnEnRz|%cv?t%FS$IrlZY8r(?68I`m1j1?2 zeWKpCYO9%>?c>P5FgVETyCeGdMW@<%KCC`{`k*>Q2+%w0RQuyyv~UmrOdnMb&kw6Z z>=^9PUX1|iicU^}$9L-gDCNWap?BeG*wbAL06YmmJ%BTg{2R47UTsGK0QOBDx2nF{ zg$$9-4vP#)t86>;!y6cWQ~YYG2NejD(hX{a%s4q{wg)ZFA3I*F1+>Re|BPcI6##Hd zE;O49Q*H2y1_Imo4s@MD@hEtsJtpmfK$5yGK{%q0w)7e_P%Id#wFhnvnn#30qvB{l z@prgu2e3TKKfueg$h(M4>x_SGVF03X(ZP(}gd#9txVyY7{5oz7c|u|J5d3B=Y2M!>!QXAos)s6`&5`v2niq8AC`Z@Q~(KI4&v zLzb2dV@28yAiv%fs~}=|uf4!O2_;`#)M@nuP|CH#%!s#;lJ#-9~ei_ylcEy+fVfW|0=nGOw#MNaru|6SoU3gZnM|NC84L#Z@)ht9=Mp zEW;TvaYvbIXeh98hEIkdBu@6(N8tR<@r@PS@J;zw22b% zz&k=~3c;GfPjO%3QbEXTs}(@)4_ETsseP9tDit9&*`FLE9Yn zr(r)CeE0tke#UWs_TO*?vCc7gg_C$SE2=Tu<;Lx5aMrI5j(4j^M~B3F z2;<6ue-9S>aUAC^B*qR<*vIQu<>ML4Mvr6Yc;d`t0Kf{mR0?-F8N%oYgNoRz1 z>xAvE=bQ+@*depb{}RT3&bFMe)NdIZbfPV=1Gr6L1U2E`SIiLvxA86(Dg^Mp^ep-a zWB@;bx5Gdngw`vt)87Y={$qFvFlzNR{`c?{5ZD~#81ZO6abK&qIPV!Z^uB3%&oJF} z>E6$KnRgq$rUyhtTlaoF;GkP~nP!;r%#&%&&_SQx^o&aaJ*gl3%XNBv`EuZcfbZH3 z0bK|uolvP?FkcBPHMi=sx9K$gmo@-q#KW_KI%U;&3NoC+G)z$=?zl?A>a1j$7Q|Yv z*kS-sG!py&8NtDLWp7^Bh^rddOryt}m!-c*6GB`avkPki?yw|QGt5u*~fD!vj4MPAxx(ua+WHayY^9cwEA0JmbSkq1FfVL*u6Ii?4rFSE~TzxPuMAT$G5{U50TP(OzTNZcQ2 zg8|_Hgtb}$@m*-D(BtO`&!tr@#4LA`5eqY zcqrOTU1EN)>DH@RPrL0MTogeSiolWr#93%5b=-H%Rt5dj!9?-F5FgRS7v5{FzKiUfE1I4TzL+cC@%z5MX4@Qh(gRn0PvKh6cv#@)jEMzw ztjdjZXqFk;h%*S48FS+d+Hg)Dupy*_bfmQVO|(P`sJK}CtK+`62pp^fu13U;@Ywqw z$f-`x0_tZQfyhH%<)7i@U49pDn%<`}Zp*}YrZs)D#rYP~j5qIbd1adETla=N;HcV}6 zrBbB|5ibeXm-`-fE}*r%#A_iQ(;_TNw5wBAyH8jNJg>u3nBQ}epvIB3;;x7Jm+_19 z)j^c1XGX{BDtRl!n7Xr}=kSGTQvsz(TD46$T=wXVN2uGms>U3T# zb1$4V))qHalk(`%jNbh(W1ezcRte$cDR+|+T zSJ0vGq@7c8zI5-l|I|*6Mm~7#>1;!SPv~Mp-S8 zRg~`xD~ph3p~PN-zpJ)|Awroxl~Fq*US_|2;Lh*txAhyU0iZC4l?`;Nu?2u80N=F_ zI#XO#ga8Tv%1&cC=>zYa+i9M?SlGB?$jyxvKsrO)RK_}Ugr_pB5D+*gzF8nLzTc*u z665N35`E^`9PbcGWUBcJaZ7kAPwJ@3;542D!M5n=1aobK<|im6X3;m#l#IMJhfk z4p0~xOre4WwmncE_upEapF-Rdb3n5VS=M^k$g^s*Y4%gSoubVi|0OH`ZmsBG*sz1j ze{a&Oh8$bF%eK1#(5L+kHE@jQ*toty>y>z$YguJGDl6`_p9ZFfUzumGO)cVCPAec* zjDlLD>pJ;u>agj&vPBvIwF2PZ7^AfMV(pz)JItM94C^^6nsXnUwCOI|mKQzX zrw*EeF`x#b8c(iQlr4%f`ivvC$+?YW!s`2sMV&qZ0qJ0m2fToro9@s8pYji(87yML zsrv5;CSg1~AoaEN_#=3c{{t-m3-|{AJ9t_zH5>()Zo}-FoDh6@bXA?^eO;zE!*XZ) z``$g^2idwe?}4k(cBWkwW?H_%YX`hx-t#(r-WOOL@ZaKfe}HE>_ij*qn|tyuRG`yHlDND?D{UbC~@ZgwGfi=~Gs%kMLvC&R`5qSe+PS z_-_U>TxvwjRpAa{oZk*JsdUtd6oyT7q6*a|!+-Br*(;w8IxkUFGl%s6na3@^6kRTV z?jpJTJH~*6VYJJGaU`e0iv{YL<~1$ukuR7$#k(S2tuf{EOsIA-GnG+5at_N&D(f~Ty>;L{UWcPCQlOzB zQHN1VNssYHLvvqm=?L%9*qB^OzDVz)9*ez)s*RU+C zakbf3=?M;whp48ZbUHM5+3!zMVm{=OK~lx)T=D zi&z)=fJNj{uq~O zfnXE>q#)02RBoGEAqig;4Kvbkq&ZP3`16^-XWXXUOZFQrXrsps+Wj$CXafMW+GXx@ zE0J}7BUiUM@*1Z+c+k)&>zqQgE1*OM*O?$>JAu)s&AV9q-^bwQ4(k5<;3#3Q82c;G z7iHbZPoYmN+L&Wf=6M9$qx!tU02ykTe#b3VLa3Xl+j%PSrhRQg4e!=jixgl?XaR>7 zM>|mHj+g=fw|6)P#gyr=an5#ry8G(iZRdS#Z|8fvy;gcv(;>0QQ>QsbW+0^r^vxLN zzpa)|57-5lO_?h_8t^93^2?usksUmQCx*E)1&)S~Z-XO40AOW;7<&21MvA=3AK?E_ zygba$@ls)6-vC|#Iz1CYqzM(K30nGe2`#1>zbeeUhMA|CwvAuY1EQp@d-op5!I>rG zb%v%J&lxQ9<={8W`+f_r1r*c1$IpL)CCLirRefFcZ-vl6#}iS{_V zI0Zl^%F_4=74~xV>hj;=Zd8e~7ZCgj(Nhr02unv#+57)nEP+3nVF*yhAM5+4lYaGV z1W|B$RxM6Y?`97rloGVm82S`rZ-`ChsWhfzPbpCkwe9T1cc|klAF-3__e2AHj|~B3 zX{FU|-YjPp1T7l#6QIG+aSvu(L-0k&^%Npg;!Glqj;TLa++Tb~68R)f3&Bgll(o>1 zT2QTA2h~t2w9LbW{ca}7#N)$Ai_%&dcnQ$B4+5vtmQo>cO(WuCP`4Ov7J#$vQ5d1(AwgdR5A??qFC`Ohw}@BDY=A3`j?X`QC+he%^w#k1LT zvgzWRSRLZAY6rtVeKDwJKVU2j!&-B!+RG#?I|o<^e_Smdeu^drAG8M(VV}!94C`~l z)yVkJTnzBKQN|tQQ@+&*_Atm>X z$1wTO`sh~MBf})~pZ$u(clucvoq%@-AT0%pEd{LZ4|jm0k{STwYE!_nqkWTK!m=3q zu`P+X<3#*~l+Hc&^AW4<$Iy)6{uWwbZ5Ux;d(QR3x!rL%O=?yfn1kqRPl;UT~9Uw^|sL?S4c3PPjfs&^8^!k$(@L z?pL3W9#ub|KdyGr0+7jeoIHxdI1Bu#BeH2{)f{1Eo!=>t^Uv|eu>Vgv9pMF5&}ExV z(iRygySCmZW4jb}(S-1>E#{|7(+?!`(~1D^^yH{2DqN zfRn#n!Z>zVxlx)M>85#;pJ1Tr*SwAhsB8hj7jbXIO#;$a+XCYGx;!#?^k58yc#L!# z9ZN=rRBDy(gY>T})X_2JI?{rfca`5pSO%^}tBaL(0clYmo;UP9t_+jo+X*B03qja zva&24<)xfrHLT;k+_NrgV`Zh5Y4>>FGH|wCW+G(Pek0T1nJO6BIRb#m54+Xu8EXHi z5-+S80~yud^7>c2{ha_rfGdoS0uzoCVH)OIwfn^g_&F&809DvK z*h^V(jM`#^{TIelOj$mYa9l?(fR!o*Jh|z9csIw=Qv@s6X|D3wR802SYl$dW?g@K#>R1`0A z@)~V&GB7q-ygXfA&rFBizArVlvRPav}(t35OvD7zBo(Ggs}tFA>{xPCFD` z{76d_X2j}044guM5y#WcIr6Q=r$c+E9PXF z{}wn;xm6cLv(o5XA>b=3@=H?XUH%v^FY_f{Dl3_P;{vuV5qsG})6$uyYqs3HUSAcO zH(ln*>uq>V4{QYh*L2JqBsT}9+1IZ#Z9Uy<2fDr)&osklc)35_KPtg%e&a1nOCbcP zSNbLFpoW%E6=D3(J@f#%f8i30UQ_h@-Y#1J3R|Zzz-<6!3qY?rV&AlO0Op(tJs})J z5XBY%nFv=+IEGJ)@Sa_LX$wHzbHVIoPrh$OuY2C|b#=EH4SrK*G9CBI6~7XzT&?bM zDQ@k^yn9QRAyGe5xJav?GG2ebEZJv@eE{E47h%5e^e+O2xF7jSkqQh#<;*;Fje=O@ zI_y%3W)s!MbLKa)s(qC2!h8{6W=$! zrO(#)W%h%3s>`sk-t#v1Nrig+Yf@a8v5wSb##N?yJKotyFaxiNAN$#l=e2RZ z)ttS`3-;B{PEq|20RT(_D{9MKJSx5+CGWfRL&5rBe5}ygJAB25=IkrStwzv1y+HxM znC%@1`P%10v|~K(Pv#UuWWn+mEr7E6?}ymB_v?W&$YBG6@mHwg?texs9_AXj4r8Q# zBh~-)3aKuw{=Z)hu6#PGRl|U=D$WUk7&Qa;x7Y$uu?3)-!MI}I!=nL9zwf}(d6SQ|w_eY2qtNa5j{|_Fc zwPTvnX6mF9c7k!i$+r_CI^|i{>H-#6? z(yxtYzlg6X+AU}vC)+|u*`}?n69oVWe9-#nY4~qkwgBw8`j6(t9!$2gR1v-vWqV4v z_I2-bgBsGrLV3v0@P&inm+?P>jXr^Wb{~DoA#=@XMdVU+5S`j+Yvi?HTn`!IU%`&#}SM=Y23gqEN1Yytrt_@dJBcUD(O(4hMV{k0A`q9Z*sXhC56#y*UM~nafojuxuhj|GjfUYL?@ityB1E3%vIw4E`5W~8&WG2H1 zAoIS401@Q1WbCFerL5@ofc+jq09XE9bCmgamAb6|H@@SC*hRO{CVNoOvQO<>F+wo^ zbw7s<0JVP<^68x?^ebTBa3yoxzZ6=8=?hJAqZHl_UHSu{&{^} z7$1OkCF5@xb1{`spx_n+U?H?H)GDfRYG@qQAaq^PkzVIXp@+}Me2@Yi%5H;~+Smcm zcYw7HLY5u^mLYJsi}u|vry6Jk(5e7bqq?_;C3b-Ixr5XM9u zK?Zlh9|<gnu&m!qkc)Ag)TaX(dOz zRZzMGC(|Ft{ee8f+A{B)!RYJfFacS!Qfq4o;TM>aZiv-W87C?mD&M3f!P=~Uv*&N2 zO&fbfv);}2G+*Fo&^7Oy=I3laZ=M`Y#?7DJ>vVNF@hCqj*fnnokc`{i@q7l2=R#0m zd8Re$u%eAgi@5i!YkH!qI+`Z>H&6P^XP9Y3SMj``X@+&ZjNXJxrr-W9amJ@awh|20 zgTufVVC&If`Z)iaimp1KS*vEFn(05~cs)>ZAQ?iiw2+!~hTGJ>NX9>u`ADkUjfFjNXK=qDmz?n(gis1BUdC- zEbMrCh7>T&llrEv1BdpKLN}6ExIp~Zzy~tFvA3U9^{~?cpDoNTrfL_^Hjf2~cM$L6 z-Nzc9_qj5!tq$!I1ch$?8irR$jq={v)i4sssu^z-cvZ4#O=p{R_FLwUHga7HJy>|= z&>X%o0)PR6^$vmty$1h=*njZ!4Fy6MqBci~Mf!VlP8Oyx{I2Nxg^LXUS$yx^e^=@# zJySa0UsrC?RzxB`MU~F&09rAaGIsTI_I7*h8)VMKST%mLU48$%@?)%F0kZP#GtO9u z>C$mTWCs47dIYpvpk^$FaXmw5IA=aB#{u3ZoaDO<8$O6X5fOex2yz)?`r3gl5A$E( z439>~GC{$!>%!yM$M zHRE1GZLHGrp3*YlYYCN7{SD(+Iqo--nP5R89vQM=8>5@i}%@(3|3 zqGCE6@P-&9pY0A6^}07@TthHm3vQ!fzUQu;BSjZ&FVRH8E1I<)9(I@WiTuS_^5ILv7W)ElxaK!!xN#LvEU@7Dtbbczu`4XDXv*}t-2p1jb9nQpT!qlGcX07$l7#W(b| ze#=-&=DS|{8k_nu&2osV_9NrJ3mhE)Pa-4?!&W=YSHm-yC+4%!3+g1!w@#&6fh))w zj$)QDybCl3W+%)YXV~TNm`>U`=h(Z&xDPY-fW7|vSo-e))3g^s!*UnWk_oZxaR*ElC&n)bw?i&xnuE9+*C- zOz@N2b-V8W$M9eOs8>B6J*);8)g4Y*@n^n$xY(~A&ky4WKwx2@5;<+px}K5v;gp;XxXZD%M0;e+JgOjIp-mL=1ukf#65}HN<7zWMjBatQ z^Loq!1R-7ZJ>XOb!-aD_+gsvz=d29#O2HtPDwtLJ8WZ6d7dtfU7SnrXSuN_#|xxCj5oAG?kv}U@4JEsEU zeg{JV;R#;%AD7^&U&lXQLLwYt5Ex9R81M)yo(KWl$KyImF#n`G9eaHnPHDLY|IV=X z|9rY1@j2J3`#)pf|1;8GAOtu98=itd+^4!g*Lwo3sl>bQRUU9atv;B8_4 zr$@jPjH~Lz3Pu)4=jZK5)#Bh69P@<5|G5kUUdG`NL$^biiC`ko63B)a=4APWqw)#+lXt-ZLzob)|2qJ+ zKuW(jB>GiRFDsMxt)V}y`XnP&3@d6u-AM&QfDGsn-(Uza**iUo>ozB^v|JHacm-j% z^wbf@u5(EfsRk^@&wF$R&%5ns1+M_Q3^%yGdITdbz>VFkkIe`ys4owm182hDcNoj# zQ4HlpW2iwf+(}th$s#q(31ff$f_dg>FPQ!%aJpcR`+}YB^Y&NO;_;{O+?>{dVZ_h| zP=L1wydM6%2<_D9QE2Bj0Jra?0Pj6o9F4VIAs{1+xYr^W3eM1Y_DhCq?_J?;vqB}z zRUJmaHvV2A3A^PHvJJ*;`9QEUe6myh^62yG@C;*mLVklQ)hhTV_G-G>hT zIO-r>1GS2Iw3?o z5$3H`XrE=iOpLU;lq>G>MCL4^mu6o}zLd7Al#ftHuP>#oT{rI$Uk%Gl&(N|gQn!lK z@#b}8*ual%WRhOMxXzCanXn3Qd2wb)|?apz}T!#uf)sm974OvR3Sh@tqp zqSm@{HtfpI*g#$HtOz<48q5# zIPL)d3IMeGZy)(rkm5~z%scC#JA1MH>0WA20g$DVoO8p~4pOWk^F!zKnC%&yInCMA z?LOZ?Ar5YCsFcg^dI@1TemBsZ6&z5O<;!e)RNmodrEr8tOOAV8c3Ax%uzKI-Xe{@! zv$Cz>P+fo#1ZiQUN~K&0pO4Wt`*Ei_f6i+E8HPA9dbh;n_7Y=$iwD0(pzu4)Bf=^I zj#%kOi$_C$JD-rI#t!`u^<$1v6Tv+1471i%_`nMnGWrSuh--i`tY~|We>K>O7F&75 zHtI-Tx%d>8QM)J#8wt}h7|kcB)1RP1d`h1n&>7NK!ygC0-lx@Prw^)6$A_V5Gh{S8 zg86^A!1P}*|7ze!dhq`ED`EYLjRe+Mmf00e_xc~f^0S7BC_rWTSy<3FG@s*CEui94 z1Rxbre5ueT2I1Q^E!$wd_5LXUn83K5c3{#5r`41F7uA#A3j_eC2mpY!1M1B2ZE;L3 z(?X@;x4P;IuQL92HQDC=$@YMsT;ZoEB}O|C2U;*Xg~^_A+SBL+EbXzK*ef~km{4%= z@!455;<#3|0Or`j3XMv#gqSQ4AmwqrDd)Hj$9^ldiG@N_taF-$IHVBd zLb9<$U|NoUzOq7p1mE$$Q-53iEgq>WfCQGULm$#h2KdVKnP%QBxKyd+G0p3A>(`mS z4X^0|hUC`0q6c!&HM3;eRbi$z^B3CoVgQ@RGzWjiz1DqGg6iKTWGV3~SH^n~1$ny$ z7Xdg=0SI7K1AsRal^$V8cU2Y3olX8)CHMcwHUNnI34(xg2>&t6zQ+KLVWcz!cusu^ z`ANN~tY^(HB*0{#R8Nf~;7~sT;YkVz?y&_RP(^7=BGpaS|K64Ly3c0!UG;6taJlNv zWg5TP;CSYBFKj+=ef-)9>bl~a=^3xvaQ$00e<$d3c_A48C2H)86adhZOI8b)eHaKq zw1xU|8wSGT!Lz$Nn2PI4}D<$lnuP4(B9L#s;io}bAszNV*egQoi-TSuHv}b z4{H|Fkk;xwa+LewNex6Bp`{6coA@qkWk^5@D+8GFAtS_9_rUoOo;{eU7Q$fmv}>oJ z#dZLz5FnM?g@Svg$}qiJ_n(j00>H@}vr`2Cv}p$zZ6gFgV`n+|ly?BH9?j=_wBG>? zhX6vDm7tF5S*LtaBt$Q~^^aW^o}U%0@HL3*%e`{T%ecM>F2BzEx(xl8F3tgVGlT&8 z>4~T3kb%DF&=30@uX{M%s~*h{7zgFV4UhZlV-Mi+1^^3o=E%am-kfv%$ui66tNQOs zdI?dLkE`-tYmn>z7xS3?pMG<7dfSq0L$<@V2u*Vsw<)yAd1o3&{+)5`-znPxKyFM2 zY{Otk^*8}QhQHlp`tQCuZ`=HB{!R3N-#ySB5r;hSCF5cNUSoG03_c?aLRf94E(QR{ zY~49$9-V=cRsYux0FQ(#Cq41dCHkVi`5u7+hJeOENJZ2Ym1WLY%H$)I(8##jWI{m* zF2x+d*OzA5%qyI{j6BW%g_p-s0AO?UJ|ZC?R@3WD(|cbnfu_q>SXJX!h3omFSJewAbkpP;Pd|kf31^%5cY!+j$CDe5*EVx zKa@cn{TCR;;>z@8Sa61EH|zkp1x=YL1c33E`47*vngHSBeiOo}*UI>x%zp|1pmgjq zSGfh{>--Hj>BfqGpU?3g&%Vc_H`Wzb7JS_hLfn{Hp}$+Du#cm;2|mIHlBpJQp7umxcmnj4B40R56aTxG%>chL}Mgit{x!Hj-d?@OnRwf*y_+W$C&~E>>ivUpi=vlq3d0HkwAmrN-iV!!>_@}&b(G*rN486IoSE`bL!EhQ0f2T%=J1^;P6VE^ zFWg7GI~`Q}Y)?8|?DE~qi5oky8NjQ;Y+o?i7Fu_((T%x6m&h!*dak;^-t~VK>iw0? zxM<+UUcB*wN=vM5(E#vQA;398fN}R6KdDCeun)_g|2B&l9T+@49e&|%qMI*D-^T81 z5Afan^pL;B3Ckd3@!1SuKKIB!(6U<%`{1rIr(ng(e+U2=Z6F09#WKX|H{~o}cnl%s z>Lu!siE!NePc3S1-EB~4G?Ak`yLxCn@=qx9FCb)~g_XPxs#n1W2^}`gp3x_?nAUXO z%d}<(L@gQ_*RLD5w$b$-*a`sFd*s#EImXw+1ncJ0IhYOezRxw&9qfA3zQ*f*h5vmc zS2~8ig=qB8NhzrX(SvE>0x~VqoO)e`2HA!>^;YriRAPHCdn_h!|*0%Y4 z5M~l*u`)!r1Yt%Psz$UY?%hl~Hq{^7a(+TRaB1+>^)@X$;|y(;LTCeN&VQ_(g(eCb zEWtSC_{`98dP8t_?|M}(Mepi=XaEq(ScVn=>aVO?Tpaf&15zxItKwVw=sv@7VAdKp zIT)I*+-s)Tp0a{z>V0WfsZ;qaHEc64Xb(i&WCQ$=F9I+;czUSA=3nqT4nf4sbo`@U?kY=9Up z<6i6R8B0x<>3Qva)9i+Pdo#>@+wc`VP|xhI$no*sdL4YN-}gHGRlVkb&HIK9c+>PJ zcq|}=`|s-T${;{rKx8jYsP;Q8d5v19dvS~9f8a@J-3oqy3-a8QlZ*)ulb>&ys^-tC zzx({3at84k2LHyM2mn^o5a6j=0Ok)YN6ifF9#{Qco#{jTN%0V6IgvDnDqXe8?=$$V z+xEcw_JH6a(XKP@sv|`9e9UShMz!Xr2&+)dTWbBkgEeuOjAa`}qlfRvY%oY&`PUAB zD~X$8EJ}^;$FEFb(`i#g=4Jxw!m50%Aj9yq&&C-3JH>PdhW|7+2F&ik(7F1^?&Da4 zEW~}Yu=^BGLcfIKTmN*168Elv(c(CkBNZPz#>LMY9ov*0TL6F~wMZOO zVXU?fJi;U{Kc}8QV}%LE*|TEe_51`C40{-JhE(7VhW>V|#SV5kme7@9)R6ke$sDZy zYnww`10f8c9kwC1>M#XI8{g+^IX3WtKgu`>n;7RT%a1tu>i7xpLEW*-Q!P%}r~d>K zF2|fgsQm?IO;2U$@wEnwqg~omPjj}_Vrg91B3ZZ%Ni_~hUbaQF&iJ0sd)4mIPSrk! zc|HctVE!MX_W#xBQT1THSM4u$*mg6Bu^>~e^1oyCCgD#e+0mwRh2PbF_y50u#CcLZ zNBzHS1+a02p>~S*uRxSIVh5~I3>4Z4`nz+bHAR2{bkL$=3~R5&Ga%TC>=}to z2~E{9-JfZ<_3=)uq>F6Ckae?Y4sR14)NCn&l@1h;|eWGY-Cqed8w_ z($Jk|u4e4VsVTbrIm=IU@?xTz5QL&=3?5}?% z)z}nY6qgHY;Hs(?_jiK*??J0dp!2H7sw>#e>%YIt* z9%77Z>0< zuLj5cYH%{ZzQ&+BK<)n*<4>zkXNO_*PnZ+dWc)oAQW1dH{%zJd%KYOK#&3Zk8GcUy zc!CMQKjT+nfI1sY5q$=V{`LR#5!UciZi%e-f!u62I}9_O#4 z$)x~5p6Azi9{`9V6p5xFpb7e-6&y@-d!?_)WEocWm7U-2*Xv7?iH~3yEI4 z+P|1!yW(UItKx^%jB~Z;W5yz@{}q{c#Jw9K?Akp1AXA_#Dm-StWou!FhE)z!PiNWQ!DvG~&OC!NWP5`^1q z+N*xWYViYb=`nr;!^xoy)e+zKo1^0jz8lRfggF|uR5f3wSvvs=Wi4uB4Wl659|C{_ z;AqY$k%@Mkv8jDAMy>ypEjOGb5n2HXoPts3Ip>Mcv?0`W$lEI#0E;2aewVTo$~k|y z((jS7wj)>l%TuL{n36N$9YXsg>J0)hw3E((3x#4YzO7o{{_`RTIC~C5$jJ+PM^*Q; z@2mdf5#|Y)Eio9^LI4n5@eoEGO@J1f8A%xka)-vXdT_j79e}HL(6HNugZOOmu=?u!6EtwJ0RX&Nn12cZWdC!FzC&xTd8CXoyCUJj zxQxCA|BkTt|4sF*`v3S<7$EcrGoM85)C|&lPC<{~K9FRbtqoDzjSaYK>i+6vTc#LL z!No~^Zh<)9jI$|EdYs+9$BO7DP%&En7gPY72wlIBZgGg-Z4+MI!0p|e?}5hmmlh9a z8s2R{sAW~lM|h5m1U%3%1d7lAIPYU%62jyZVR{Rk+yUqHx(q1r-~f%2SedVjyU~C- zT$O(p7Z)=GnQbNvG<#+KTd{vhlE6GJ|Gn1zAvyk6ygbjZ@IC^f1}T)dJd(X6GELVk z*0}dGE#p^(`MhC1*G&89<97Vky}k!>uw~A?ZidF2-n^p!^m)$#uJ_tdNmw5J_YaA` z#tHajflw+d{SZjTH3^Kguvq*jLja>0i}PhS<)S(;;|c*}=tTo_;%Wi7@BftWM2~<# zD0lzA>9I+{hohR*FogiIIs@S*F(}a%D>aR7%xB`cn`+gz+z-A7VjS_~e;toiHw6J$ zzFkZaXr044onwuB0yE-qe^7W!_SkBnycqu@3=86nU&pPCNr3hT)O&VL`ebs1O;>DP z?Nr@a6=#J4@M-Qz?qURRfCi8>jcWt0@3{h*s=YEK_ti=CL(YJo3X@-ye#^DQzpI)> z71)DI_2M$uJ^j0DSNhdaSjJ(gku}pMLm$6CZNY>UrjX;ML9et8!A*yirZzqd1X_%? zE*#T-YXKvsGRxhN3w%%cA>1X5F~)m_Aw$RBYo5dgq} zRSSi3Lxpk(0D{>kuk{yhllc!JLMbZdoA(-q_ATCey9FTYKc~Oc&J!-i$9S}4P7we= z(6{=hC@)MT1*&=BLo2Ti6l#k?v6Uu;b^yd zINGZojt_u0x7zfpLl}RB0Yk1`NiY57Z|bJx3+jH@P+)aSl?x;YLqZDX%xVUDgaBX^ z0)ROzzAOFal+hPA$n@)ro`PZu-ObcBihhHi(jM_ZF5?(DMB7Je|Bk7JI5|!TVC*sH&X`XFg26K$(WgxS z(ao(n-^B|R0)z`mhKXwAg71X=M-L{RX*p#@-r6asvKw*aBVG~)ujh(6v*SQ=l_ zxm+QIQh}1sXPPxwzxKJUTkC8=aQ-STT52d}=F-vO>S%`o$PLtOX! zcuW<)+69flIQK7BK4*O2(9{0L4eoE1Y~Hc&g+sRpS};xD$HKuOW7%V-ic?xw{czA z;Z9QU_hX394vcF{AFB9HPdEwBVE)VHMt=ibc#pU~_Vv?$A%P>r0N_#sfJ;{IRp*!R z%>2wLWo|G*uK<92Y|$x4`w^xM1E<;01hD1gZ3+P1w=tJKw-?smkUn!hc3aFj`~TIH zVGBUadKv;`Rj<`!PcN%@A^V_tPJ5!4s9xQyy2L2TPZCFwQsfd)Yq3SCgC@X`|2YjVdOOBd_zvczK_% z@YxGsx#*4ZGA?lTnD=#8y~O*bUl;n^)?L#B4z;bj+yf4zSGo23UZ-z9m-(7gfoXYd z$kG5JaU9_O_uh1hwh;H>=#>T*0f2GgM+ZD4v0f5x?zetb9{J}M0OK0?Qwv~DTpChd zf&YM1r+wp>U3OQ(xFK$(GgU6PzuO*ouO6s}Rg__zff&j&4objB{zG14p&>w*apH(S zmUi3|-G$L`H8IrQ5{xaW9=n@lE-dyoUGxh-!GPH*^~=>k7IQ1|MB5@U>5;5Ggf?BiU&rsr7MQjSY%tMmBfz+0 z%rTDd<``dbtM6KS#{w0&R1Rqh)IysE_>)5p`j51HzxRS;HjUe1gj0cV<{nxj8h`sgf?e!=_n-J81AwFbk zf|y<6HIHfVugkH172m{AWr*SVpc*)qKu)>AnU8dG|NK4%`LhVU6T z&$oDiMyc3eGJdsdj&Z;ziF9E`?j>MH$(&QL@PhL#&Br2f^FIXzc+NC?rdi?V6!1V? zGmQLAxh`qk=hZ^C`K@6fy6icwuXVT3hHKxwz45{KK!6g1bBSuLsTt3DIJ|*Xh-Psh(8&A7{t^% zs<8CmQUDM_09H6*991FjaWq-?9Oj=@<_*mnkthQ4QOlToL*DAa4YC03islc24J%A5%J)abh+__r@>)V{nn=GT&zh=6?^nI(t)2+2A`3z*Fv@_b<2E z+yx6QqpVQLegDG8m{F$pTEMVR3h zAnkxeo74j6KzZR?;cbv(?~W_Jef|CG0S1%fDV%WtAQ*oMW4$O=S_ItXc$$It&NZBk zfUgUTFTl}iN=Z|Tmy3_mR>LjJ-~8~aXE<@5+WWph#I>Ro>IPl3kStf%g7m*6&x3H_ zIi<)0{W-k+kv(8&GmPs*5jxYdd7=*EzMvU$dCBGdONrZyiyqht051CCx>%0ltHSj( z%gD5hmpQJaJGkw0^FS3;Pw~3{v;^zFjO`rqb)*>MU>e0x(tL{5X089TEYJd*giQdg zDA(e|W<}OZ-qdyM^#@5EbN2En7KlYy3Ik3EpGVuaqOxU_@54=+k1hbD(tzu*gl5`C7=L9_M0#mA}ep)Ra{kmEnJOs{U z{P7s6Tt55)f}RrqT%BAk_fUmkI^L-&xA#!M5_?}G`Fz`wm_zv-J~Ol0zpQC9ZYvNPD1G2U(}zO4I84tZTxX0QhdTV0r%%y}Ew z_f1>ngrg<~HW^?Qzp5Uy*KChgVd#)?aKucs&u9Mhn?H^9m=3Dx(|!+`7j4>qRE^R6 zn80K&9s4rmj`L*DRo@Q|_Fdb{b7@1vuCrGyUl;I1`LVL@tYMm-DRl*FB!rz9gatb+ zBxyi4;L<$x15sXGrb(}IW{Y|d<|FY*`3XIIVWzH2Y2UHZF&rIT;m`o#||t09fWCL z{K@0$!M7Osdx7aZY>^Bxth+nwS6_@CSO41htLnjQzk0CTt6{7YNB@;g0FoOw?}P*y zf0_Mf%=AA3J+6{tA`ioPqw2SiIo|+Fo&<14E}gKVU_e~pv44ludOt){Wwmn1lT9^uoDz}stMbBUL5XKPbQBL8h!?JU@DVmc36R5pi+AP zzUYQ9QZc~Iy0WS--a~X}rIAef);2;3?G&`Yw{bimczKB?na-8}IJFD-7Li_|2_Vn& zkMQz9@j2etx$%N>$~DO0bz&UC|d z@3RhGM}8UoC68(5HO)8_g93lJGs z2i&-PK%T7N%Y|+>MU{Ugl4pxS^Yl$%s-n1AhI?Jb9#M}A)IpF_~I4PX!W*UGnq zzCr*QW|>j{?uWZv4|~TmR3!4B!^|iMPzaFDddrrivptG86dK6X`22lz*4X}6Mf@@B zmMfTrX`6F=oC2Lm_27r!RFlC3GZ)k9yvGrOSkIq6II9*r53A{;FWD{t0cb%o;9>uQ z3*$M6r98`@L_&NuxOO9Z@p;Kfoxjm)k%j~4|v(72bdn( z2mol-N(d0bfZM3@_8s@W2LgqO#w5`lRNxj*9tt@-+J`fa`dnz_6WE^u`{&TlClhGu zDKI~KP>nE%%3-JM2wDL9XrHjX$jvk?qg`tI<!w}H`Lut{)<$S|aDk%?&-?2_PlMTr|v63`)KVEke75dw@MOpKp_z(%Z6j6)!x z)qf2FUVi=B<;yqCkeQnC%Q?4K+a7qg9&k)C{e%==2|O!sVP%`-B}~Nv3H)*gX21I> zkXx_#%lK$zT(#q{1pvrjp4i^4F1PtqFjLI6uB;lDD$#1WO#e9=05USJZkpy9=3YPj z4XeZ7u{6Pb?zK2OKA8UFN!34R1&kHTJ}Qcy>OI5=*$`r22p*8I_xQhLoQp1iSNGG& z$VgbpAiG*A1Ebf;TwUx_E-jGxDSMn%Y|g*?*|ymKPYVuMX`R7zDXZg>Cldpm^)mmJp~cjcabkA=PV z74;~JfS(XX@Z9^rV_oE>>I95f3B6Rjo_KKWzziz?)zJ?K&z|95pyH1f!0?RK{bw-z zXaekughWQE1z*)gVT~zfO_laF@TOgdL#rEwny(h1sD3OKE(|-;hLfgK2V@x8;)pUoMgZ%=qbmcop<3= zILghbAWw0K?<}R~=eQq@xTbB}@@aEo$@Z)fw6xpMirDS)5EDb`HaYBqf4A~18Yt$|xe!^Pmx0b)AGlCs zt)>z{+5P0MgSJ+HT6 zqX)JEfQ!y>;9Tdtw|+m-`+9no;Q-F(4D;Gh!xy=%^gj`QW49tP#UMezgA^p5EMO43>m3lc-KW=j+R@+Yz~&@z+1O&9Uu) z*YlW+jbxGWIrm@HjXPs71X^I{+F0?7;M^@~p~nE$MycG2YM&PP=TOZ9D6dJuwXeLr@XL5H9&I-C4I6S%6l132xVc9p z%6i*#4h}eBIu|a^ftA)64FLL(v-(tJSgXe}FDVxPeXDh3=3@(hM;Gek^%V>RudfgwnEz5gEBUevp!x?q_V3~4h2)72 z@QOo)Btx5}_qxWC#4eoobcsdFRe8pEsaU37gg$rOy^CBQLF^vQuJ^9Db8xL!%)!=l z<})q5gEjMbubviG1KDeq(gIi>6Z}QvFS#VHGBktn8hbdwTevV5VM3P|H!!rbNQ>9y zwV{wX1>h&F`cEJv$9O}J0F-pLrkUSouXSd!jjAW7k0S)Y1zvC6wg=v|2N+fXJ~759 z#A_#7_pC8?%T63`>R|TkL!Fmy(hck4pvq7!27IOD6A;P+KaJn)fMD{Ob6w>(4Lc&i z>}$Ae0fXPtyW$Hsf;w~6m7yVTzfdV^?X~H<4yuYh`eZv^QoPdD#X&CTMu{*dC&gnZq#(JaCMi0)n#7)3nBv7w~ak0EDmN+~GKH zexdkSjkLJ-OVyFpeUrGb3AuDVe{1d(|tow6cl94Vk_cV#F9NhBql;4vsJo258UTG_s{0o_QQDEeHsvlxP!Z%^bfnj| zZ`#)KKY|UsZJe?4@9O`ogLpt9EU7%dXMXFuXuw6)x3Qb*0Y3LjF4GLx(G6)!5a$9I zUtq*D1ppcv4k4c!z1l5t5|zyD9dgR)K3V|S)Iwzlu`HudSV6wXSkt(6oDcxc_QWln zzY%jR-jZ9rGjOJ2GPWepxZq5<*^0Ww)pa%ciwF!Jvrx$%s^Ezg4`Bw-KE0Z}N{ggVDwg>(Irr7fx42-a) z0Kolw=SMJns4y=T#>3D+^j2-uzuCXMWN&zDhvzz^O<@p;_Apd5KqY)gpSk|10R6~}u=9U+tMoDs(R(C@AaU*^<`=RyqSTV-Nr!Nx@S_QUbis>Yy9|ype7MDu#I;P@p~}DFfTHfdE(RcL0nR7{>w4655W&cpgYR)Q8`{lBDZ^}mqV!hs-J1KpJ+zk8yp{*sJ= zVj_-aFsnqz>`D9<%f$Z@tN%yy0R{m3Yy)Uj&(H{XTH62+C%)QIcQI!gR$?z@7#!0o zN(;iuJ*c)b&fTRXdop|2aO<``a9s~L8N>K1ZP&`Ss_Ux#FR=DMJKbR+93yA*hs-`h zRN9!JW&W}FKOg)aHUKaJIQ#_SUMo)u008Yc3J}y8tDg6K@JS$u7IYdglYuz{ww`@c zd>H#{*K|DXRL@~L|3&vH%<3O=5&+r&I|EjyAV~KQtMMm4$4KBOoEW$hCjFm zSBhQX$JjZE)qdw9=BgIVV4JzA)BXYU@Ml%~fYUG-J#Co7Hb?*U4o>jo!PsA$z6(&K zU*{V90uRO3BbbCP{oDl?eg3D9tH<9xsD@`S##|4lsQ5F#{`u#>tbQ^6tomfG^#)o0 zBD8TlYGb3Usb}Ba96oY<`{&p>1x^xn%KrFKSjqnr?EU{g)t{ixdkS2r=&wMn%>JG} z;k8>AG->wpijzXn`qlb>5eB5?f})*LXqs%-&4#6ArLHnoLb5GA*D53ur&?UiE|7iJ0pzz1mbEI2u9ws=rY_dbEv@Yq$1 zXoEkO{e$Z1!M|BehQF+y_CH6aI;;-5^Xd^or~$%&Ux1f7%;o*I+G&hEwxV=lzPkwR z+r(YYxM`>0w?zY&EY!`>j`CV#fC?&F0szM)w^>+maYc8{mgK(!ucI+QEBpli1>U$s zgAb-qz-xP6XPDH#*NOD(WhdQ{1c|^EmNx;e05Gp1Y8Frr?){%j#0ZEM!;gXkC!kF`<%{7{2ms+| zHC_E5L-;?#;NN%nX9xg}SxIuC^@Kb}+*b>ruHn_y%JxcZg&{Jqr$n0`Lpv;sM7rul z!hTBF1EFlbsaMx=oBGr30mhd@XTgfw0!!Ora0eQHfm+^t#Kg>Tbu*06&akw*XtM%} z`knjzm;Emb^N$tus)yySWN2W3Vp~8g`P}DjvEkG&;D%5E8^`#?e*Wh$^xyqS2;5q8 zRxu$g+Cu~Y``=;T5CH&tm|GARvEr{Pa|h;M*p%^s@Yy+OReQ(X>a(x+s!vW}Oc0L9 zoJib%2J`;_)aKsgT;VIdbekmo>%NO5Kh5FSRsSUUW#(mQG+gGfU*B-Bna2UTYAMs= zQ?g*Tq-X^|-0`$!l)u-#_wMc&ROt$=dq~Sv7H6)5)7uDae?9$#)h1VMIUW$Z4riR~ z@C0Uf(mJl5O~0>3tY)7LT>T$blLw!o0iXd``fm3C4H34@2p(_yv0cle^}fAWMl$NS;KvOmOnd&oN7F0iAee^>YFS1JIQK80BJ)d&OztOB;t zM0)Vs!|HdQd|n-n5HPXwzr$SGXKww~=*#LWto=V+codk5^JU%N?J;1~Kx7Zq`aYq(v`Kh5y z`wlnv8SJL5yQ3Zm4C9Z?eIdVNo((%fkgL-p1W6bbUSiZUgnYvN2*Z8HEQ~$h1LhGO zBjCdlD7f@dwcP!J<5quJEyK~? z7y4toywO*9YcKCa&qY|klZ)DUKYe_Tyg}&11|omSnSVX+OPM~lgslMJ)n7aZnPIv@ zIb9yk&HE1Ayf(~hLzWN16I6fOpR1kYv<5CEY!DlvUPC-q{>3z_)r^`*u^=D20p{PL zi&Mb}f)}PK2LhT@$5TS@9$N(g_?VnIS9>wrV~nzr3ER48!Q^@5 zUmIob?jsm~gaLi7Wo%?{bTTzJ3TNdtoB55_m!iNQvAQX9qZYt(=39kqGxjm}5CH6B zwS4eR)gAuGswM&e2o9Er=>vS9iQNevNQU01`WzGInZytJgX(d|b$|9KhlfysG%4(V zQSX&eF3!+0?uWA`68bVRl26vH2mofG_U|g@GZ>j4@UEK6@DwcoZRop)xjdK50wXHQ zxKC}o+|z}nk_pQ?rV6?HHNTvCJRp0WY3G=gq!aLN2jS3n^upf!TZlS@&jaxP0AUz} z-ems)rZRvHVZpJHs{d*L)MMrH`)~5fzE4-jW!_!U*VYB9`Vn$`Wia)@=u54a)%?Qf zli#^U_|WL3bF5{^{5vO|a$41xV=^tv=ZBQN3(-9|g-AzBWS9QhV=Ij?1FC3i>7T>9 zy>>y&E^*aREu{GiRLimW@2Mjl1OPn*0ee5}RG)U1hW|p3Mqy6bic%)TY`6K}Bx1OkA$z;l6V1`KorV+Oin z&M6-AV`dcK+%)(9&rb0#FzEM`!~C%Av6!Mw=t)9{2mpF4H1vN7K9SZS4dyw70E5q~ zaUUGZ{A$`9=D!0CazyB{+aqwvxtaj6`VWf@qg@2MROVJ(ff&^sT&PrzT458T1y3N| z&{CT+7at@Vu6KW%TYnj!{1KhNBotUQLZSgp5@6Z5CUhD11w!9d_h0#Pp806qRsira znr;rP=D=vC8`nGF(mOa4{d>=Aea5{91tIQOLP1r3X#6TCnN~(DzcrRo&0k`~Rq!Ch z1t>~xLwo^ht70x$9pjiv{H@rpwbu_i5fug#}GK(tas0h(x z?_wYBMzus&@+A0^pif3+^+T02*^n800XYrx~|&+E+i*+P*ojpL||{sIxiX_ZH2jvp*BVVT`6zL z2&XVQ1Oeb~i9W~KoxA#*x{@D;FBL9RU+X7RAD)5i{hV(?Sb$J~(+@%zZF*=52rs~g z+5{6;fZZnGepj_)(D!XAFhe6CR)gtOwO)mp7Mc(#FSL7t4z6X~mQBRj|bHrTk3Wo@@0+lD9y4`es|XXo1aq{X#VBOc`*X$k$)UdT>r`B>l|ISNFj!y ze<{u=VvHKWMDAuh5^m)u>s(-5sE470!I~imm}2=%(0&H5ep9IFvbc1pgXD|u(5#V z=wJX}&BM?F;69V(`m@qY1YHfR{hDgQDs3Iz#VW7x!MFsY)L6Ie;^N2mrYL5AfGI0mqRX>iiHZ3y2UU zX=(vTya;S1O~A`Be{FFaxuK9jzktb~0o+<273qkKyqTYAI-d8dP_aulv1shnh1pB4c!Y-!VUto>7@~>sDoDW>tn|TDZIUWOn@6 zu`}7RWb8gg9J9?Pg&ljO$I_1&M}tdYUm*q#B{KV1eLHIKarH)?j~w^e1+!Cg*LpbC z{SZM>>z%B8=HirmZuj?=yOz#TLSY{UpI@mib_}9@*mm=Idn=(x#F_-D=6eM?^;{mwLW?S_-8xHH^s#q&n^Yf!5K7=>aeWHVcI0+IjG#tg{Nk9$tb2 zEQ3iS+@8~k+h|)N~~-8agAjYYFIn4{>dJZ5%ZbY|DQO`kXf63w$2 z&9USKR49q9d;?mc64BqN{tl<|y^sh=-ioO^L6SfU*kf=<-a_mC5uKfE#Qy;g z4AAU57_ZHDZ$9!)m#8RHfo9KhDNP695M~5|y;b1{K}X9a?0d{-j-|`!YwAA8F>l#h z%?d1%9rld@paE3IX8;4T!?Yg-#kB5e>C=*Y*AuJ@%_+ja?#v#~vFa{V0Q6C8!jLVP z3bN=p+fu=wIhl*8*DDu)E&s%j;)L^aQXkNMRLxWGHv|z6Z4X z(UQ5^eCHvbb+H&#r%auxCn!Kp&-nhphL{00{bdfWxn{x~_$*bT;UN-zNM+ih~U5I;i!Zz<$;KgW~$HGC+En zhKKY#lrCoC-6~d>Xcgu>a|S~*Wl%O2i;9K?%uOg>^ZFax0-s>6f{+6sM#9KcSb)7- z`Xgkc{{=4qDW|d$fRQna(ZQ|UM;WHdLw%WF#4@ula+~GsMzYNG&J`(_-;dw>t^i2n z$gjP5oaG`_J9%B^2J7S4Yb+OGH@9j1{~_moL4Ip0S~YMUMx!RcMg#(s1Bdf=UvAt1 z>!wl?o+(=V2^vlbkc8+2#^r?LG0fovqBo)cIrrb183+*e=pAdx#cLsj_Q}i{jLB_S zcI^N3cLke-_~uu+DPU~h^GQKKvTbo-I~C!nsva|R z)W)lscOYJOXS?(#l4x`ECxw_WOHdGf34up9{|-x+^;v#5T>f7n%;5IDGpYLfv#Ni{ z{;u;{WoU}9KNoJsPf);t0a_AFu|l}nA@HX{%ON6*vGKL+8P-eTMS;@4yO^Y%3N#Au z1~Jp!-?FjuD-Cux8dPU{53932K~4z>sj_oGyHC!Daf0A$(4!f23H1Q3^P_mi5}I6m z0q$apudb8AsoyH6ZrFw%v|Odf0_OK;1j(G?2JIT?ryS3g{py%W(BFPLt6ol@6R7H> zn(g2n0j$P*yVc7FL{HdvWdIpphC=(0%CvoBYN%wREP@1r8(RN&V1C2fCJ8%rjjrbT z%le#rA4wcHIUb7JV*>Q)qOTi2%C8PnTeSRl&wg3;W?!+7H$bhzi^n3=b#Uj7Oxwb< zEXE)BPrhr%)iRRnk8zi4r##;PfN_pvy=92_-y;qH>t{yaaDKl56?+K0&g~ygvEj3% zVh@iA1O2(w-~MxAWIWqP_kf~o-YwDo8CQSj>_^p47LThVW(XP;KjZtCdGdY_MQZGkfGh5B_dIboS;a2+IwA{jEDxl3;rPZSl=#EA{hY+}X| z0|W5L?IoGJsgJ`ex9KB70OYs(%f!YQ2ziOIkFpi3cDSV9{Fng3CwM#2&(~4?@!(k! zuVYEPjv5V7-B|Tk1{j9FsCR$Bb3q{I$t&#d;Sq571#Ab30q6gFy+XfU0BZ$mK`O8h zA>U=Tp}+9mBgUjY%GV*Ddpl0gax8+5_LZS;1P=?43`SmuJCgu|7DDeGTf2BPW$ZEo zc56V4z}@T5cA=8Lpjg@HE3&c@0HFhx-qqex6s_}Sd!1y;eY5+SJZFVA)8=)X$D7xG z*2ni<0kHXTMF!L6_PfeFFT!Q^{u~zE7lGlnBmJk%_Ues{2)JzLS+eBc5;w*bmW#Ch z*J%3cm|VnT=Arq7?%HMxPv|?zeEY}O2VX4Aiz+1pFPmr z?wOa?DWx>$WyTuiSZ|!8OoZJ~1V~^6qpq4lR;ae2ed$BDh4&T$*@FcD$ftsOb%sUf zHGPT*y+-2JRdtDgvfO2`-enN(GyZgS(Npk;G>)8?#~`h6vL*?i07SDd$-yWX=?bk7 zvtVvN7SYb~6iMGk`C*fPiL&tz6@o@5Ub`1A>9>_S2skDuM4WB zo2UTjA&}v^+We_rUeIawq3e4rNB6_!5zryxJA&>M8vJs+sDAbOtonBNnkebZ>Xaz= zGrT6A9m3pxv0E*VjAV@!OjlMJTa{@~evS()eJU7R`j`DmhPTGpGtjKcwXw9O-OYWr z2$C0-0Cwgk+p$d<&*J#os(J>Wc;8^5R(AfAPjB7IRf=iqtok zWa7>Kne=i|IJUq1dFLx2d&*cpAzm^41-QwUy$M6x!{49Y9>Y-6p)*sBOsyK_K*hkP#h+mImx}>CWIIIL3p=fPS;*2b?#mKS}_X z3LYZpAO4KU{$FyeApyDvadBm#y7v$zz!M1%Wl8@aL@GcH04O~SUPD|0p`?vDZHgit zo#rUiPT;q{o$V7NU?+mL?&7ty*TXvr3ccSS<7snKh$vlvLTHpkMyahcxdZ*`!f(`i zQic~V*8ogaf*LkM8Nkscy4~OBf&U{}SxEwHL+n{nXOG=Cmlv}`YB$z>&*e7Hx69h+ zJb$m#RsnGJ=WipHS9yF{PNd9piLf5KFO1b_f%}YzRrQDD??~XQ42DB*%>Sn|*`c&_ z(2*h*K;XI8C|-a3M7IqqSh^qS3E=#r*s?ESG7dn=r9Pzvw&ERAGFl2Nx^ZTXSOB(@ zCrLFTbC?j1op*f4_Okm2fu@_p;EnrsX!NyaGp}8wBy$t;Pl_>y4c)2-yWj6fXw+c22wKD#C0;m9(F$DmlY&AzQ zG>0);>=OMS>oybLp=|_WLK$#|sp8bMn_@6kP_I=6+XcGk{xvz!&t@#PiWdNpzk4SL?Zehj z5f6a*|0e`Dm<|vIT={^{>nH3$Bb)*-M4>vuB3c3(>fHd{Kyp5B*Y(x>eV$}HOZ$ic z0xeMdj}zJ&JHIXlTadLf)lHHIH-{Ghyf;pHsLw2eK09tfLp0QR%}u2u(4#(sw=f8x?~XrWDwSyf z^c#hLX?4(aYsM9qSMi_mygx!gK+9N2q^iCoyYJNi2l7+)13K*ISMoTYm|M?fvaEfa z<@bIIhTYqgh>`%LE;4IH{SF9Ikq3t7{biYV9@g zDEK=_uU(bzN^9P=9?|O3pJEySeJHl}CmN4stJBpQibsH3B_f30o&ph;|Hy&?LEmWR zS|36mX9uS&<~`yPZ(uKjmL+4a$RcAeYcC^kSCh~w3_pw$6w4_9MG=6DJHp?rQ2@*d z^0pu|@f{^6R_^f_s|&{n!HPn<$r}vKfPg;lQ%!y=zgQ-jN`V1?H#=6iTXY)O0U+7wIQ?qf`CH&g&mzF3PC=@T@#$&iP^0!_xP6fb2ruPDu++&3Q z(|+`eT@?V#_5Wh=pn8m}@IG-zia6X2i@2UMDgNJP{}HqWyk)Qa7QY!IUg!nzitqlK ze1;+{riY+VoDoN)-r-w1R~}(R7(4%efZ}Hdt-y$!ElfpWstSeiZ6L2*CnX*GwpP69{-Nv#c&G}Y!-=jh_C?UEgj7{14#Ctq;d&|9sK%kUp)asSG{Dwb{ z%4SA&l}sI7*^D>g7{g#1LWxKpnPMOG-iha2mM$xfLG#iR)WwIi&gE_>&6`u+?*MFD zrU*q&rHNyNqdCGF^Vd6YHC@;0-*;4_KfBBfZyiE@P#eWq5Wd#754J>Mu04hcBWd`CfRs)o<2r^5UwJFz-n{9?%Z3#ToTftd5xqYY_7}uHSVq81JY$#wvNU5QUl}c5m~ABSCR>|Z+k97&Jsb>- zw(1F_62SHv6x4Rs;7_b>z_hWLG9sEr#*H&u*myCbkjm zkFl;M;(y7MK}wv%U+W5@r{EBSfgVm;>)krlDT1A1JW#N3`YH(wN51R6gu4K_Zj)M>U$!Et)qHWDs=ZWSdHGyW9yr$Q2lKR9o z>!)OGl#%{Rvh%f+os?1iD%soEjXOQIQTevqmWGz=^J}(WlK13wKJVV9tpecPKYb!t z-r;eZ{3n9uHqYzI0`9{ZRn;H3znQ!+to?z{o((DkQ(3k_b;3&GF?ehF8uz{a`qFu? zuvXwmiy~_DDXL#Cd%8_$G&CknDb;DQ?8_GnVa@Gh5fu4~@=PaLL4V^HSYJsI~ zohAG87YOWx>(ojoJY3HjcmG&&nEJNpp0)rVangKYY;HyYTvA;kBI7YMYCM>T0B3bJqya_XfH@!O) zY7OG{fO*`CvjfJYDezem>~4$z++&XH3CA;VYekt1^z;=9lsQ4-SVphLQoMpGUJ@v9 zJO}b@RRCBfvs}YauUIN;Mf`x6TN)4)@6GlDa&YNvrds{M>r;l>iTM@y4)53l_X$h~ z;&M0NgaIQwT^L$|8RrqT3N2FLdhEqhQFNDbi@Gq`9ok|)P!SeO`&mYtREG6f+OKzv z9h<;ly1Wkz{zqRqoa|Q*=10tfr;p$@C(It#N7X}u{OyA`&h2*we9rC{whGF(jV0MP zw1DgFAwDY{&%(`rT%9m&Xna7_|K1rfA#nTe;V@6^j42AT#RwZZ9x{Ndd@A6l%1C8L zDvSbOI8GIaExt=_HZF+Sw#O2OXn9m}1P8~s(J@Om@e&Dqy6wt0c)Q)aCj=xZPT^s! z)1${>H3WV<+*UKjfinV}&IahyrDM=26aYqlS@oIEzxxY9S) z#h!0Er)f>m^=y(RXIq+Mrz-2I9Mc1MbvCgRe0}lzxugPrfUNWnnFavE64L;F!q!`D zP&*5bEO$SXW#*66*nG|Bu>~XVWfDQ!sq~h1N!f3g=RJvFdF+*K#I)SwyzXl+ApN^# zv+)~@2E+#rWUU0S(?E^F^&iGw*MD<~0U%yO2IN>iGLHME>_xF~7)0e5f#0BiM*cr# zYtX+}p%B0#24OPP$9pHWh!RM(sk&cB=4q}aB$4yk?Pg~M-G0Dp-@Crs8}BXz5^; zQwL>$%l&mar^r_X0PMbCX=3dN*tUfW*~tIl3T-XqG+n!yFagvnY;L^ z&#EQ_fSex^_>N$9)d7kC;J0Lo$dsu7Cs>=E@7@PyOXhIDCP>~1FqyzaP5|5v-WCdw zw!a8FcR{TCez4DPr$`Fh%gyE2@2jA?!j`=t^rJ$pYbcDtNoDCr;L9QM_;VycR>;!$ zAFBf_m|Ai&b+rKCsO2AzfCc@JMHQ-V_kbH-79KC7Px5^F-vS1DZj@{l0(M}N_$_jx zXeoV)GM-z_nD77cm)MPdMPHyFi|;P+Hzd9VfeMXzfx8N2JjZ{O0kI4yI{~sOiR}UvB z0OlwFP!fp?hxKmtB|$SE*Si1f6QDXph@v>)e5wG1^KB-$4`%qE5$Mka|5O6F0ssL3 z5&oa=99J)X@Va`z_GG|$1!R=;P6e2tC|ej@mHUgXl9s?D*fy6obbSLAN48i6NW0Cq z*HJu8KM`tIW7h@iI*m^R32F!XU(4O+31#d7b5C@GEVPheB#^-7vjFxJj zy0}W0kCjrFNdeHlc#jRfro{7nnvaz%$2NcoeTFBA)d5(6Xi4tEXDJpcWwhw-)(=RR8b)QeKU)aA2>}sAJWZt<;2^Hsu#tOXi5`{(+(iIU5fvJByS2&t$?HB+O5@j&@IvBPNdm!< z&P?VwuZd&JnsF%4(eJ~0FFnXI>4P2$&TWoz?g@#7a+LzsKa>N_u}lBCWZCPdRp*#- z6!+*3?$BMVbiKXT)!>V7s=)*71On>3Gveit8cx>^{TN`wgMH zUU}TBez1B#WcUZw(HTkr)`;Inu#ve}a8a0%{V0DIfN@6-`1brM)Hs*<8N&ZpEIq8C zbJ}HPQ@OHw&Kht{x5e7KSup8` zaMLF&l{lr3Ey=DLFoTXieTHa-5Wb*nPT3p;d+ofEyL+^nU@vJVW?j z@C}>_5aWWtvp+cYsU*w3u|VT6L&!g2Rg3YjQ3%i%ST&}%vjEq@?>%E&fa|!Z>-iJO zuB>Y>9xaf8_&9b$gIq3{>pOFm3$23o0j&Nzxbz>q#Et)Sw-NST*B%Q#-~Tbe`+hWg zOh7*rVdMymiNJp}-LD=I@Nc9C0LKcw;W>c-q40km|K1)`lto1q(9|(1dhc##^bvnX#hWWosXwi&sa(Xsp))7+#fL)(5%N?@~ zY-oIgBdCPg7N18yxZU;&VR6_tD)_&ED!9m@`vwDi**~eycHqJGKn7Ng=pRsDQ8K*& zP+DC(3wHCL{quigGc-4w(q4z-?Dq)&v#(GEp#ZG0riTIm<@S8?nE0YU#sh%4{V05E z0{hi{qWvHIq+0F#7|#$a{tlwSud;Qe6RrPg#PUta*T$+s$wz!YkURaB(I4D|219rH z&{2hqM{G}6o#i2Y>@{>|pEw))E_2E`{1>>6RXJkBD=oji-d3IzQBS< zl*$!!*eQpq1np&3T|AY(wBXY`5awvQyZZ4TkB%5!ed_p_tC-!>p zGqvB6=gXOU{0rN+O;=6*-n4@&Wd=!24pkc;lJZP{5P(4e>O|iF5tWPz31qe+&V7O+KRo zkI69wfNl1+_p1Wn3?%@dOQug{fKj&vEze&!-4|HA?aD%8o8AI}=)9tqf$mTOL;xqp zB5+6RUp2)NzF@3zy&shWmMLT_h%0yp(zRaT15LRtM+FxxyMU7(kmWKWyWf;4z(-_4 zk4Y*D3O7;&{dhNJQBFOa&#w|-txTXS>WL6_jFn%jzsD*9Q~+ohefgcRF+kD6zlx~ND1cA`)qMm2-TQZ6 zR;yhU9VlgGa0W13XS99FvTuMX<_tT3SmG}Xq~zr;yf~qo%fnc&tGLzb> zoyYEiZnkj&-fHzd00;M{z;mW0*y#``06?NM_6ET41dA#*p~hm2fKJ)o{!`q?!E2EX zW$#MHd4z|-8Tf1eh%rFroJdJuVMT_(^XyMcV_V?CGe*%hAk9n2xF&7B`i(}fuadc0sKzHgqW2y_DFgvF>vm+pkV7T`P;`ab+{ufIY z!bAyHtonEWFg6mbyQoC6)p7By{YZgn z1ub+s&{?z_u^&7o%q2LxV2VQxF5w^)G?UL*#t}*0`6s-!`fp$S{t$@a81hh~{Bw$% z(}KijJ%pUnw4Ac6DXVrYmX9f8kR0k2c!c%;hgE&>V`vqI0u2V?xe7vP>DS^f537)C zlCKR{{W3VcqB#wXl}%Hfq;fFlS>Q=YJmTm`bInr?uoc&r4{W8{XJzS44VuJAw&J# z+sS2Ebx4v#m7L`^%ItCGY^cY%&+axQ1n#2(KxAmAriZqRV!wS|d%u05<%yK;w~s~A zPyn#~J@OkV`-}`?bfDl!yo`=v=O9Pt71ue}7OzW%%I_Nw{=kBEPsx3k7YPj{gk{{g z{GZ|urAAUEKnVmGqQi&1JqRTrZRUbXK+F1~w6$q&)+t-RdHi7&*xvowK|n+SrE+!& zoM#LjTKKvM*&Vt3u(~te;PzJ{z=2gEP?x?J!$%_AI|E3}Y_gp_vd{AY9?Nxb90Cf* zA?UMJ@(3#@0(;!Ub!yeM{%h5DUqRpNQ`mRuGll**=04lwvw~VMxj+9M`1l9+ZUH#gnzBm%?pnJQc(o>~FqQo(^jlaYJia#)-7@fs8mIiWt5WmL?MS6v!g2+!?$T#=K+QuC zN)HSFnDtLKsG6P;%o%4-L2-h>zv@qLsef7x2B!#Hz)i~)mbBFfD>2XN5C@=xH(0F_ zAQWcy7yC!k2YkJ8J5&HT-DOIiGwa;$MW_2dGCZx34JhJAnCT zZLFI6CFQm`yaO9K55G|;#rSori~lKe{>Odh{_jnzvjbED`+Ut%06={o^zWVgbn9*m1;7%k4bPwHF@nu?~1;Q8z#U6$VHW6bXyR@?q3)o$W!T zmR|Y3$@h>I{EeQPRv(!0wI($L6Rz=vLOEZW+xLC-_P+Z80Z=EE@DWmiR(BAhJ6Ly| zBV00w6(>Qe#h4iZSQqVl;npV7kwW$Eb>(pVD;`FlZAzl=f~*SaESnZmN0B_(=VGOc zKxWS8v0J0`Yl;l>qt}V>UW=fEC`HArIGHk-ZznKz5TuAeR*nr#4zq5Y;IR1ba!nui zXY(%YWtpyy%&ZhEGi{-yRKwSqEHlsK~JlA z`77|f+fYgveb`nJxBQjoX#Fj5A;cVnd5Xmwl_ZAK(u-gUj^p@`r5phg3(uH z7(fpp>oRITU<^=k7lTkDER3($b#Tw^Xrbd?r|dAJ0Ob{P_nB84Dehy-Ko(uF zDGTQrxNE0-4;R#<(KG12KO!HjiiKaRf0@&6RR2*3_#S6F&%@h^0i}n$*+1@1pHWFu zK;o~IrU=3_Xv-OH{|f#Q5Rbr(XG|fQGHt`)sWiCIQ<@T81Ul&yh9NXVa;b96Y-|Kq z3keG#-|zg-x7|jMut(;5OPdR~g`$Tx8~I=5hf@Ny{Leuo0~;DiT^1y6ZEtPHHhmfp z@N-K>a*T7IeqMt6N%OHzb4k#3dN(RfhzRtAxG>=&N8c|2{h&>b1@Z=WB559^-+`bD zd36;4O-n3a$56R}x}NtgBp8TlC+Iemw*mT!ZP&gOb+IR23d29-^dFOzp_HYVQvqoL z>SVc={DL04??c@8vF?}0m$JOJ{h~b2rS~^&6#$oi`!=GuznMj}ye9WOc0Z4wu@6IC zt1kRo?!S>lL2^t1fD;K9|3(mSZn9A{qtis$$H&)F9SMnZjBtH|h{$|d?p)UyuK&8b zMx<=cO&~Ui7-$_OI;9tW?^>3Z@)W=q!auH5eF(0>R6IA7;f63XcPeH)@vdM1<3-#< z*Di!EKL_`0(-s1o5MZDV*MBU6c2I?Q$D{6)`EdyPy|Y&wGgPYKuMzqYCRPOSs$X&S zL<_JC0Q;g@3WXjd+66xHlM==Hn3up|bc{+K1E6COCm8@0;yb!MvyJ2E=alKbj0Ll! z1Y()j^V|sH*X211{yxj>0IPfI9+pq6{~h0--UBT8*EIqU38=SABVg(5Crw~MNDk&s6O{B)kbqK|+3Fh;G>+e*TZW&y(j zNw*3(xcdTk!W$6PysBOz^aH8tj2ICUGr=O~&>oll3xQv_8p&CY00Tn`V-uF(6~f_s z&_h_l+KsTJP%EtxE?R#TZQ~nWfKS~03I8PGmu(U1z!lmkP6z=@z;IGr9;#{}0~88lD@3{P{cjJdfA{n4NJss;o! zbA81;U7`-g_wkkw_T>dtL;MU$U+iIQMR3;@FlgkXU3OKZO| z0Dd@sR6S;$?<3k_8|@4Bh{ss@4{42xjM76?mZ>BwPVQ2iHj~@lFK@n`U%!ff2EVgE z|AqoYRe)Y=5>ox4s(~K!>L&P{&L~Iqr|ER~<4F0hTCF zCnMA!XoXfzCjqBoDw#t;D1vXY?%Q{L5Cr&qPE85V9u$3L2nAPB4lapxvn0Uhg4k9n z19VegG2X2@1pgZnhopYOtFib)(POE!7SQg&h*0IrRM z>A}x}ERY*O2ZY_X`99cvAL@QP=Zl(`b9S575RfyuPe~+bCz0l|)V{90-@evz?>D<| zwtwaJ8}?0qvuxh{Ettu#ObraBLH?vl;WE=4s|XOU{kw@|U^K1#GZ-_4eu;`@Cs0A&-FWa2ZTVxJu%=?rYFJjnB~h< zXwYC{X>_stclVan;0eKj@M6s6tbAnL#w*JFM_%D;P7&ykk`EXA)sq#X4+;`p|Bo1t zABGyh#k~qEpP=BbHCWug?WFKu-16Oeq@d26NfaW_5n{eV*#9*G{0YFA?<0I3K;!n9 z3V^%+Vh3cA4yp8US;##E%p=@Bb@?0-9FQX2{++IV!W4_wDs)K3ITtRj`>wdCKq$t1 zzNv_{igyaeVnhm*Vu)~X3}eQBd;`COg6AoCIYLN0Md_t0c}$_8ZyCjUNiB7o}vI)><|ZGulj-&Lyo3<1V{uv&{g|_P$(+0 zq71kxm=vn1(j#d>DN(_3!qf%>9DXx;RejTYRlVq*5cm&FWwn$ku?`lE(j$VVT48aC zaV3nvH`RdKL6y(rt&VZfYv=hJ%fbE* zEL81HM4S>+^nBZ72gkLpgNq7SYCJ`a?&45k*T#LU3x>Evlqwj?FK!e~PMtJZ@ zBl{?~T+XzY+Rl$%HTa(*$FSV1-dT+YR}BHy5TPQsE06T{e)G4f=D#2-OZ^Vn!IfSY zTkmv8H9HVomb}IeZfftBlJdKG|5ewu@A+)@@0$YPst@N!&z#qY7@6{%W$k^>TP9NG zIrnv0vFDloyRy0Lw;6(=LHAhlXqv+M4>~gUv)U)B>eP9i2u%n! z^)Afg@I*3(p$CQm@Ca=IPBnnfchM1Fuubu#`RYVUw25KTRf|3 z=Fn?-)KzXpV7nT()!B>Z)#~&KLPS~qCrn(SsN#XKZAgKgKqQo-nDbBt6FY@wM#m-) zwgW>QJw)q08u^ay_^g?2l=2Rfrd{cxqgyQlv_iTr`Y{tB6aw7JD|_72!3q_tV%VlU z$F^rQb&su@y)u*sApy~~bZ+Opo|kEbU+Kfx3J%?h=j~LSoY7T z|BvSf)sI$>nD4CJe+SWj#C&I#01P{)0#5T@w(bFhX6y0oC2L{(oR6;MS)o(Gbc_b* z1lQiD@NvJ|?^geM)Pr&2`=bC@9unA(rT@-GBjNx+kMu?|K!V@+5T%fD7WRnrOi;$v zOzSE0qF@FxNsm!wK!_ZfTxz{pU%G^fMPil*8(JG%oy|X6ntd(;VQHD`5pPA^ZG4iBo*cA znmM`%n=1o#amFj7-;c30^9+@Ldi~gKO(A^3H1|~k1oqkna2@NPF6%><|0;?B6#z^p zV5~cU4k*+b;I9|=aXo)B+bTHH8%B}V?733r@x^o(@Ic53Pu=@n`mV(KCmKHV>Sgb= z`ip~at3UnXH`O=0&x!s|>;_%`nL@PM=es?Eu|I%@A^&uQ8D1I#VuT!_C_H*~RP|q@ z^Z`~bd-x+(3wem*#1#?@oT!q-RNz#$7oqdJiENo*^N8w!OQdf*BNtO&x26u;Sj zUVSxuUOmP0p|h*U6nK3Iy=1w{@R~Acsvj`(=Ewbb)!#n(eIdYyk0Bb%zvJ8DIbYqm z{=~Ogq2yc4b_tX71e)`2ajXFV#Kse~MoYfh{jI7#{3{ru@B+{i&?%}4{KkS&5v&3r zh)q*DiA)lj_pR?+?-TLPlip@dkvgN^$9PgX_Vn=rF#7)-?*tVAdw328o#eN0`RDgv z|DM2x-ypkuZVjz8j#md7-*JpJ7%|2Y0|8!a$s0BKXO#R4vf{;d8UR4J?gSQZ(*^|E zI9d4Gb5ifQEc3S9cbnO3+V1~<-3zZuUL5oP8IZ~p0EQ=o|Kk2nC(^1&r@e{fTS}L7 zE)nyH5cC%aMefhppQ6c|LR`)`oBKtV>! zEToH9V;Cv(kz6EZ^ATR!jfTRf2$5>^bwJa0>40;ZDNFfe@8R@*kl4Ko( z$F8pa+^6ubaBmlguou?Z$41>_qx@1{E7hh7`Fg6$@`l{cfO=jIv#PL(_`$ceb>X~B{jBj(7(=1}z8o23K29x8}f#2YB2eXz~(D(OXuwC{~S9Z^tJgiPPXdrEjz<;hJ(NsC`>t-sxeanYJ0F({>(J220`*RvV z6YYOBhu)(EShAYO3Kzke(JfpBQQ_A8M<~9q_8aU^1%Lyw%z{c`#|HOr5fP+xa1(1U zfHUajg!&8^<9g%;9!#j}8jAR#Kzz6RgZc&^1TB`);{CznmlGVvPHTJVbN~8VrU6KR z?S*cWgK^&nTb?=3Qxs+SVvp~AYB-yF0S6JHokWbw(&lwnUE}?ky#{VD5X@~x|Nonw zcv~v612`EwGC5i^WMIr?a9a13w>{|E&Z!?HGf=M>uw}AT0OU3TjBp;FDssN|T6$Fw zRX`d+0O88DqPqT)+SV|Ka*lefySv?fo3;>m7YKkhWt?V5WVPqA?cx^SiD+R(fOZ_0 zMUCz}M+v1X@ELQpIM&i{ zG=6=Qhlny<6PA7P-A9_SO!#Q`P0WRhDyztd*#}-@Wj#;sA@{mw(S>`+RJ9Uhc(PPA>pl{TX{FSpCO? zX*I@EY6h*!m?1qBW1;_2C>BD}C5X;|Z#hI+YBp|yei6b;;lFrI2+i^_+_pZ;jY34M zY5xfW>45?NX1FL%nQCRs1G{_;KQbiO(O~LaK6R<@Z8hLVq4jyZELd!iUeax(|BUt@ zysmEl;Oq)zmDc~dqmnnYU3`D``(&r5Mle9(!G{+gVxYZUB#3@2zfPSBpH5$9ytY;z zOCL*Lm$$!(RNf{XE*cjZb!rpZ7t82*`7yq`I?7Q0D_NQ9cgTt!4kT_FoY&cxd{+`A zmw~|NwC}&_y6<}aCwCt5cJGrPJ97d7O>+D>n`% z-dJ4!p-fUIvK{~tluUf}f*VTqOLNRAV$hy8!2n%eWDYSYON^)-kleXL*IP$~`5u8Ub=8l)556nRcd z76C_AUm;yD0E9?jw7}B891cT>uh^bPc^0q&lD28}Q5hg@GVoJ)X7Oa)pH~P9bIzS1 zJdF9q9lQXX>nJEAk~p|g#8(AVKbnbe5`e#}a4WU^{=c?sGhJ3zu2Be6%r0JVmI*7V zz3KuWL_hM_-}0yM?ma349D~aBK1bod_<2~`q}aJwBWvS3&27uQqNz#&@mrUE6#_+E zE!QXBpDO@-NBNHB4Hw^&Rk(cneXhOy3E#K0K+(Gjbo5S9Srx(W2>N%@Oad_S{|WSJ zjKDu9FPN&d+#wUMq=uG62H%}7CD}9C8Xb_FDxnvE9uy9eS)X5M*c?x>3!W|CAdQ*dAVhK%!J` zJ?Yp+uH_#Q_G>i1F~+%%Vz1WipI%?H#9xiuN8KUjoSvu({tEqirbcdwOgT1Oc=;_H z&`vp*HP6l%&1#(BvktWK?J5R9QsHqUxOx%rMc5bkl#`|DR>r?5i;7V-$Jsa2Kcz?o zfHIY`6c7z3H~UO=AUOwcN=o0jyM0CPyz3FxoBLH zM*(O92ddgYtH}9ugT|pI@>_T z2LJ5lKZlwn*V!LMOwbuX04f_EyY||$M0m$xo zV&5fgb6MLOuOQFYOlys$|5O5~?TKI^2>xzkzQ4#1BE*1t{l-Ify>xsH_q>^OPP6_31zVp%BN{%2VGUJ>-~TLSmI zCaB1qd%P{?KXYj#z+G#-wh#MkA>f$aWm&-f1K3k~ZV3v+7WaD@guz2xyHCc<6@*Dp zot|A#0Z_zS3x~}K`e?ZIM_;8(j@X+J61!pjXADvy;H@&1TIQK^UIcyajmJ_ZzaeD~ zs=_hX2cCo9F>l}NOqMrQ>G7;MZmx}c>{BWpe3s?y)IPSF2>KWR%MklD`vm{Pd>sJ* z2dDk&XuMxNS{zl6SO)C?CA`eNmOZlqSz++oFSr}~viFMoV?v#kKxbv1^K0Pt9N3&5 z>{au}SbiSyT?o8b?Vz{ag$5l$gPiNH#b03h&2{}>ao+Fid}tItOM;`FVs81(A;Qt& zX?3uCS?v(;@c?-0GJZHaVmUMx10=AVU=~(9Eg)7PC!8#~pQ*H5{1G~t^Z+Qzr96|$ z6NNTCITT#|GkMP6!e+M1JnI|s+2w8YqA2xCB<7x%m8k*g-I8~BZF(h?FIdi$H=OT# zeAkk#SLtQ&L}J;;RydA3ME1wp|0lb@s{Ul}FRE{bFY#cRq6{Dk!2YcI`sdH9$zQ<( z>Ooxqs6bc0?GPl>uCP`-(g*4(FsBIIb21`|Eu{JOcuQj%c%T;NUT8A&!G4 zC+%&uV7q&_AP|B-Lgo_GMf)l%%@*DktN-GdH%A3kFQ&+!C< z#1N(SBfQ+4#$p)OLcg-cNgMO{I<`Es%(LKaP*#`Bbqr-%QHQt*UA&4yu92W1M_2ucF&!s8*TnGvb#ZV|$0a&>TfI@$)18yfmG0-Rj zZVETG{LfJWOduw&SW@XFOEkH>$SV{8$80BLJp#P$`jXEAth!bkSycvHf}vuB_XvX( z^;jbO+eL+!3IJ(Lmo>XXtD7*rzDjMM^tnKwg{mQw+b+w<#_{Q(NYcGNnT28{K=wPJ zPoA9xeyI>BDYqW6U;fz#0X?N3EU64@=Ve`#0HF}D0$%5RQVeijt5c*brz%AmP_FY_ z2=qZ|yfOaEkM~eeo{=XkBYBA6+Kj2CtoaSnll%55s^?0D^)WSnL7yV#uCp1O7~eIZ z7l9BDQ3f8d3V;d#U3$wLYQ-Wdd`FWby4F3HIy()fe;iTzj{(Xtus72G;sC|s1B82( zDAFI50DG*F7!jV;#t3BE81w&O2>sSFHB19=efsHmSiLkt_-KOAa7+Z|6BGd5Y9F`K zU#uoDWUQYKEgwKbg_%#&?o^ZkMHr>%-lk3L@!0VNi1O$3FH`=e^;Qw~yzKmnvRBTy z|7H^Y(P!*8>;2f_eU=sPfO4)}>#tv~oNqtftMd5#4zIr}NjM2D-TlXC^^E%O@d<(c zPI3MJ)y}i(Umg6W`qk(ueF9Y((~?&Ecm{mIm0uDZ^&ws@8bz6w6v{6<6{{-*8!jOs zm|BNr7W=HFuCnVG+?9lbQDD(!qd~L`=pZy++;!w=qTvhK1`h0rz03~BQ11}@cA7dLIxx&VV z5ou7(PY$cu$(IDWWrZsORl3Scz5hdK`A--Je#!?&0Wd(|SLrLwcd0*@{R^+KO=@-f z;8DnCk-zE`!`w3z8fP#TBlwIx>R*GvPnfc%CxEfMH1H+e3?3!MwxnOz(-u7sq=~9& zyJ77IX1qr)%1(GVV_0GQbl;^3cCv|CR^-Fa!H&fF&;)MIrSLl)<>=(^gDga6_K=C>8_sz#$XGv6r2g-bD^*=+{A2W|{8iK!C z#$Ln$D9qV)zL{r9h@=F%;L3Qr)Rw{7RO5D-pT)9FE25EibWf%@45_#$IvpUo{LO&q znj5`++^s@Dlry3;!--yg;hq+qfMJMjXNSHwQwhhZC~s;TgXTuf8}!xpdwrU+Nbw#Y z*t#e79sJz6c&-eH6nkImmi57f!sa?}YL_?r>mqk-L#Fi!3M`k*=mmgPFPM8B?ueY; z!D`Ya4+!YB108T3@0=g409yniuDkGZ?!7Zf;im-V3-@MNCFkW&;O3{melZ~MlPivl z$VC4S+H)1d7xW24L9h>m0V(PQ&&HB5!8_v>F4Gf)r!MZ(Gp?P({G3j)x?=fI_|kG+ zAeA4Z{Xy;wz;3uAi8*bARM3`9Rpb^iFD6So+fE)8=J6t$x36jMpT8~NU(S~D^RIM% zPq{A7pO?FL{Z{Rn_OXhCzXm}cu-sq& z5PF6_zKby2)0@bs=?u;DF`~2|g0a|GA@!VZhL@B99bF~F)k3uX8!g0TL-iOc)FRoa zgw4&tP8<<$iV`3L9vb$LeXOO<|99?xC#HU(&~TYl*b%+N+y-60x#}i>w%hLuf%2h) zHw>>naTJ^tNA>1gO^Nq1IY1$R;&+K)kFu)Td4T1g^&WR!^O3Q@rC-}TX)p+P^W)oG z939}(Q35co=^;BK(`1y;jB^P6VYCZtyKQK(Ff5)hku|yC@ZQ@Cwi*p^WttayBHD01_4-V0rGd8!5|jF!4BF+FWu!H}_Ei z;K#o#T~=<{WmyC>n?%4o)vWtGmK)Or~A#hcX`w`T%&$o_kQ$q z;R!H@sLaTE1(+lFpH&L5T*C|7kC5Q1b(Pra9>jYcd256ZtwAww3#zs<1^|~jFL^DT zwV$)y-$LLj2-ut3iQ^dO!TCt`yQa%IeANVm3P!gnk83ucL7~qG_t;I9pf~sq2fFrs z?ftmG3(u3M%t?1XX8bn7XZ4+nE$^-h|t@^H~@+~bAyXD@3tn^L#T;l3I2S=c6$y1nMKi6y1$v; zEQv1LT)%ns<;UgO<(&JQsl0u&^wT^R(@GyG_?P%7X3kMg#hm{hK>!i{k6Eom4*>P> zyYvU+k@T6Sq$|8rm0$tN6g)s7Z&GXFi_CfYM4=I7dXU2Z5ccSNlF;3Ns?dP5YUqJ9 zp$Q$SRY3(VUEdtuVJZMTrrnW6mdg<4(?pHWx7MI#@P-QiWIi!l@Ym^mPRC+8Yt1y* z6}eIgpi&n_6+wUCJ_r;H^(&R|1+Y|H|dKYtjF^5X|yZX zp4aW8pfYt?Ki3!1*Wx&=|9%iZhUJ;g_hZi=1fbSayil3yen>0H&amgFPbk^Ic-8KL!4F zmJV%x#Hb3ek`a_fNuRmS2;nQ1Mbn$W)l0fVrbz*v1>RFL@L>)zsR(dsHH9Xj=a6B& z{3Pv96tCF+tRb+$1g^_BcM^uV-8_HU@%Op*vit9DnS8~0QrHbEH@{N?{5b`{<1vB% zobNwH;GeVH-(pB9UMy~%4inMujjMy@U*SKv91%8ocrFXes!Bulr5jz8_A0(q5@s%* zLgKs-H{VvW@}<`mg`i#ldgkDvL;qZmS19g^62LZ7TgX7r?z>R^+XCAs_TFTrV;Vq= zV+Bve(J&&x7f*MU002M$Nkl81n2P%;aaMNiA#b?wy(3PF7&z%t`XBrIuCMF1_VbZTuECHobE z`H;YS84Ykt71!xc0PTs2g#~b%otir2U`cJ!9`N;~tud()z31S&@{+;fmETr=b!hcuy zcU|A*W|HF(O$(zC3c^qlV)k&h-inT-z?EJAMfi8AMd^n5oLYQP<38}_QvIX{Wg38V z!K?xx6oRz5R*|dHLk`(}+n)IY>#)831|T3m=yVn002Cz^IOht?t`=28dDeOB9;0MiBUM`igxl$@0ZrNpATf59_yw=p-FD3Wn zSMs(^7tu{**v!Hx%S0j(&g9l|%VPdN+h33`NwRtc@nZ|7hr54MwjwA-&1AZW1z?AW zPQoDW(|tu8U-H-wDx%x-0=u9!TS6QbXh(JVAG3eV{!8{JY$sfI3L!ZQVp0?ZAN1j{XXlWT!^LIybM4y7zj;1!aGLg3uBz0C42N`Q!Y zL3ICDz0>NO!OQ9e5$|34@AY6p%nD)v9Gq112iOal@2~JbAooxJm}Bm{Tn=49v{$(x zE3zb3$m)#DwwwFJ4Cx_Y87E|fc9o`;H;XkBEq5% z4@Mk-F7bs_hJ+V@I>F%dwte#Uzu-I6z$qz=Z!2buuMBK!FhImZJ=#_(w{`V*wW&Vy z{A2z<3ILCd{jzrX$Zzd7_ut{&w{(dkhL(O6+xAgV7DpBgckt`R0B~im8J@FD?%|3u z#tiWW>d~pocyj|4w~}POMvRlLeipC|tG|jFc#dGAyzo+(|AG_$FIidZhs{OyOdsUd zrknHT{CK(b!I>;;A7}Z!+TJ$>KzkHQB*_oHc`lJAw|QM2$B;mwFcj%tG#C8G&33&} z%T+L+;YT4qmbY_X!IhzUIf=5e59N6e4lF z8dlGk5A|=IU zmdC%TIxOQ-5yiDTT4Jq)!tb9{{YS5$+rSZmCZK|b`*q9>^S5SGi4(J`>v_$e;)$0*Onh*Ja! z?akOfAqe2{sCvwDp(c|k~1`iLvlH|r(x2)dt zY;nLU*?su-Im-j;3$UsVSn*@TG$0iKHA48uMs2B+?ij9iwqVKg6>?DrICp~gM={Q~ z>ABK~4UlrYSs`Vs|DLR@B`IpClD*W2Uuc4NZ{}nSe1rFA^1639m)Czb+ZL98Hf?G* zs8^irHRXif?A*KC{Pz+X&q zdbq5lU>DM6wJw}|?*lR3ZeNxLQK(lL;GBOfS11EslV65XK&`0_gtvtWE(GVjU;CCD zX=l1&QHMxa(`o~==&m(qz3wSmTRZ?g8^#G_3U?_dg0z1oa%JPYL9qhbdX|+YQgWEM~2cW4HW*(xE zR!Hk-jW4FV1l5Z*+aBF*2#8DKl(;pIKUch%V&R@tFA;FR9=?oa{|xvy9$_98x`GDr=_3T?h5kSv`8PQm3 z7rUaH{bSDm4@?8_Hf1gb-1Vgj3<^$uJTn*&Y4cGYXG8Ox$L;cR=RNrS+!X-t@(B|O zyw?5AoCuZId2ABlEb}<#|Fiv)jCA^D62lyP$}ijCyvuP1q!;n?T)xPswD&!}?i30D z-r_d*)g;=JobxXMF=w)x*7Tz!36WVMobL>RYydz!0SKy9;fhR@A_NwQm!1?65RiKy zc7l{Dm(0Gqk*x6gpefsKwh*`q0$1V6RpssHyvsH1>u-8LJFg5faE@ZUUVyV*kE10j&O zu1cu{xl{RNgnRIuzi9`B6qf&Eqy6`E|3_kHNDbW=k^cK5H~=i&m2>~ubO-?WMhpP! z$cuE)iwvVs=2mk9WgVsrM!-<;JT3kuc8KhM`TM|Te$ed&MnwrA4UiJ3kPB}KjS2<< z)XRr?{}K2w$N|Sm3fSGIyA6ThQ61Y*aIf%IiKPJD^6_ivag9c+Hp;(3zs4mM03NrM zzMtTCrpYnZ<=2TIfE?s1068XU@UwZYN8>#=m6U%HtP%H&>37y5##s4%7?L8}+YYbI ztJgJDw$k%%GX#5s z^O=`K@Q+mhLXelH&`Je=x9^&~Rz)R(KOAPcx6hl2p1zu$Hi~4-K1qZ6kx{daag?lkX zCBSyMgQ_2Ee{H1y0nd;dB*zrGrW?eA%j3&y*pJmhoJ)<@5C~lL=eX~ZdzAH{As7F| zXReDJPrJb%A>_MD13dDNgE{y@msY9%f)>8`{LbejISkaT<8VSl-v0B zJ#Pc&hn^G6)<~-5TlI$S*xxuRiU2=NIV#u24VyoIhl2l!tjzVhWP7NWXLj&RktNI8 z+ib37raUf3<=1ECGuq{!-M%FMb4~eyFKb^SM4r3s+ICqR$wV-ZGrKH>t4f*vQQ2(# z@+4`FC|Z`i5b43Mh{DCbga?T=FwwVOhLRhP{NO_^<_h~%s>}$=XrU4b&%qd5kDI8= zTN?vFWXRRdrq(v1w(=PmwDr#m+AaM?;~QVaYWtOF$2M&tu!TT@Ky+t*Lg+V$N959P z>$ETl)1KkiVy=3$GxS7hLyPTrbO9o-ybD7@_|Ri@%dy z#{IMEWH_nLhWMQjJEz9dPv;J6e^+ZiIfQ@key#gT)GM8er#Ey%wiw(UBJ6hw_}4=L zu(Lo}Xm-g^6o|%6>6!zN6PIu6Qx(|w_Tm+xkWarv$e*DEm|{c_Ml+T{oT(h4|2kJ( zek|lZ;1Ju}s{Z!9?*{?D8(th;lv_@5)5A^0R(xBv-E+KOYGO#qSDL}qN{`Z5k&FFJ z-tiMfg3xu)7N_>kBcrUN(B_30-t=#q|FKhBo>1md`cMY(FSLrmm;id~WYOgnQpQpN zpvB}vy#ISX?9S%Xgk?=XMJ6ONZ;R+5<*`IBu18w$P7wTI zCIaXQAVc5u$~y^7S`h+&iGW@x+ze*lNdF4pC(Q9Y9vl+=e}{LWv-V79`4323Ka zt1>`WcIUCb=$}-7xkIo^E&tAK$MSzXI<1~QAmH6&gq|Z*{#g7Cf*#BM9n$w@qwxla zrSD{;GsVmNA;GR-G{@Qx&Ym*mMP^;r^-^Tp=gH1}g}n*QTTIkDPV%pKwz z@O^~vT0Y`Cy(RrMWi8?Wz`ca*^;5P!IeV!4nd7k>=L6g2ZRJ4weC~7G=b!GQ0-*g> z6Ctw9<92WN*yPq>(Q~G}#%;R)Un=~2u{Z15qPxElFz2(==m5be8VF-aG+wojToc!N z(??CZ1wj}P_)l2}^%+rnRRm06OkMi##bPJQ(^crBR%P?y&c6#NG$*jqRl5-9hfMt; zxK?bZz>lC>tNvFE))2CjrvxB6sg|#p?W96?kI%vy<{jK_HO#3DXg_lEmD}Sj1nva{ z7~0e`x;)b26;|2Oi~`pJIvmk++I{`J8DbD+5zhHtfhRLy?ygKB>C zuv$rDb`anrK`(-EY|x_1nk#LQMs;Bvy+4$^cpc1Uz;;^wYJ5^X+hb|9*LziWHmyc8 zBCSKlenJHG{Xc(R{ph5w_OznHq$&JA0MftB@S@U%n8+92c=71MsqMi%f`GWLwO?HS zwt5|ce+0GD^3VMKzu5b>`j?OXpX&MWxOzS~uIe4UV)jsk{a{*+iTJ;IGLHo=`b7K> z-4zOe9_Z`*e~;yEv{S?sA?Stjv&SwK+8<-#Kkipw{`zs%dy0tvss~OFt0NSKKUqDh zel&YrJtX3|3PhELCY1p0m8k$x^wEFh?&ajA2~LG@Uu*v>VjnyOF26i_R{hE0Z>m3I zWrSmRiS9$_;A6V-lU3D!fIvcQxc)wUJ4t|iL`aq&z3ST+d>{nm0rhMdK4QF5@OK3O za92;!#dM6a`|E1<>;Idv5Di!j%~k7_iAwlO`(@!q3b|& zYNi`@(MW0tH7443@axK2{~KA^>*r*8XJj_9m5Q|md_S7kSmwSJG3Ce1<5GH$ehY>E z{2T1Y&y*kis^curt=H#0ZbdG)KGWe*Hx$!7F{&uF{&cui}-56$nF=-ms|1h zZV+dB)kA1$P#B^Cv)y+=yKd40yl28 zDm37V!js6Ty^TY~O@MQ=0o&s(1nwpTvg6Z*B0!Q+k`X?QmaI2q7ba=2=(AKE%XYEc zpF*g%|6>0ycD#+=d8gVboz>bGZvRj)_vbJ?=Gg%6rqNDywp$bY3_u{P*DU+DAR_b% z7tja-7}8HR$(FuLYq=(;D22Nb&xVdmTUQ7SXL=ayjhGn#ts(}%3DM!hX%-y`6G*8&3*{BVt-tB z^<%E@jKo0&fPz0le-H`w*)Fg~h5Nsh^8%Qz@9ppWr1a-fBP*d6Mk)lT7q&CNg)1Tv zzSQn|PFms=fOn@b6RrJp!C3*~PWjIlMbC@goFL zt^ct2k!9$M1y7oAHGzNZNY7Nzr^O8;J7y%5p!U7hv0v_4|vb|2>b+FI5=D2qD@9%lV@1~XY0O)D!{s{ zyx68K1g?UBxFwd9pnpXP;9Pc>vpYec)$*?r;9Hjcb16S9q63YcShf3&wLjLjr#mYs zX*HG8akz~kzd>VVe^FYt1U*^_Vu=D^hbb(>Py#?F=EH_w7(6uH|4Up8?k1@MXdYM! zZs=EvAWg7ml|6&}E$DyK9ig49HX*K08Jd3TrG-4F~v!Pkhy z;xag06aZkK3IIv;6faRM(A5kN@+nNCQ*aeLXLJs{bE_rC#&Hqh*YN;u19z_n?#{6{ zrkC^oXY@^-{`+=nz@hQa^Ea1-Bk$Ab84SA?J3kcsymO2E4)oJ^NdFl!*Wbq@#~YZ- zv0e?p#wZ-{Fkj>sr@5}VIe0q{P+7a`1vI4SJsvphEC zHD0Fzz~s^taFJK1HTFPQ9FhuNIxw9heHkXb^5Z8l*(@!{03mJ{xC|LfF9L*o{A#@0 z8$t;H*dt&IV8(@4=RP8MMXvDxsHu18VW@izgHjXpWlc|Ps5#TkfH>c_-EJXpdk|>j zz58?>Bhg1RdR!yn3S#Z<9{UFM>eH8cC;`nSARYVsNt^68ce(2%v#;Qv3IJCcUce_T zVF1I@k5$j;{8e8%0{w6asI}B{9iORzP(!n7X_iX_4v@m6_R!cROs4aU&u~wjkY!^+ z(Bk8iz<^6uV8Bfifli1!;HZ8n!5Gt#I=_TlKWrYeyG@@c1oAt&HI*&q0x(1DE@k4k z(d!NJH}0Mx^c(DtdF=?a6Jp~`ne)G3F8hio|MdvuLibeT-d`i+R^l5d83KQDIBkxm zg+|IiF^2L8w%1t`x^h$0-UdXn%)kqh0!mV_|rThNs5_{APN9 zih)3MlmI@!@gX__4-7wf@!Q0)N`-43JIa%<>(^$}MELne0f0iIN1b)~xBg{$zyh8I zMA!A|w>-ypn|$MCxqZ(4OOqer$K+p;T@H}>8_{d?xf4gk1{u(G1kakI{6#iYgM1~Q#8USfABrqY~0jES|N1h70yM(6gaxlgXRoItE>c#Uy;lD=5 z+=pKKEqqd@_I{Rax1S~iHoLCJWs-=iTNE5ux#fKJF?0T34na3}!yH5$MYH^G{~pdAD{gCPo&nBpyLlEb^%3UA+bjSyJl zv-DP>ofKv8-5tO80Dmi#Wb(eD0ARYus;l5nY^muh@SMPa#KtNL0LBOuY0&|g;u7OU z3jOfQ=g0Ay^Pk)A1W^}xc-uKe@jS7!zr)@?Co6;5YiXPhj(s+9?8E(dnS4m|!YsPbWDDEZwD;FH zd`>%%yw5&uVov+Gy?+@XM5;{gdwmWOOc+8DU($cwY_Hyk@Zg@VFRLX%Fmywb`WP4x zhA-yCh?{ZU)sMNBGroqV=o&PI={&*ZcZwiAMt~k;Nk4VI5X7Ry=De0Se!xQjxudeo zdPLb~e*r@c=<4Y{AY_j1nEAZ35kZP}!sSa>+~pato-yoe{lL5yG}~JE1;6X7e?V=w zw{9VDryx+sjvYSwjGlJ7`VUTF)n793!|RO3%-x+chxeFFK(En~%+wmE0Lajn6#zEH z&O6o0Xr6QboeymgKpp9Ik3OcepTY>v5W*L_{Sy_s+93~M@QnOyz$bm~{k9F>;F zEphb{6%EWcT@jFQ&T?!MVEpvaG499&0Gu+98pdoF<;xt8j4!Z6jR|;q$Z;xR{1*F! zW87uym(VN2q$+^7#5M}HKc6fFN>^1>ElIn-LjMG;7Nb)U;QIAO`+q(-t^Uoy*Wto$ z#DC|tk9PQ+Fho5U+ulQPg@BZL0ffKe1&(H8P_z=z3fUC5At<>& z<2fh_4^|`Q{Tm(>+7Y;Epiqwo;A1|x{mk}$Y2U~CwdzIiDN`h-z)m;{!ztbpbKL(| zt`vmVcmDwT#`K^*q@Yjm;I7jlvicvZg4^eQTnLD25JeSU?zqy8@hj*+p?vMnC)MEL zOO)UkjiAFd^8{8b1G!=<>GB1!!tm-G4D(giGOHLhLW-Y@*q`Guad%xv;lB+7EjJcp`Kf&!;pRln!{ z+Y>mZm7h6Bt0fwGw2UG2Bk(_@Y>q0z`Gip!3BjMUR z#L6~>HV^^1@X7_QLA%uq-*U5V6{g#l-wz0Y`YQ(6Br6@5cR1jxbJDGb&#)!`8uHKb znfoZv4hT|raJE|=p6*shC<6{*@DE_^wLcdnfWLQF2|z1D;8$3BMO;=Rq^krtfnj@z zd2c-0tL6ts)#?FU{|@cWm?Ard`-X%|7(O_)h>8Ngv~%wf&xVm)u!U}|=5vI6Ew!(z zKRr3Eb`M<=kktX0cjamTt_rX-eZgt~6-%pW^Cu<)yv+l||1V=~!2KGvfSv&US!=hB z8)f^!jo3cmmLQO$zqo8F!7NuyayoKIXtb7hhy~O zoW)u>dBjwJzdEUw`%EK2s8v=m4nU9j|Ggv7QR60EAf^HMB9JKLmlpa;Ga^RFgxaV` zmz|b&oFXhwdex)lQFXN1CuT)iDMTf}LvU1@F<9ee@-hWKd5dqmkt7WD22%Jx26paG z@RB&e(mP?Lgyr76>e0z|h!nqI?tj4M0QYDVCE+D;9pvCfTDpD7CIn(yxj`Hu^(u4} z|HNkl-*!=ub^6AR14EoDy1>xoGT21PUrwJ@)32X#tpVv!03iG;^skP7Qq_k)f&YYt z_vlC(qulN?cBn)atwU?n)Fj4|o5S_Z_UExe{fy523gcd%vE&u)qGio@Lz@Z zKZC~)Z(qu!KhYHSV#SMw4(0Pcc>Dje_a;rUEn8yNj);uN{xtX8dtX!CD=?}iG%~?Z zW|#(o0R<9G8H_L?Oa=puFn$4Z=9=;c^b<6YCX6sJlNrJcFzHpP-fd5pnUT?Nec$rE zB6qg;+;cJ_BlCo3dTigmJ8zaRU!5-xDXf}0(?OX~`U$4AaRc(g(N_N}Zk@QrB8XlKfM%FWliR7=ux)`S-2ypqJqr6V;DLNR z{rAq%dYxdj`vXMG5COp1UUi5U??bF<4zQ#-@Q8L#;$EiGzclXM)UhMMuW7W5|2uw% zkp2??XD}x3;CRk=!Dk0J4Lw4Wv!`aq2u^Y9zOVqeZ)l*UBwF?$62)CQJ%RvQ%oG6N zc#QAQ-+zONHUtkE)z}^o2UX|2arMOy@7YRi2Gc)<`QM3t(3;_Zy2xl5>=P#=e_7cX zlT?{MHnoSM*xR2wTOil^m%%I3D#QOCczz8VdlJwM^N;EODe-rMAF6-;{I}Jc{gdj= zu6ubh$N}fhD;S;MW6nFO;a`9U|3e4>v^b6G2Oue#EKeJ3{5(;TWYO#pV!Dd}K=ok{ z&;KtL2i1%E2xej*nA8qnr#c2gh0(HT$QQO>+D_+3S9cU2$U-Ot6c-fSz&41q+c}mJ z3zpvWXrKNwwu{3es3+r(bwm%Xaqx1s&o(^H7AT0ZY-?GD(h{CKX!>>Xhxe6$Z-oF0 zmcz|X_wWn&nyqnPBlu#lKnr6M!cv;&RfjEIHJz{BH9(<&_&hAf_>jV5=MVh|MBpf+ zt2gRP@ZVfseO)M5>fqes_{kdGSCM_6 z%b-<))>yvjfUtBAr9xodSIQWY8o%w8i#D__o)^J{=?H(y@Bc-7L)0gLpRkGs)ADW& z*klwUvyNSbLsO4Ph9|zz+i9M`9C-0GYL%Xqd;f)vvRomw*avB2;54+3b4me zYk=N+@`HE3?S8Hb?MeyL380=rbqwOU%L6uIG$EGWQqHf}pj_BL!=;K{atu%3}&p&%?A0J2L)m+|7>-kS7w8An|R z1$P11;n)KQsPmT?@b6;qY;H?gO^N<=0w~e1!>@4q1rDjz${QuvGA)yyIOaa9<~t2K zkuvx_LTEe`1hXW;T?x8GJs?YP+5YF8j?jRN$lKLsm7tNP=HF_Bt)DTw)Z;ch{uapo z%$nr6M+E`)zs&41Vg)ej>i7>~fU%DvEY>&6lenE7_ByWl*9_W!!CbI+er!NKhIM}M z+L13ifm#4bWzBUPLAt&v#19GuwMHoxDW0X3(6yI6NQR@tv67Y)d0glN00u-xKP7GS1h&aVja=}rmHEypmSW8nJTmu zKxVA=Wl2_8pC*uq&-LTwTgr<7AivQB^V;W`zviRGP~0)0ZZXGjZrUh~-_&4P1&g<` zqA%NnF9gry*9eTqj%`VdnT`7>+ND5`+!X!}nF;{h3BceaYn43Gc@eI>smZJtX{aB{@-nemT@cJ>EkM zX`yKb0QX*za*_XO!8d2c%2)hS@c}Slqz#d7j))$W7>>y+4nizpKKW^7_@t+!)#-vD zqB+{0dhKy>BV=-o4uVa+iEaxBxdbz_5P4(X#kK|^>9ra`lXDcg_{weAw!l+u0mpfu z7g0{Ly2$naGW_A~pY@NsETic{?ChcSclEC8{uKZe;vOQuL3;`SQWUTm?G?47D30Qi zmT-_!a<%Ue=ID%6*%l4F2A-Ipp_#kI*HU}K)Tb4|D(!tmIEk~Ga$4pZLTAnvg!6sy z7S&lC&?K0C#C%pqPIWd^OQdo#F1fQ_B_%LN(* zv)N;1(%NFW&4Ae~MUc2ls5RFdp;+c#p_OE?F}L_T?G4$hp4d499+2~&A0s1L3#*Q zLQ~PSU9=l*dA;ra0q^-==s$}tPlg%rGPE1t5uG1wbx7Qs=TYP4>AZLOvZtDOY65`l z%&Yx%SH6Ifz~WJ0$@@L#wf3|S+JAsgOPXI3uZ1>%3)2y~OLO!zbBUvH8InX_k)OTx zx=+qXMqbD^Z4BhV5z-R`aS=UNeCE9y71{_uD*&}?v6UA{SW_&C`yEQ|Hi05;>QUO> zHYVD1p^I{($-qWkI) ztC&IJK^H<(Xn`>r^fB0NB++jgkKY&sVZ}+E)cDJk8-pVvuZ>sog{wSfITT`wx9k)I zFEvgA=d9zNutZ@zr~C*nW%IQR7=hM?aAapSY@!wf!f>V|GS#_x2YAo{v*0yoS_^&wn|4BvbGWjtZ z+}^dCrn9v@ns2ZvnvRKd`EXoX{&@e-$zMMBm=aG-0PrDgZ^tH3wC}%~=eYor_vg{P zT>t;?wO>%u4a_)uF5w3woG^J2Cd+#NSo0rw!Xkr?^kvvCZ@Zsg208@41Km<-;y;1l z9C19sG068scK|pgx&&avy?PGCC)KhB_fw9KeG5$=SlKb#w5y_e*JJ5n``OpzbFGgy zZNQES2PZMHFQ%{nBZwp(ar+lv5u-ldRUWw!5La*3KudLsv&Jz_1K*qvs{sty zKKNPYU#Dv?amJpOye>s;6kG|K;;{yCSSjRkOo_qW3q+0y`ES#O~?E_bCYlrFo z&M{&jz)K}&On7#=@dLp;&<8^cU&YmQNZD{q84dx*lpR+Cb8yJsY!?{BZwQcAEC6=G z8bBL>f-f#0ZuL!@$bPD<=?19)e5s{#d0N?k{Lx?iR|3(*7(6g;T13F67 zKSC@qTxao1p|`)QZUOt0VPYS5v5pC49JqAB`3^LpJ9O2d*(VPHY-pvqf6@OYTmmc@ zp_~NMU*j})KKZIzoPG(PFW<>vOTRJ)(4;yDjJbt5#_uW|&@#X!IA%zLt|2%gklVR2 z79*k*Ma{pKzwQ7wV(IJ%z-M|yK(0stC$#J^!p0bpE}~^Ft}@6gMWp>PH*!nw2tl;i zR?K0&pxnv6)^74(|CIQK_(#nR-jtDskE(N62CvyP?T|0Nn%}KX{1tpbOeP z>fYKA^Yy{2s($eY;9n5#0o%2p9a$Xyh`BHAJjQg3ZGWl>HVp~@L3KFc`)1leK9$%et-5Q%w(VK=5+TrsD6PT?`H@D zWFB)xZz)#D;P1PHAN4-*Y5o-j{-cU@`$OWcCGo;-F|+VZl@%{>T#Q3lEx_CzU^2yH z`O#_hTd36jXjBcxqpClhReK0AzkN%cI&Wb1PpbjKf&-{Jd+JsFton85i|ToO82wg+ zH#l~rM-Ta!`2MO=YdzSyj z7vEK{zkFMr9wQup`JZFLJV!G*I!5gEhf_S)*VVoP0OrSz-p}{2?qPd7(;)77+)yJJ@0a3|=X=S~UoX)=Zi0cgrp z+^(j)+qXVQ3jiKntv&2x@xSDEz&h}==kgi1&D23R=S-L~qYEa`8T8|P0!`@>0GQ?l zM+E@W=`XqVCFe)n3)8AYS)IPV{1r+mgu9+=l`1eP^kvys@d+b<6P5% zmH;p=8H_H&u>I(vn9*pw_Dkf!{wYzO%<78a+L6e<`gx$*f= zSpaag@$JwyqVE$=s-_j-&yL@@F9`rjvB4uDYb^ZXPBU#OB)RUn`spgFpz zPOU$Gk_F!7-zxBeM4;OLO9B88**LWR5XYoXj5tFHq`}Xef@lqJ*NC}X@im;aXJv_Y zEdchg06N4H$Zc8JvZcmUtHva^IUUHZm&QP|JFDJdCjDK1SpCpD#R_1A#vj6FcMt6;767|_)_+2jX$4>i!UDVz z%K=tdzt+3`ro^Y3#v=rlF&|J5wm(w)G(>nYXRUvC%$BC?7O;Z{>b*0zdF!CR!~)>O z@CU2{#xP$CdTSrwEoG+wt0M!J%vf2I0JlI$zg_GBoU~wVyk#36umyxvDFKbpHRVqc zKR#9UeBt2mJ<=X!c1Z;=O&jgl7a=Ren z7y zbL}7C2f(+;n<0UT;3&@MBN@GT7^BzR$GBCmWuU03bW=YG+-|Z=WZCSPqt2Y^}twReT}-`w#*O=1M+ z(XOJ3L>QFx0RSEtxz8|KjXCM?0RX;O?gZdN5@uKNiutPy`Mtnh;4Os@gxYhOe9?y> z+Z#|UFf(QEs|mrG={ZEJ0**c=%sV=wqPDKSmQhTT@iZ;>eQKB6?PK0HY(@)6#@at= z0pQWTvme88CHiWQBM9*sa4^KG#WnvUwAK?WT6A8g|Jx3l{+?@=^#MRSrZk7Gpp@&` zuMXp@=XW$o&@6Bdx%NMgYDhQP2Y^*7uwU9a*Z%8NG5%;%&7EDMz4QSWfccW8|AiI@?RMDq&v`|@9lpQhb6t=1fDlNQwJ=j7FL2iY zZ`7iUtzOHZaqtkezb}(;d5Pa#WAJm+O7>zbSm^eK$S3QF%{E z0B~Ew+F2Re>CC(7=zR^;EvMDY%PlAV+D#7zmI%UII3h+`_$tH7p|}(blslFn_o0Qm z@w>NV=3v%fq4)uS>5t_A9KmW+syXJoYz@*X!G{ckTfVuLY%zhvb1?pzW{Hu>GhfR9 zSeqKF2E7&s{;)nkyF%H(hMQhLin$Hj7WkAF2%1A01WjH<_{Mqy@eaYF>Hh)Fid?~~ z7EeKdznkL4`|f&68YBbdK!(tVBAY^J>Fs~a0>*QrLcl&cjXv9(?r@YqGd4_j;EIP5 z0;qzD^`K2nEh}Z2@1hspM`&f0LPaZtZs8BRFsuDw$R!avTN0dj6Jq7CsdCV#|y&-}qoyekmx>I-p^_%7+^u z%mUs2v5buJUbzvYOMz$jl9@4Z6|m1fR`& zOlNd_IBs(N|DTh-77}t|C<(N{lFmewxg}gR+1H+3Nk%CGUsv1js-8vwKsr|ZIKY~F zR`UIozLc^{z)R4(Bp}xEa@2H4t{)_BTSt4_qsBa6X}Pv9-?qR8w1BV<-J$t^JJvH; zJtlq$_I7j^04Lo|4h@L_9xG&*O99M_B>@zDfhK){Gp5B3gqfbcJw{sm08U7P%SuLi zlWI!^ER%T5HKQ;o#S=AkU@hr_HKp^teNY}m8v=kSCfK9-pgPAw;0&#-{#zCxJJ)ya zvZP?Q*2o;v6kM1rzxEvpN6YboRkPP~(Z@|N;Pq{|-U2i^Elj%y6q+(zz@|)S!fY`6 zF!n=yRmhBn006;NF#C|;qdwLgFsxG}`LkWDSBN?l4+nLw=~rkJOe^WOw)zu0DCWpg z_%dHYu5=JC;YtTi0f@jOaDNKE0M>Rer*Zd?9<+ln(~iw6)_y4cP};vN58@Z*O+lH= zz9V7E4nf8lae)vm7z=4L+RkW*<0rOddDHgy(Y1j6o_*h>wWR4VkA&YStgs}P9q=-# zv4teQIBJ(~iB@;;8-Q@B(t}ogT9i##5fr+VhZsBcOl1{mg#!lXB}XipMd^ys!5I8W(^kvQxmF_m0Q_U3yqTgKc{Pvr ziqYUl%+HsZ*A8Ac&4g4)#=e&o53tmwf3K4rcCIqUWu@ZtRvrzK<7 z|4xxa#(@9GZ#>*%bce`O3xHib`IvS&0QIYJOtfH6bDb911|jxf4VJ{yLW=+_A4G6= z=n|)R<2Gzt;3>2Kuq?`v>7U`nd-4`S7%fHzM_#*V@>o#LP5`X^$C1$ip1hy4@?SxK zZsha@P!XLK=r(p~dGRF{959gM z89rNZ)`~`UIMk;DRvnNhdk~{L5SU-FgTPm3Z>vKYH(a;RVh%E*>)3Word0=k?pZ$h4NkGXVnaxl7gu=sr!$dp z(=V9)mo5LAKKaz_C3ENgX}{Wi2Yv7(*+X!~xL>`R9apa=N7dnEw>m)h zw2w0aEr^6W< z<4{w%TjzkEm{+mBnLtk-46B`IJ?Ko}O8;3Mcb|I0SZ2$>^KYwqjI%%`cX*bp2QTqC z@imq-zsEpv9#X2;;Cubj=sZyCw49r4koZ2|yyqZKARjP+_8-CnoLM*0Q!UL9JRUMf z?lB*E-}-|1rxB(wg0+(FaNY^$9G0RWr&~(&-*W%|(D(s3<>uS`0Qe$bkg}j>D6e~LP(kG7eQEyxg6pn5xe|aEXHl5`1=M$J zD+0qG0sxtRyz00cK)L72qboU;0ao+hW3czD;T#PT)lvX(hCpD5Kw!erd)7PH@1e3H zM>S=7R^3AYz`Fm~T8sKrvqKPV5ddJ{6#dYJn9}i9ty4e<=WW=wz>{i$_EaSb0^Aoc z{4=)j8vh7se1?-FOn7GyF4g-^wR_&Lp3M)dqk6x3)(8M}AXjz(xL^P`t&P;Dx@Fo3 z#_E(`iGJe=8ol=j`OXdxs`D>?S)D`Nj|Sl00S^E0`aeHAG_!cCMli6$&H+E3ombzyKSi)J zu6nZ>I|N|*56=75>(lC&>{ETj+K&PAkwO6bR)=kWOpDpqdTf_rD~wwa2Iw}h%m}jn zh52_X6e2$N;1Darth9x~C?E_rUwD-56f%o2K;hJTe9*r}XAma-T%Ev_zQaM~H|$dL zuU`CEoegmIhmdNf7Lh&2N5A0C7YckhXV;pA`;ar8O}`#jo#*(2fC1^bKbL$0MOZrf zb7vbVly(=j(|2{8xB`@rdI>Ao(L!i~K=2fC;E#J%?|bY=PP^4E0)Q8bqw34~v+CJ| ztwW(FbQ&rgC9JI51)%*=Z~}r7+Sopsvb5qHD~nSY{vY>Gs=s*oJ@^3uz%H6uoV;~k z5RajX4q$^&$o5=5VS9PdOMH{QtJ${Ko>&Xm?P~k&djsQ1t$rAna$K-&U|7RAURWBi zV0V`J@C?DaTeyNTv8Y>25tb3Br{Cck0OsFw1OozDJ@}fXU4O`~RS5HXGW!YvkXXz3 zAHYtS*3?J%%a9g6d45mFGG^Qc5Tziyd7M#E{mr=4td9Ud!9Z~b*ec6Cef#FuSR$gl zl6;fMERd3ICugF-AzeYs!=913(^4Q7JE3j^s>}6?vXFA2ln2Vo-x`_gaRl z=RcL7*B`}^>E%g>HmJ1IcU9W^1Q3JicEsgpgnzp^UOE)0;TIvmLgLL?RjF1GbC3oC zwUH_7GK^h%&ApyjCfD@11Aqg2rsq!t05bk+|2;1o8rI zsLk7fIN8Ta<`AMo9{`$&7lyDff@>@5&-{=Cz68G}z3Nsa`u!X6o)K!A@h(@Co+ zZZiB>5Ab`8Sik_ANh~ZstWuMTOWU7lfiigrhep|cz4|KvFq&5TkB%P!fMNgyIK(jm zfH%F9>MwV{um0u1x7GW-voQOgq2&(~<1b-Izh-iBry9V3wHq)5fWdR%0LC?({YkMk z)JX~fmK4gz_D(1*c-S>0Rt-3E*POu!9B~R(IKe5U0sw^S&#kOsHS_VOD@h5I@DTQ19og!p;dvIF4M=N_W7*^fb_7CfZJ+>`moP|gDQ13P+ zw&?3E{yLj#`>nfLpxyTXRZI=B1b`uj@+iiJLj()bF5{z%Q_dbfITi@a^b$B{5}LbH z09)e0hebub;i=&)-y&;sCJ4FZs=I#sKq=aKBtHdAHz~e}}98geZ>| zPjgH@j%1`iv?kuyZv0I9o+lNaq5$BhI{B{aUd!tOPewQidqH;L%iWThMI_d}IqS7J{w^=41Uogh)-)04X$lXePpm7sR_p|FV3=_`giA zi3C6L>nnTAAuf?Gsjs$G=F8&@YHeX;>@Rfq2T@I=qMw? z%Vm)Gu})mG?j0?i5H42(*71*7+J%;XtRpxGP&gl!0buga+UH}|qaLFLMPh(F!L0(5 zL1Nb`ZY*qn>h%=?XuMt+T4yOIK0~0?=C|Z*f7>k}Ec#aj0R=A6VbQ`xBYjRvVSwAw z;lm$u+fg|Bdygf+I~Y>e{j2fUQh0!dUoF3;#%0Yv-A6}skjr$?RGSx$#01|2;XJkr z^)u3CJn=w7nus$@cVu$(0pPlSVsCMm(yhE4%MaMDwnr#QCDb$6u*7A^j#*}8;%}4q zCq#KPt7ilIBB!#P&V2aR7c|#=_O{@&cU`~jxsAKIUKnzq8)f*7i-={QhotY8nrw8o zy$}R535j~@6hmI(*|k-6r9`n!FEX}AMF--N^>+au-G*%otf>WnZ-+;~IzliRet1BR z5WK7v*SS|OoB);yU-nN{u>8ir;^BD1nhN~$KI8C}z?bz`>!-$VMtNt9`#C0*IsvR% zD_yI#aa$%eED8w&3H-cot^aPy>{`$a5NP7LKv^QPz;z%ocL%V8_aG*BsT)k1cyCI- z4!9q;0IV@*-8gH>=PVhRscieUL;=XmIY|}Cs-2BCI{o%YrY zBK8mlp#2-d^t-j+5EJ!t(ltv})I`_2^dY9k-F?PlXs2may1&=fR6CE|cQXcX@!s~_ zNV*H|*g;U(M|0UD4orvWNP%Hmi4@FXtCWIWv|7nq?Qi*-u&oeAF-$pzFe{w^HqQTa z0H|QFgZl39@_oewiMr73&#A_j8SCB1|EZ}UJ zXglr8_J zyZDx4tv|$k520Cj^9BdB*}P3|1POcDRt>JzWNTXOGJp{^n4lt^b=d)+k9Ln(vHf2N z0Q#`FO9xAjal~6@qTFBz07z@m5PnY(0O;ochk>pmt+6Fvuvm4*mT}`3Q#73eEI<&E z=nDluFmRjI8(?Bg-?OQpTgqbzvfzjVsLA^<>2}wE!qzDq!1S9xeFtQoW$~}DfRw2@ z&zAK*!`0tHUdE+MKY9P9%y{R0VCa~Q1J@UfU%pa?PSM<7e7D>yjFmsHJuc=f#8{RDmm&&M9@oSzCG za*yxuz62W2+rX3N|NoX3ZVv^flw=j{KgOy-kvG6CfM0^G+uw9wSKM`^>;!;@2*Pg? zJ^*kCMp_AA8`AIVo2!2hT_sYKAl95J_FUzhI>qb`@e%?6_B}_u8H5d04Qqf$TH)0< z>GlhcvjrT$4)PqxXzo}78=C*U*t?sFoxQvdVE&KUhUjp@`fogVyN9=bMVluvUr2g} z$;JlRF&QwKeod>3gEcg(Q1m14z!VFB8m6}n=9uX%oc=-a=MsQ>B&62XNOp+jmTSSJ zIgnW_dxAjh!`0|WN~tp1TI|X30j+CemBM7e)kf3FV8ejbexI=)}0L3CevP^BTza^(I@dbjCIi$cbp+@lo zx~{@kGLU(+MK43&<+Hn5T*%0~b0Cx<;g!p*{zXn<_I2pFx z(`%ZT>&0J9{#(}gPSNnkHhu^ITz~$4=L|Fd({M;P;d}}cFgnCG;0r7*Uci{5=??(_ z)+*u9PtE@>t%ndGw)+Eoqubk>>bsiYW3E|g1%^b1R0zkzY?(Q;53KC5Tab?a#1ndr zFzqpWz4TYMy9H>cJzs6eKC^!m3fh0-1|0#~KMR1li<7@(%w*2Au6Q&CL91=P?b|=L z1qAb;KbseD9)dfK&G0XwpFg>3HUI!3!EZ{`a74N2y@j_Ge_#o~x}LIZ0O#Ce^ov>o zD5dhfVFd;c8{Yu$-*a%>$moxulg}B=1p|Zo(7I0*1V}8eGcX7FMX_&D;x`{hp&xmk zTIjpOpK$sAAj+%#KG9do!x@sV`_PJ&;*@9G>5_AIe*2z{PCo?!K)Zq4o!d_5JvZgG zujO@*$^7T&OACO%nGf80gvqaGZVjT>f48(KGi;oPO8TcE`PO&;j0@6)GWZji;vp0H zkF$et1bEKGK4g%;!I94yjDYvZKRmji_!V>Cu=a6Xm6F0KZ9hDy<`XdQdx)u1x>7Oi&YyK%4WkVbysmD0PPjMLx=Vs zq$REvxwE@L9{7KM^DS$- z%dP=k^4wOiHyT#QfAP<&-WW$|TvIUMR)L3DQhvF3QGH#%2!>ycuuT6xN4JkuFrf3u z6a<)3Xkg5R145Iq<((IPCJM>vulHVv1}^eT%@Y3}}1D-x+^s@%fvwwtT#cXaDDC)%Rb%twwtY zqz0Pw^G0^0m>+T1GXyI*`HMUnb;^4G@iBcu{ytr~i@%B*VqdTf(|@(onyDxCL0Q!z z>Y+RaXKdu-}R>5NCh%*!T2~eKp4V;{6WJ|JZJE`eIb={T_>5 zSYFZD2hOAe4uQoN;5scXlDfO;1KYf93*68GWo&}euq;tnhuKwteT@LGeugj=l)S({ zOR>arjDZWz->^FXUO?V{#~9N=wM;h70Y|@J6~J%Un)iEP`G{9xxvtRKx$4#L;m`i7 zGIzO4z&!I>jH@(fu(&v5D7(4!ryI0oDc1aP@`A?Kv>~` zWq}0%ez2m+t!ijGvibA)X(ib{y={SqZ2{r9G2vzQ4B?hqyd4~O?c=%o#rZ)s7$N{* z%b(cx55i-QEkOHP0E87lQo$F@*TYum_ODCw%d*L&;X(~&tVA|fioL%l`T)RVevQZc z3eW$+G)p{T6>y2Gy8RQIcO_;ike5>0pgx--YV9QMb5H4@Hko@gBV~>m_YbPY0iqHZ ze3^d*1fA&^;m~(e93UBAC|QjdVEIVfDE!szwEo(VxxaDZ7CSATIQuTSumE^l*lZzQhN$+>U`(H zXUm_rS-uMaKw%d1y5&}5tNHh)6lH2;7(mq-NsO=y1@b=$7 zt-jlTQ=RYQ>~EjR25^%(=-|D-`hp`~{lkGD8o`BKb;uw+#y3&&X}5r2oQYz=K5Ozj`k_%nGU~UsXMq_%o zJ^Xzx{jbEPA(>iA@agEW=G^H;hAi`&?B&6H3+2&ZIzwK|^GAJjo_~rVJ1*;%=N@m1 z-YZ~uJ&&1w<3$*Ir)amExIOrUK_)+$eVJ3!A_Rl?v_UE|SNG$mT+<^-=DHu5e$x!A zKm=?K|5|=`6ydJI3|i>0=Ao@ zgovKJCE|Bo^Uu2PJp=%1VF#cwx9{2k56FzAj@2>LmiBLAdz9)Gt!!c7ipF+~np7uj z_%}qOiiSn4zfrBZ0sxPNirB_A%GWm zIJauN=d{l?+QTO4FgNx3FteQ@{O2h!faL)1lhv2Scbmv#*glzjb>a#Dcnb1$5_v+6 z=LL@3O@eZ9j=Nb>{>ps&K7Y$RRPOLD!PeZ8<`AI)>pcC$W0oM<{~`=f<6o=;yk1}m z!}0i&=~sy1b<-|2(b7bL(|b}O0N_`q^IZ>9e}n+T0nYv)+{1%E@~0h?c|AP(tJ%ju zg%eucqjD+p1j~luj|w*3xvZ>>vdR#REb<^Wcq3?(26yNmB)9t8MNpW69^t^g&VFBI z5r6vK_MF8RQj1kbc>mY@U-MzLhPE>?WPlvQqJq9yk_|uok?kGZ7P!^|SK%knGt4vp z;9kd78NeF-x-4ss5Ws0jWT&Zp2yGYmt6Sh8klkE(s9bbB`m(UA+7WZg z@hG;-{HsSUMfJ^ZH^bF)?|by&u?qm~l%E@}cKA)_zB2*F>$(2_S0DN@fjG#Gh9DD` zBs&UBwc+YR-}rI&`K6GpF{s1aXB-bJn3?U#dcyI_mMSCWdoBC9ZJ} zVpAxvzUF_lO}j1lBWnRsi_uxViF)zw;p}gKRm|=jrr*80A>P&GUXbuf$Y*^S9~&GB z7R6K>;(kJf(WemA#zOov+-DFC3#cr&&WnYv|BXMOTQQsQ&;KbO0#m0sYau8T&y)58}41Zpz-L!8{5*TwAJ z=9|IEs<|HlO)`ZdRE_Mr;9VIpi{$Lr<6JSbcN>Ga49N58!ajB(@a$8((KIlY#!;Ejp&Nnl1Tvu46k^hLb;^rH@LwLef7x~smp@7Q* z7O?!T+U3Z*&bgxS$?fIFdiEy{X*)gopZ8f>5ez3aN87AVuddo>)}d3$qJbveaos;! z=rBQVb>FgXR%}f{@Q4WB(13&{2^`X8-V7lCeJ0K*xWjEj@9vW|6+1qYeINZyzbu6S zrWFE!7dpUpiPQ~nwau69Zac5Bt=HK$+i$I?1%3ivgfYiDD5FH~7yh~k06I9P>>!kK zTGA4rgM-kHYf|TK4+!EQFW^xh03p0(K#IrjIrv5~u9|+ZetbhgK%Z#7e8GiSwtWBo zOL0*t-!1d+WTZ1fN%&H4ue9UEGq;iz>+R{$R&`xLG)#GhIA>eo|1pt5j>VwzL1AG!-rO4aSd}rHhPknMmzA`JDB`9BX zi>D6eKA8O@WgIcUOpjrPwFYpY=kuRjkcW6dn=m#V#J->nLWOK`+m#{|uy7(f?kNou zr{-P?*@%}iw9LZlPa#ll+TQ92e+RHyjM z8L}3Bgi4Pc<*OME`=)yc30O1hwv$LrVvTuBIZitv2%s(;)%Nqqk^!~4QL$yEI5%89 zFS)Dxr9s3WRH!Ti2yLZl>H_|VB|`MA{h3kmVdOmDnx_ss$P4=C^ z`%8t(Gnu~gp~rMl)c91wHAtXhnU@`ZTV0)w4S8RCdbZQuTEg(3m&0AZ+%B+6Y(QYC ziMhNBfUjF49Puev9I^@M)T+>PgK|glL>J_JDKM@ z6bOugm!WXPcg#cl5$3UPaH9Jjg8Y$8zkfSxxt`57?((c>h-0?-Bq_{bRei z(DYMYU^B`s^Qqat1vfrqC_^g9<2k~^`GmHal8H0G1?dhJL<(%|U$y@k6#&T+tiK8t z*sppt*w6O5LLMDA;$)3}iRBtN{u$xd!mR++$i~hJ3S>y91%NQL4ciu2Nei@LOY|$; zx%&k8K@et0F;_#Cf>XPA@a@#^7;oTbz4>H!qfVXM|gS z=d1Yk#rMs+A_Vx`-1Lu#@@(Gdi;VU{rb))RFTW||$MgA%50<;Vel_o=_iTKg{r*%! zc3Rfw>bd#m-4wl+0FuYNk3~9wo}Too>d(FLt`Jiaz&f8|Fvz-|1p`_EfP+Y3zyhhB zT8Rs3*IjS>@M{*X9r9dho*w^yged#}p;p`t;FPFEfP#P@Ak-8N6iHwE4UZu03?7TB zENe3!-2$wOH&v{E>iQ4JX4YT4L&EB=4D`$FZ8e*pRXsdk*GgXlg8&o|exka7f=5vG zZ4tLEAn2;~*L(NuH4M%O90TDFm}bHo(Q{a1p$c}%cUpx8}*}(GWZHU#EYUv38(>_sqy8nq5L2;XKI)@f*(7~ z5B;wSgRWLzcDRda`?No=UhlzF9lQtC!jQu(!((Gzf^Z3Lxr?JonRR2R(xEE5c)+IH zh~)WsDNX3uxsn=%Q(Ut+e4?a>-e2yGJoC{&D~RX}eJ|&{rwjEN5#I*Ah}=VcT~BMA z_h8G>_%09%`4|5T5}k1c{iwj#05@3gKC2e{>=tqKD}+UG@iA}UuV7E-iO1Fa_yto3 z_rWph$ag-Q&}1*G$p}yLle3u9t3HJLE#qX_V&hw;e_$;J;Ng6Wg+_A zhR*55;ig<>>D509^gus05q&W`#q!~M+U_lF2QFa+NOd^GX9K&4yc{1_U(a8FKim(( z1s@0mz#PSjNcgf+>k3IVm2V0bYX0@h;C>+gU-i3S{)d=VyY1o`{qq{QtzW`e;ESPu zh>*&*M+l>DhS;`^^KIC+z`eGBLp|pi#+b>@5i>0)c?ThD;6CzoP(Aqpy!uz8YX0qC zRoyf2kGOM}Z3Mtg^J5&X9v&cEL?FQzpJ(i1rmfEoxYd!@Ls+qcK&^{VI7i}rwOe3ptsf+6czbCysT1ZGB&s#n zB0B%X`knISjsoro%Xav$;jjKK?eB}^-SD{L3nN-h(;jVx%)ff%(z3-(d)@bCxO$%X zkM8)C1OVCic1}CwxyN=)V8}e5$#fpQN3zAhC}a-2GZYw+!FQC0_TNQy%(8_bX(U+z zdw0I*-Y!}qnR^8RV;KH0|L3TLPwAh6fQG)hw{NchMRr#P({`H{0ASp(0D#%2{_1VQ zkE83XtaQeFgsg4Yw!oun0S37i09p)&CvT5h0KlB}VeHEGU0MK0xED|E7n`)T$IfQe zT-;T}0L2-bI8$lI<{xiH!p@ZH_1CVyj^&HLZLV-Yd{^z2>DoXiB!i*;#qD%d0 zh$E9youLMW$m$~mkn@v9QbUSadq+Vj%O}*lXcS;`>Bwr17xmczYuyjQpfKP;*xE6A zwr*f7@F=f~qm2HD4|0^zr^~`JMMc(pMnC#q^NB$SQ=A3w3Uw6UjXd!(&&68wpq|S) zq@Uy-UtD_90CBC{yBA-velmJzAa+>_pS|E}HEaV2?7c5az17Oo zTs0p17ZB_9b9R!joq(g*%6EpzKU-2Q5J0INml*BzA&Pfr)y@Iz@IK2JSP~Ex08mx2 z*F07!9%HS43IO=bvK*!#Fa(*>w9f*~zx7f8&><>F)Q5-`0PYrI6nBU>Hpc=$5n=Jw zpanp2)TpyYgf*OpJpe)>3LkwHOEE+P^iK!^9=QD7x3qEO3E;|O_J0yHd zpY(uOEC5^rP@=Z8QqP5_rjRQMrBq=pO^HHD3Zq{vsco37ZyqTG$iLiosSPCh<<+zR zkasif4eiM3rE{CW7w0{tFy%bc`AqxVyhj}#vjE^yueW-ko!?HkZdoR?!_5!~jD|d# zKJka}N9AzWZ~2@=Qkbj+MI<%j0A^B!^6?IbQ-Qa;-u3gYB~+FYl((B#hA#9N16u(= zL>OQN0tx_1iGJR z7DytV*%}asfY%QI(R4TgWUTjL?qvRR$9Bp1A^_OjS~?u5Nes_S%ht*4$uFuXIcF#j ziRTV=2&@{-o}TX)M7Tt-I2SV{Bbnz<{b+qJO=FyfnG=nr1_{&mn3rIhi#;m39+=c( zp3kkcb0}Iso$hBpK|K^&Yns)iQ?cAc)QaFq20Ivf4ho>c?_lJYPb~P9!i32#?3&Bs zRP^v3nSJ{+cVg*)R}})dm37V5fSox)0S4uT`FrzV2mnlfT9Ed)EE%-~EV2NKuL~TWJ4Kid3jhYe z-_RW8r$W34hzx*?feN^K9ze^OkG!9H%g0|2NQH{>7++=J=xx;T6!o-5e%=zN2QAX{=Aw zE`3dbK#*llR>HQh?Dv`w766oW3U2QcyY#h14<7))#MC7KX!gSbz~}NkRw~mTDLd;I zh!EFmhE7WWcbAx8Kr}QIM4U2^(a;_l%v1m zhM58&Dxwd7F^vC=icCWo1O~D1gy$wMfqbpy-hS+}YJnTZcVvl+nh^LkGJ#JKB0_+` zQ;pSdk<1ln&u8xI=v!q)M2GU+hB-((n0|2B!pJDk=y(hNEP>xBbUsub{p8I1+xG}GERys>_rLUbEwmw)bTR)2ZZbcP1&+!!-;i*1?QNf!0TU3f zZUg`^hzs*y267n%pqfi`mXEBeM4wopk9eH!bEa1SAn~RahyBm7WhA;MHN+Z-P8v?l zQ~CgqxK#oh+JS_CkNEobk!=gCwFSgbL<#oT{TB284r>d$5b<5sX=??bH+8pQD~!K{ zyyUxon;gm{ulB(O0Iv0oG=zSbd~4>9GrJn|-lE-OjEA7lK`jp0tLP`gHzB?3AVbX3JO!c)a+ zpecjr4;7YmYgN;-m{06z&A@!<+W!uw|2tDO{`hxr3sG^$awi8mz5Es2VY96>l;VmP zN`(q;XskbA_T82-1ONzTX2c2pE9O{*xb0erl$Jto(Zf1>ZTqcg0YFyTJlO(4SjJY@ zVr9E(a19sZx=2yv#ApMfU2nh@4?IRoluHMImQ9pw=z>hk$SddT`gOd@JB1?E2D1L1 zJC-fc_4fELxZ@uZ<=rfP-r+GZKFLTs>zLoZ$Fx<=Bgv;3gtDg)vh%Vod4Bci^~}q( z=Lr;f%skhT2zZ|VEz_4m8Lh3X7&@FgQ2cX*17E~4aJVi-QchaW-A~fuXsi=^-t)@X z#sg}|eVZpt@*}E|QK)xW0A$P)3v`vtzr@-u%YXL70p!8_Vw4wxM$%!1bz-^ zsfKO1+yYJzQk~jcUgc44!RD9QK1i( z2}rfdxeOk83K%-ByT=^A5Qoh>Iq`c-+)gDH6msE`5$fl?5lqPZ%k;C}pN0KI<`JD! z&B)uM5(clUrBj86zkvl_Hs)gl%`nb24me{M0JZ33>1rSPd^w)?vpW?^dE?^4V0Yd?#q}N#m3%w1WXA20j z;yag16;KXKJ^i25n*297Dp-vg+{0QV+;DOPc$WwnU=0L(e?VJCQt6TgC4;tI``?Q= zb7=x&ML|Tt_omkyLUGDh%gDF=EU81+!Ayt(@pCcf|1Ehof>-3>+I|3h$OiQ2^>$;L zj<+@WdA)t)QiS%snfK_9PelNb4d3p}%*&(KGA0nT?`Nb%XkQBf0J+D_wM&N}O_1|$0 zKUA%ZJ3Rpt+hkSjl_Z00O&i-KkPrzPk_7noV zgV}TYzcJpC7ti;?X`Ab|gHe0-CFA}X4FKU3`+cJImmeGyTUx52cBndH0kHsYv)t)yr#w<-n-u8UdmdtEP<(v z{-(TkIWDYs4*90$`kQG3%f8~vT5cc%8k~YJUQ@vDIA_;|ozYJ9e0EqJogP$&lRpIgUY@?{QjLJ>$M(oHp(Q*T4+E zA4?zD{=o5N_*hFdwjcRSTflicgq-0(ltutNb<|rSY^&KGbuq`mXe>DM6Vjg$r2Bc{@(r&0pE1Jq{Xar!Fk;LPz?E*Jy5qP5pR>;nca$fW z53VTTm@kN*wiEw?hr|C0gICHWmY=!gj}lpri<`30g1@R;`p{FhP2_iM;_WUx$A({1|GevsxN+xGbaQAQwTOWqt1}J{$({e`4$JO5CoXMc2Lo% zt=eV1XKd9Zkznt)hj?_}BX6T^@gIE)6axMNHe=mC1iXfB-R}?pyasGp^|piNZf7>A zcBc^TC;Qcl*-`bfJ`ToTP*#JNTL5k67n|7k%*kqTqRss;hsTq?LUyEj4PzJ@a z2F^9tpPWKOzJ=iZfp04Z@%>iLC1ZOK-p5~XgxS}s#ES|6rU(VJnwV+MKp94FiHFDo zURU*xM@%p8tIipEavUb^P`(ZV=Kd?@mk^*(Zp%Wj9-lkaPz5L3h7{~AmBenuOo6nKC&Oo_r|HtUt%EM>s6Y4{Wt~n+I|}=+hd(6ipAi)RSX5`Oc9A_78=BY7=k!|ex`i>c(bvO4Jiz* z8uJnOP+@>fZBU|3z7~^ct;2?26KQ8dV$u8qFOj~eisq_5ay8tPCt}U@{>%H#(}KWn zdh{F^)+GVT^dgY83<7C8dcO>QM!G$`?%VxCb8IcVDXa_J zpaZ}eOEIPh^CzzTC-!1_hf6&yD)o!l6x*_{zvzB-8$Qz(aJ(%eV~*)8=uoYsV#zLJ ztq$v5@lAX`co9C9&{QDGE0f1Hj z%U6+Zqp@2a<*pLE&W9qj(@j>q_pa-C-^Lz+v?m?1gFRl2R=hpJuBN??E+WEz(i|@i z0S-;yJF+9dW}~feVl}7awtp=|7O8pUo(@ao;=tt_v3&>9I*)TB`R)!DJA}2qSxVQ+ zc9+jJ z_PA|po60O16XF|K!Zg#eoV%djZ`*bZ2LrG?#>69kkenv`k| zm&!I%s=qs!QFmhhH}1d6Tmx3g_(!ukOE%%>qQrPUANFYRWcGb0$Cx)$h~<)l0Zy+hx-{6Ieg(#n7U7OMyWxJjm7swTjIH1%<*S8%ahwhT;*VV1Aw{|-JS z)O(eeH`0gTjJe5qLqR|YkbN(3#v!;$+Y>9BvfPCAx(k;IP!J>+S~Jvh=Nfhypshm? z;CefsHQJ`u-SoPG-!sa1D90eJ@WnaL9RLR43jKxbFb}$X$ZbQ@S4i>yUj&GyxT~UK zZf}fI{2~Y}qCma>H-AjxGaUd9untfFz_ADX2p@Cd!9KLljTzS2_W8~2@oBe!KzdV% zaR)qtUR-kIF~;E-rk`S?kfQWKd0xQRSHt`K&`3!3^DKLGL# zSlY}rXTxJh#rtC z=^7KKpc)|};EjS9(#i;D!a*Pf%CIg#g?MHgwk`0GEg;4TRO3{|Nv0KGmHoQ=anz&t zKCrzDGctg%=p*Qo*)P~3j}KXs5Bs**Q>}jy06^4-0AR{-hZKZA6)IK$j&r85s}=ws z_L--9mjJSyo2aH~g`qA1konh}y=&PKtwg%-4$zpZ!!QTKPqU^UfB>EqwUlt3A=5GA zQV6%!)5;?le<>9ie;oY9_I!PaX9NT?{Gl+Tyo(@Gxz91-OVJ8^2M4+XZjtY25T1iAZ$~jv?-kijE3J4_BbsE@%aNlA10GjBUZ?VQA z-VuTTzv-h|A`qe+R5V`|nXCG-*by037OU|C5XuVDJ#dCwg$^*$(Ai)52+3VTN{P$w zs*3p2?=AF{762{)&>BeGpdWy_{fe1F*Qjp_rh2V{!wm>sx=Q%{>2h!H`0QGMv9?6L zrWte6mcjgE_OGlpgm5g?TOdTNar#&H!5zB@5M5^D5+wbPgg`(Ag#aLE zZYoiVKGS(5>srWodI4c!o}rN2OE6tNzp8}8VS(mP=YMMbXH4u$^2&A|cQwzdO7uYQ4dx$2 zsxJUL3#|YRLgPR{j*g&#Sz9$>y(Yv@7Z2irphswGCiLB;Arcc3^nk5aOv3FmYQhKV zx$S3fY5@nfF*J+K(Q^n1O?G=||Bt5oRgd+9di37Isn9dl?H|MKOyQ6@RV_Q#`vDV_|4PGM@Mb?{%|=!SO7416G_M0 zKF1&0F{seep26_S^h$k>v5FkyF;YJOv}!m4+&KvbIcQC&0?p$io$LPXp6sG~ZBEO{ z3oWbvrk#fUxc$3FpDGcEbMo-_P#^AAiv#-nkn0KsVESsc{4n~i&+p=BD+C!b{_Jm8 zyC$5q;qG)GSsM-qS>MWnTx10A`6faDG~PT+e8zk*WF93iqTgQ@jBnToa+T!4_}6Ia zIuP&mF1}{=5T-!s*SmP0*ZX|ulxD{l5Od1noOfF-8B;!${s>mnrWEg{AXy>~K^Wnj z=g}%_Ep!l0{&e$)Ab`Ik$ewbh-4F$jf+hfXjE=hLD=W$KYf@TeR}g>Q0e~Gr*j{3W z)P4aB^z>DMfM^Hpzvr|oGdw~YYL^lwS1L0TU;bMDig&;;iBZ1+D4vD-c9D;rQD{y!KV#*G;Mxf zvkCIt^i9F*w_UsG{*BFh>H+{e>ZXt#?6pj{kLITU;8&isLxDZ|pIJ1R{b2Z+R2}(x z2X1Wav=mqulsGUQxDy8L7!BYIqF*O~BhDvi!6&FmiUe=HQoMG%ttB0VB1m*!$DahX zUG@oHjjQRfnw|U-A;4>#H6h=eoq}6&EV74_lamviM?oa+paGiEk12SCSkpp4C=o!m zVcP-^(gLCzc(=tlI7M?}K(qrP(LKX~C632_J$zN|;_+VxUVAwIJ3_1Q_2NbK3Srki zV_*OOEP9EeD-3Y<+axi7c(RQv-QH^miT?)2o!_v%!CS-tx&nNUsqZ_8{1b@$>Ha}A zKfqxUI|2leG=M2o7@%hMa~1$NL521j?#{GPvw!ekH3sLM{Epe}2Y7#kptNcCU;^Uc z<qyQJvglg880szwYg8b~@HWKyRj3}c=PDA|$Dd z@iVm3?Yx`v+t=Ia*2oG#@Z6XV0RP>*Igc@M19Y(zz{y==3n(n!{}loVltor1Y_2-^ zjS?Nah2bv(05oMG0Kn6z+VAGRRhQ>M-*4w=4lDwdV6$%&&`dD1nxNUKUO@ms;GJQf zIcD1?82;{bR?W_4)y^5(qX7Z{7_1=HB-m)Q@PM6A@}QO5e*Cj-0pKt+ckH9SP;&>0 z>5=Z9>$Q8Q`fBvNIvO2R`y)JhBLFynaQ^}_{@I)qroF`jKmlSI|GN<6L$qe-G(@23LC8-DT@9_}M))!F!BzwIy<^5>Cb#yqi|Ttl655 zQlp{qFLP6v{%iI>f$=^4p4shNm_N2drF}aPRti45J+^pa7l01TQ(6FM`4r1gZO;2> z(u*!GlU7r_n4C--oqjc|-=$xVe@UN0rU27!!&mPgR`ttYR&!!?gz!iI4+wcX_%rB? z-r(6D%Z3?N4b-XEJt1Q4z!ry9pELpv)mgDVe@uFcmuvPQR3PST4Hpl-M{vA&!{cs6 z05LAdE^H}OV%b3)Lxs=%I}+>6|N96ej((2;$+J5z(MF^B?<+t+Q$2ajC;2{30Ym$b za7FN}*|mT{8R0&fwY=$;U)tO$Fz^TESb#S|M}aWFodEV&^RLJMS8T1Y7nT46SpU5c z0_-;Ie=Z}sq}o_xtVJ-{#lES2F*N7*c$uRj%`d9!j|aCcEhs@@@(Mb_W5ntw!j0mfM`Tw zLi1hs5+<#;@k)>8%@TlT)5GduwpZ=3uFx&J!i*P!z8LY!=ENZ2A&=|9OMK`9Lzbr; z%ldyzd?EOU%Vhw=>b!GUox@m7noj--AwM z{-Yl5{1O&4GXx#n!-KK9E2c)ji=e3k!`^{v*MVOMPJ-ZOBCwz#3{W!6%@XRd42A6| zCEooQW$nb$0KWx+k7s=y@FIZ^0f1Xq!Mj2(l=)>HaB90+vrt%s**`f7xoHDdMIggq z*$~G62k8F~NbSWDL1HWj&{~M{FJru{InVU!kJdrTO5=Y8gY7t@5{n($7c{Wrc96|d z00miHEm|MUbp^Aywn5x4_uwHk+i^)r^F z?th6O8yvEW5K$Z>ZrLL(&U1O2d8-bVoo~o1upumC4Fw|OUY1`h;L_rB1i0#=#QPby z$zx^1hIKU;i#vdV(}GsNd5p`u{Uf5hoOfg+n$9QMX|k7yF7s^?(;lB(0Lq?JxUEyK zR?_?0z|c;64T?f?JHmg}9G3?tl$cC~i5T%{0h(hO{i-nvyhu8&3vwi$ino8Aca%XK z{s16A9JrrNu!ENCrkd7weK3pz7?r*vEm6r*i5e$Dfv^#l1m&5`zK>=6Y#MG`(T!{Y z;BZM;fR)0$P~Jshm0SJc#d{aVXAgKj!1;lki1z6VoH)CD~>vN{~qcQoB*_ZMRYc%Gg#_NBl zu>tSI6bJLK1%M9ghzbB=!6)qt*p!f9vr2F&0C0hCW3I9vWw623GW9@oEbnlAf?Be^ z+J7VYUK5x1kci3Aiu)NP`jMz1Ve9!msa@(fpuV1anQJiR(LNIDPTA33JRg=5##~qoA*Qdj9MWP{ZNClxlYR{)Rs!&)udVcinIQNFmk^6ZJxWFB zSL~*$udFbBOwKHDFZj9;>ZN_aovQN!u{pNA_xc$Bb8`PjqBqLZ(df&&d~-h0PLq9O zXn&>M44Hr9Lz|vygFNPt9e7(EZo1yiGo799F#|Sx!kt`Vg=p@2NS(+9(OQ5p&wa76 z4Jp^(a{oCB0UW>)86=rrcRB9AX7}|*dPM{)@pdUTJ?3E>wk@!6EdXXgYj{Dt;|UvW zUT7B}==)641Ey(L?3N?j0Fu7Y`fpr?qCkl+J<6^b#hPnoK_D5vLI_+V<8o6_t50*yCLQPuia1J}i)@4@Up zw#v(yaD64c`%BTCt-cMyxWU_K^NTq?=W56_TTob_K)|{y2v8*qJ6m%MPutX8^?QsX zOj{QUN%RMxRgFRbZS&oekg!hFoj3Z`)Ff0+MMaCZio;QwLDRw!C_gwRT-y*jS+7%;Li75JD+Z=c!V7Km}{ zxH52bOgpYz^IzliFXm?RVE*fg_y9bFqraM^OyYw|&;L5A7H27~5|0E;3hX9r8ZTeZ zPlF;F!!ha*{DWG5MQ`Oi?^#!gLeo#<76mKZO$Y%fi^2#yfEf3PsIG@E3PJI`iTLkP+{?nI$>94%l%(lo*uQE98dLn$?qN3)y|PZ0PrB*)WZrOQD+|4-E{F?e~7_+Gc^Z7mf0ri>mjzu zf_P5m9EX>hw&Mn#Hjol$PL$D~eL)kvB@K?(QUJ|=JqF@NW3+Q<>UH|cb2a0q#xwUq z?HodYAO|GGWhC2k$+9iHMzkCQGI=Xl;L&C0kO97ev;Yuy==e_yA_a*L z@BYtrDAbhrA$9`ccLe*N%Y)AG12EYEA)@{7?6Oi=kf000eFNRG4civD_ZAT4ifcS( zbc;Vs{bwg={L|aN!T@&SnVqxyRP_>vp}z_tK!s&crPu#w_@+B}3GBLl1;BMaTjD$M zi8ydw!Ed4cCr-eBBbGFY`T{XI_cjVe?MM8w@^@m5w;s4AH2#628Waxaam} zVx3s^Em5A1hK|DL-5xU?Z{$3Wc`aT~zQ=a(K1%Yq!&4CeWG`f=d7d4c*KRuI^k8S^ zv!=rWfa4$D^ibr*j7tAA(d(U3(R!Gu1mWR1@M2t3@Jr&O34=n<|6`s1kv@m$854Ev zvA)u*snWN8hOS)pev^(<5s?I2Ejgl52JhrQ-dFX8N|jem}>F9TOG{~!jabtoS13Cs}8TM={2n#z~%vP z)C;Tx<_xXgIDU2YRaa-2bDzL4y*}ElzCV0keaBk=H|()Kd-kfDy?9xjA0JgSb^%y~ z=YPhsA(%DLcW6&GufC;__xyWxo(X0aX6Tgl{cpa(@R9ZYGb{lx{qHQ^!HE7?^%$5lq-(n{ z>&7XXIwu7MOMcS^Na0euF{F+y56@J`(3bj^aaVu|OAf|ZsZ4%g%`Z;A*aEPl!%i$M z76=|XgAqc25gRQ)J5bJGR;@0tTE3q1dkYM-kP8V0XE4+68FS!|xlKXd4m$ztyK~55 zzdC07Q1ONf0K_Aj{)#&u8h?ltT=)MLMcxn9yYLI5FksA*j<>y2oPr|BI6wg4_J0S! zjRFARxQjDDw_IGd>%BGV_C=p-3j|q@kT10TlKKk#_+Jb$lRv{!?c3dI^8Fyz{A>P? zR0_kQudCV4A64^Le}d4j@%Aqbdhh}t0AJzH1YKha0Rs1la|GfB|E!_0osZ>cbpSZz zyQgs8TH+xljyd{({IUxG#p1p;it^dj1ll>Y{_Zd-A?^+WXrbpV#tU z%|#4)k-Rl%39yjyR|wz?+oa8t09j`!P5^P-!60=2yX~Khzd`^l0dxlFJ%PN|S+Ixt zR?PTxXZEO?8e=+c3hfbuA6l3Styf3ppFO3+3P8s};@yn-j)$tt_Pd{V3ozYiWF*l( z9kT!RDIT%01gOUd1GETWE5Lo6{~az4*u`A`-Gy-XC?T&8fK3g`?_rA|GUkx;nDmA% z09yc}@jpW&eR43U-aS98-tP9RH+}HzF-#p!lVtwqm`>K3Pdb(}IPO0;YCn*ALzAfe zm!Um}@pr4gv$s%mS^=Q-@3GZs?`_pTK83Gki#)vkci09sn11-^F51&@nkKlkLFOUw zpM5BUor2pC-pY^@?Qgex)O=Q=*}-AGg@rxp?zzO_IgI>}d*8oCMgaZCc6V-r7y^S4 z%)eVn40$e>O3b+*fs6#|@M1E2uFod8aII0w}nO5qh< z+|~2H?W#4O!YteIzS{CW`eXZ!$K3*sO^3TyL!g^jJ|qe{M|+O9|Eb>ozuRY=vF;z? zn*Ko+c=TU9|0Q$RZxAwKiLUv-$|x;|6k00G)K8W8%@8olv*MUF1*;{4U$zfNdB}PA z$YOp$tX7SKkMN!>&@w^Bss>n;3Y4y00^a~Jy0F>yU$D%pn|#*opZ{wV?tdpHPiKQh z>$VDQ9*8?aUh^c=?TVJWF8_L8-qTKBzH0-|8fe?Vl6`!UveVjcFs~hA+HEr0=>(3n z0Qe8v54F=W|4i3(yZzn}9080?n%uHfp#9Y9(>m(VgJ(Hn{@CO?Wps zh&_!G_+@>sDTsZR0E7cT1aqU^K{bM?KOZnw_c7t#mGQ^?A721)g zF6VMfC^>1h^_cjF0Kg`Rr4a1!g2t`G9`}0UuW))70)X&_57WrnT-M2PjdwT~%!mli zqahR+C)1zDc2h@VagX0s_z=4l_%4`xodPlv7h{A2BjOO4ML5tyP_P(}C;|d`wTFJU z`CKsl(i5>R;L?Xa{e;&_;)Y8Is;xVO+K2$4Ls{GjK!#t_e`CQPGXK<%5X5(+9_A+n zg|7S8{9opONNS1|g;oGF1co&N!wL&Nw*U;jNzH%LwhvS4?N^^{3oy)MsCtxjlz^UkmYn4e$;Gz6cpT&dRM|1&iIdsqtX69+Q<;tg$Tv8P{Z+&Gc{FTVdh9(+xwCd7b&!ZE_^A>6L>)}5p>mL%6r}K`y zvmiHfcq1`|0G@k~Z_SX;wDa=Xqdfv~k2Yk7WCgCCXa3b=`#u4{^LAufTmr(MU47W| zcmY37O7RO2w$lY}7%JY#E$e`oQj!o!FeZ?ZH8HjRjkv<%Z$lDu*N!wz8xk_TZLw_& zJah|)N1X4Nq9RIc5V6sV=r(6Y33sEWyBGfd1>{W*1%GP#FY}*&Q8k#-8A5;=Rys4a zc`*G!I9+AVHo1ChEnArh0!ZA(PILHJ0>H5==f}oQ;V~VNu-pH+eVR;@N^cqIm=S5` z2M3vU0Zg~f}a2gN6@b{Rt>k&=HugWy{W5@0QKD4PsW6nxANj-TK14 zBz=4#aeq*nwU!%J8@G2D$Oa-47nb68Z|!5}+N;(+OaLKpqP$KX|dX z1$e40kYg#2&drSwpvJ1^U$gga%Z)V4VqOCT2=Fwgf7WU5z1EVpEp0n&Nf8cTDs-dp zbLtiR6!wk7*A6?pwIxgI@E>P}X9DQ<_hog0O$<1k13>~LYNlA#)s60|tgNietgI}} z|7(w}!5UY3(`cd+r-dN!>+#&3x zPece!5y&NM-gpiG>=mow=+_He!VV z=3;QgiRKsV=|95)0Dl0xSHo)W5~p26SMY|cf)0!e3V?M6giTiPpYqSuJso>#18^A@ z0GLs;EvIn>#npdI)WhUE%>LJhVR|t5-araqp++b?Ln73=+U@-bEBzDp`%m9N$8ZAJ zXWu*K{#757|Do{=3jkLB_59CDX_)*2%Ax>}Mj9WiMW6nV^;i}cf0gwWnGAU?0oTmd z6}AJ8475DF^=mRiIf|u9tA`mxUnPlVxJT^A-Sc=s?mIWk6-_)B%z3^%zEs{h|89FP z6aoNMJoQ~+fkFR_@DDILWq}_Hf$0gl7@k*f#R?#VR(^ud>aU+`vK~}zo;4#of^x%C za0jr!y)zaFNO#Y1^fwt)L!1B(IR=2g zRseLw4b`9&BB?~?^O{?6&+CV4vR{3m048pHkkl`RWgWQKx$P7YKh5VYV{>4Hr6&Ny zojE#y6JfU(Gc32-)N^%`S(`swUb?Ekun>IR^E(~9dhsl&dCS!3`Hb<&hwf0F=WRDJ z_m9dH3J;GHgXyYK0MwJB0MHy%Z`e9#GRS8;{GS2jqP^Qcj|>5E_Ijfot90NVbDoTP zBg27;(x?L902AiD3(R(tfrn|&^Sg^8z!ki8#a*ZGvg+@O-UY13d93Zh=u>HY99B~p zrFuxa;iFtYDaR&ZHW`O}uW!q!=?cP}nDK6qLYq_fuU~--n*6JHo{-n!-xNoG?3V7a z=O3hDn!3Qklo;CpKqizadP&C<9n2_cD|l|cz$8wzAq4SO0iYnRRH#s{(j=Tmau3|n zabLi1%$$Ie$!ecxcfhf^8+qT!Z&Nwa`9ypv%4HqwA7XsBW&CCOQOE>8Fr=?WJl8*= z3JBL+`U@4#p#Z=q0H-pRLXvL^zQ^DP$h*sJ2kV0YtCHw~LiY99QPZNv&=A`D#%-w3V=U&b7^qG=0?M+ON~ik%~4C{RSlXp z;Tc46oM~(kWtP71%L}ve<(E#EWpJLc7x);5KIiO5^fZ8Tw00-#Y1AR$Mq}!ifGB|@ zP%2vTlN)tB$g{=J4a|g4{(Ddmdsyf zejBzBSOEmUSy%j(?aH7gW#4lDv|kh&Q`ln~bTT47G>ojq4m5V9QC&mqY0gi?r9z$wJK+OLzp_urSj{+hQ>+2^mYfAxQ{ zr~ChAW&bBu`SJG8im6WMcJ?OK?(1_bQSlN3_{w?dye}N4k**au#o3HGP2Yycl!x}B zbKhgO_PPEQQ@M0sWr=VTma#R0d0XX)bGK1^+DGqygyG){qRhHw5qOWQb{{e8)XPr> z-0T=aI3@%?UvuP_ikVl;H#i-vk-Y1{Un@=;#E~b*5?)}9fyCcKcn#;XykiGzG!-(@ zFXe4t_SY&98+{zK`3eE0$G+s<_dC`2``xPlC%%Cdz~R|`bvWCrUY{LSFFB^{<@B(6 zfg@2Vi1ed)0>}*kUsjE;ecCF+L177`M-Vpy6$RljRxIyOUj6CSPt|`Ke;=OzPr~y* z@O#UzUI9anSM1T{JH$krP^^4yWwyV2z7TNuh>Xx&SNvmtzw}o!%vhS8z*Fn(|1Y~$ z&0c>OkDC4qb`rg=CZm5*&3^p{@+cDf%vB2fSO7Fy7fD;R2nf0Y;Rp)=2E1v|ug3$q z&4mh9XK2#i(bg#zR0@a(2>l$ETJ5(di)m4;BEV4oUT5alarYblL&nKQf|OHgW#ZkoAY%hi7v#2zNH zJFeC+LTZ>P_eyTV76Pk=fan@~+nkAIK43U-bd5mQtH!68{D0W12JcwohXGLm@Txwj zUNr~RK1Y}BvCnyrrE-jUW0nf-J-K!8;=K%RwzZi5yZVneZ~h*mkaH`*NpH*wAE%g% z7@KHis-o;diCYZL%|9RKO%pE%gZ6Ftu8^#0%LIR2X}1J;Vvb*JXc-&R5Bb@x`DsVyo< z_d~NL3<03t`sM0l4&YkYicbptdggYI?nh3!e1G=?yvj?N;jSV|hF|4_^UTX%7iF_2 zF@W2S?OFY2RtnJqVB*r}y2o*seXY=5Ge=XcFe>Efd0VpoE&H6%HmBeTuVHnvkAO0` zz{LNAEky6|eSiY-;A{`(96P9OFRIlS5L0n4X<{5|8;iuZe`)h`FfCLDAH6=CvIi740)7w% z0-msk;1whe2LKI6C(VKP_^sI1;3-33K8VX$b+B3#e;B|!m<?+qX-zH2q5t2tUx$A>`)feRhNF0^U4;F;Q~-dGDg@)`zoaeeJ9oKVctUh)fEq^L zYkdO*$)c=FroNt9@uJTNzF#iEg}E}grI9QhScxEZcfRD`^2C22D%;sCdT<^Ju`8G6 zZQ^Yqo9c%@6-t#q^~9RovwxpL$d0+IEk2jeX2)llDN8DItJs?!Jj;MB!hg}5eeo-w*bnGp8N6i9WYpaM33Jw*v(H!t&10ej zB1yyMry%-w4fiJorEPQ800PW)p?I372yPzNg%V&FCSFE<7ti9T0$A_Y>%XFZ`I|>~ ziNq4Mbq~@{_4|1YpeuiR_MWm7T4S2tsI*h)4<$e{P>kJ8XxzO5e}NE%01Gc84O94c zm043soTF9jkM6UM<62IS>plvAA{-&sAq@9$t{7(LvO^ix1)kR9Q+3JvpL)hNh0<3> z8=UcozV3t^94zp3t`0`h9}tutRUCwt!vA)p7AHDl?3w%!-wJ6Y!NFPgp9cai7)&MF1q#^zrDEzZUFisMoHc3BH z{Qulf-sf|{Q_%qb#WnyMF{2R^PO!M*_{z&2_x*E7nca#r$DwpW7z<3}Hf$kq9}viK z4USUha& z=c<3M{4cAr&wnMQT=u#fWktxRNE$66Q}CxFip7EXmSlSS#xHMN{4ed5g1<7Jk7o2% zc1E|%@=pby_46AYHdO&2@IMun-S2j8=DVryV^gKL#xihC_C63gK2@;LYP-Hm)ttnxsF-OuUxMQe+ML3DM7L=vF_01Sw0^GW!-fTs9U z6vx}!u!X=^K>&OU#S^#~^~SLt?P)G^|Xe< z^hRF*Is&|8&EW!vUso{vo|x9aEH#c-g|ZOND2!!3$@CKsB7jn2n5)CP#AZ~=bSyVv z)gNz=y@rJi%={JnUG48<0nlf4G>-YxmkE|kv3(LbIK2Ja1?wC{kAfo0Ynk^y^~~~L zE-!UXxG_QA1AyWc{0W5uxT_b>InKhq<`_54xrY2F+r7N@*QE&;-|4$dozvXD<~9Im zho1hm7}Be^rvB0osmWuk_Fq@Ln@g%tR{f<7ssptIXrKow<#o^-K0p!vB?(l&fVTUZ zZGH=ZFNHvtp0r~r#*a?_(62U%j*O`ptNjh9XEZ1l8&~#6SQw#5t40X>TKt5insb%o z-nmLT(8e2b=a*J+wa<6RN3guIz6R40Q|vY^dGDL^`ntr@`w4Tf@dbJyUfNR;ka==I zHozM_G94!YNEMaw=(O^)g_O&Ax%qDJGo=FE((C+P_phH^qnzY(lfyC&(2g(! zUbJaG*S!}Hb)NGXxT**u$lW2)A@NZrqFZ+N8@~F9{ERO!?*I+;78ARBb=>=3_Wye# z0LKCX4za)cJ1(D5pzEb3YH76_ltY4hXxw1kjNq%$P`&0Ost7ByTztZd9BNY7zC|vQ^?EebKrKdRh^SD1j zg?NVoC64`*t^w1KMV}z(KE{M>q&S!P_Nln!PuyznIY&guw7vYI#NQGHvWlxvFoU-< zCDpVvL#d^!ZB`QJY=e_{PSRgHZ24WI?+~}Hxuw8&LO=SP0I-Yo&;bsDr6C>{dZh0V zXvjW(LsTNV@-G{I4JY$oTM>Tx6~V7b7jy!sUl0XRU{DMHfBVbn0F8f4_>b};vk+)V{w@QGTds&Y=K&ni~1R63PofEaq8k=_W zTt?FcN8ZbPVu;Te1d&vGBg3XE021igd3kM`W!Zswo%fcNhXnu+a&jolHVg(Q0BG*z@l1B>9IMQByVv(`!xjSH z0s-+!JcD_kT|i&1pe3Qz1G%6~d+Z&4gV+BTFdXjv*J0NIe_sY0UsM3e!e=$s2`x+W zT+wsPF}%nr{GTKIzr)M-Uw2NcKleYdQI9je@rHh~yH_2LP!Npqw5$_1z5lDgbJ=h1 z2OwMe1k#`kUxVkx*#FOpA{u%ee9|@}c~bSeN+#`C@YFn^qBw>---^kK=gTb}t$yPc%Q#`28bV|2!~P9hAyFUj)1qI~cU-j3NCghcCJW^ZR;uDwOP?*ZW_ zmj#7?J^i0BFyABif8bp3)7g-zQw4z50BY@u6~MCJKm9Vg+a&_cv$ThmOS13u-U^gv zoC46i=lG+a7!vI1+JV7nSasbwAZ?kc=+G{pmSI=-{x-jbz!yNEkP-ysOH_%cq)b&| z1%Nd`55?5c`F{1A>Fesd=4Ds`r~pVMfQTS5?0??*i4y=||KXc1$9s7FW;k*J!1Ms`$uL?)ICC5$Sg8nDQ)Vim|7EFj z2vMP5Vq@OD{TDd)dynw{{XbUKFMo-$UX63Vonz?KU$HvNehTl!A z;hQOfQSmU}3+9v8f)0IFPH)V9UslNne46$L(OpbSJ3hZ6ws*-m2qpdJzvc6v^n2i_ zt9}XquKa7YffKvtf^))Ig`aT@pF1}^Y&(veh1;$f_fAU+@m~`HO8imipPez%c(+Q0 z!8t2*tYYq;kE`EYzJ`Xpsm3#`hj2*fHlnxHD-?;U6mbR!qkog3UIMqTsoZD&#$^;0 zgPsUdRDtaEXMX;Ga`1GQV;f)A)!;4L7gWrT5JDgWJBQ_{-nmiGXMSt@*cJkF2xv7E z3Nr@~|J~z{-gWi?;s39A!2i#9{Qn7@gC`7c|KqpS^v&N_^_%~ps`vkfLDri7%U^~S z0LO{C*rcL5LQ4~Z4n6Fcnz!+ejPyhDqvbFg$mR=N6KGiv+2R-(;sRQB$^M%OL`IPZ zh;ZTzN6KPd4`lB6!dKjO4kXlJ6(X{@SI?Oiv~V{JTQ;8S{%VwL|~ir(P5q+Uw&m%z zs9;N8eCkDCaW7w+4e>g0-@N8K4qi?Ei|0{->A^Y*^*fX|DLmi10`tikIT)__t0Hy#!nqbr-pg0B9ngxZ)Zt(#S zX8)}oP~m?Ywh;JQ2#9qN+Tj!C=8Vs@rcoI`J1Yu+@b-^0m2mdAi(-0=$NwR#|0-Ek z0C+@g5MYS#4a5w>kY8HcRFX7@2YKa(Z~{o`y&zTc%Lw6${e5UlA*80=Uvl}4A*`u+ zM^5wUU|nT{Un<)IuJ3>1bN|4-|Ba}O*R62o^QT_l74E;GcYSe1_cuiW@Hw3#i0*nW z@0)g`zjc;Q3xNOGg1bW^d!QnZchkFneV$RSlIeQGk?`jMvLQIR?pnR>|5x-7sdYGDTzw*=}a6O1a?h7Lo25=~$ zNc$)NhFJIL#493#e{tb;y>7SuD4C6vTKZ2W0!E)bHdn+;kNQF?^2o0#&g&S8=;j== zWtqYe|FJQ(*AQL($Mb)WW75LBA20v?AuFVD zL|Ur=NN}w?l3b%m*7#%cjZ4UuF81dG;j(Ao1VeE>tLQPmV=B@Nc#)5DER`m{LQ_kEjjXQCGa(9Y597V zap!KbrA+r9h{||U3&VATuHTUN$`c>|^*5alfBZmO^1095`hthJu_+3GPr>5ut}nmN zDZ;DnZ_FFTaksq~{(VXA_#0@zpO6sMixG1Z-)G^-9q<3dZHIt(Xcf9KXclGHgSO@FVQhzxoCC?6k+XmkY z1iAw=2Qq`Vm?J__ph$hG5)6D#Pu?i1T*)hJyKeu=Kd0g{9p6i>R`QY}?w8~KY-+6P zLA_?|m!84N&oGyqv4W!BttPEuq&xyJ6acvdu#%ds$xDMC0h#bV1^v-VDe_8k*mdc! zlU z7=!I&1>u7GcbtUp495@tpJtaVoMD32)C%+n`a^g`d~3z=e(B^-q8m|7R3fIFVQ`0c z*JTr)5JqjxtkMpx&Ek@=E%)B+MObz}U~LSGsb$^gyq?Q+a#O}nz1XJN#Jhs;$dBLk z>{{O6Lpq*$Wa=~KH4V|E#JuJrw}#NL)9{BVb zT#IwSBBtN^qHnlSM>UIH%>0a5Q3o9p@@f9>RsgX$w*utg{f5tO{!epNM#z}gv{;R; zN4V_a#dYsH${7~B7$J`6TaMGJr)Ow>F+@CPhDaLkxx>r{qE5&rV$C*eA@D5_V1S1H z5K_{dL0#|zP`i&;hk)p<`}n5VW#wUn!>+RbU*rEB)*-qcyuYOatNU$N_}8_URMI2= zJnrv;RlUpcsJhxe;+S+ye-UzLM{lax!Ath};+unW>*I{?V6d#CgDvCg>inQ@4&fh~ z=MwXp`{VJy*J$Sd9zp+SssP16I=|)h2ln!x;{)In-ju!m=q>v?_`@+;584!t z{uGclmM(Sqs>PXW@%lk~>dQVB^9`NQO?ksdYX)?E>VLlM1D&S@i|=8Y(ut^aqh|kq z_!QA#1b;WX_yyWSpxMJ|*_3cE?NU2=7ZsvcK+Jb_ecrbfo_1OS}?7K;G(;>T>h zI?Cajp=5krx!h1XO`bvtsBG7O@I`q%5c6I-5Nu2Sf#>olKqggKs1kgAH@3x5mibJx zk&BpAs#xB$crSmumgy!c01}Yd8JT9esbv`xYw~{g`FzGS6ab`&82S81X$X9Fv!_g=i0vK|f!H2`$nXS4>Q5X60|D|FQ566(*wB1C zICc}*&)cwtz~@4sGY~u3ARP(@vELA<@6%t%>n+@si1S`Ggc;eJjH| zubkz*E-d`VKyae=pU(fT5dKdQ{X+r3e*Y5`0H-L@&i41KvsZ6P52|y#*w;s|tNO*S zs>wb|0M1%&G_91uir_dle*CS?Eddi;@z(*M`~2PWZyx1i@9I6~+dpG@`aR_8FOV>l z0Uq}UecC-dtA;NxtHF_00DwpZ05q!4QE6rGKdGc{-C^ZGxDl!F{MvlyIvTUi4YF>; zU;x@Qlviy>*cR{4+t;?8?G zP?@L~k+cN(raFA%j|+{MR>y2_`2`%;8Q>*OK~MVU9ME%yb5Lvp#t=ysWc&NT6OzzV z5ug$Pcn8S8u@2jxKWzvoFvi%knV?cQ%{<4~#0M17e`V1}Yfnx7ail%NS>~jETg~?W z058a~e>IHX$bJ7P0bcwLMF5LNW3C5kq`*hVxpS3_;@T5k0dRLHWGWXEcbLJEHIO$3 z3^v7bfe9Bq2kG5!{IVzPFC=$9KxY|ZmBfxiEr5kwgQC0^{)Vb2~cGR1kR2v>UQ4)9$^E$ZxU&;5Go;8Ae0q?@E1ER@=ac{&Wb96S&a0 z`mdW^xb$X*QmIt{$n1)wMQioxcYW#I(8AFySNzq+IRMqfIUp~I$CP~_zH1c#Vyu3E zJaX9Kvxvc8`u&Z5KCnPSVWtfd?jg%(hksKwuR(zw9J*YcW9h{z+wiQKjlQoY9KqGh zU`=4mbHzdCgDtjk#ItA?Om@C=n{FZS6%dGd&DFaTR>6NHe$RRsD|pQ%%n4*>_P7Y8 zw=b$=j`%u}f7&~QxnkAj1?Mbt1YqMT%Ul7FRql-AEZWpmrc~)|LPwu{K=3Ce_GSqC zv!AM+>7SrC|Cts4|F`PZ2>&}A0SMU|zGf%tTRfw`gh^8PM-VcUebVGN0Yp!BQUds{ z1g5~BtAh54ld(~r)tJ{`3X4wv`crvey_a9TW8eI75o(4g1TZ40b~s7o@M5oeJv*vi zKs}D|{V)AELfgW%{sDaBXg{6&aYSu(@GJO6EJjC^h0yOC!9#^r$NCdOM#1Ky`)HU17NG=Y5u%M51<3iRW4?sBEY3pR!(d(x*}$ zkC4v@iYF5`O#x8)^<(faD_<~Q~x@UP(&0VTM7f> z&7ZsdRo`&O75%muFc{`DIu6Q!Ew8_>Q7Qk1k3Nl`UK0d*p6*w$&}H@j!mctvhD`#F zX|hZGdTWlZ)s%w&L1)yebQK9t12WrIJT?SCD-kSoi5e6k2O3ekS3Udy?BED+N9{Y4 zo96$ho`Q*QDZyjc{*&KVG3q~s|FZv|RZ7O3C z5UVS;@+k*tik(lCxzPeZPE^t4HA|x_vLi|wbF}kD+a%eAIm^(tvfI+HYEjY;P{-9xW2^w+T%-68NoRm% z|G$0!q$B=&>`=f`{DipgUyC8r3H~o8i~&#Q!H}1^ny8-(xi_!*zXsKRZ18Qr|1}U0 z>0-<ik9<`+epI{G(Y}ykuhZq)Xk7E)%v#e z;RC(HN6TNcaSS{DL8M{c@t*#>7PbNWjvId_D(hKssfQsuEE|()xm)g+*JjD`vV7O# zv)8{`v)raB0B!@{VuyY1bNM?{_k|e#Sdvft z(7gRp$-_3rfgkb`ki4H0;=mCe_3)9PGN5?>f0+LK=C33|-+v7O$BbjdU<$%Dj1T#{`U)j93itX7zcZ|MH}HiG4ksF& z0EXi~kNd+!O^Y<0M$0#bxz)NRr{F3806+jqL_t)HplH=f{)DoUH>c9_noKeHyjbZN z?7rN5#_L)XO{z_&QBZ0vLV)I_Q|$Odq$t>-=@PUyA@Wxe6Q-c7YcA{gK4* z5l~NuC=+3_alqEY>`A66OvGfeT+MM3=>nRfZP-HKP6&uI9o+GhD?N1&W;*+0rJrjT zf`{PU7{^_^FeI-2dlGS$dv+9uoJK9`JkAop#r z%IBO@xSR)yKMGxVdeduO6*Odua!{oqE1A3Ghs1%AcRPPw@Axm*e&0_l`;4z%O~_4> z*9}qSUNiSjcUb*L=$}VUyO`hru;HlCIGx86dRp{&go>{Q9NV|99s;1voW_WD&au*) zDfAUOtFSL#g^<6au&;MjEJGFalm6t2zcf0=`Rc3vxL-)hP*P=%kUeO7$rsY|7_*-R}@3joiH{5XW2 zUbh(37x_9NKVq@@h1;DczdoDz?iUnAwK<4ENM44i_ymBc@t`rE|ET(3UxlalOBrs3 z|6K_E6caB!xdvQiM)uhgHiFKp=|vGRK#U2!KuKj<3lS31OF|dJmfYSJJyQrcHo={S ztt2rvMW1%nPDXtPCq%AD7>BGz9L@HtF%F3a2tuyg84DBdOqQyE^;HDeJlJ=H{TYN- z!(Kgo*W~eC!tk47&Rcurp9;8PJ08OVfU%gu(^E&4m_YcW5+slV1i@>22*32QLb1%M zx=E3y4{o4IX$d{~TS(BOgDvZosTDF$l$N^ZRzDX-p+Orx`GQ@VGUdfGtI*!UlmnYk zj0CVAy=hA;VAX72;4N)1A7<(b{?09|Du%CNRuvfm4R-CNyMY6fc6NPC;5@HoiD57Ay2$a{A6C+g#4^{D01tm&u4N03&RMIPy|`7*$6%L|r3o^H%*K zsvmXT{@FMPfMhY>;^Z%APRzg3ANb~pEB-9@u+rbKy`zigqjx=N#gtyig5mmeE{tL5siT*8fB_q^xH? zAImh$yzZ7+p270`c$RHs>TI;`VOb|+S*Et3oA0*C^6tIvb>?NGm^vf;+cxba*He^* z=>)K5rY@*=J&BbM<%HIG#l2-qmBRsGEAW@2IWVJTQ0g2oQiR&6#EBq}P?Jwy;ohq9 z6ka5Z)ac@EJUFjC_IYutLsOr!^8Wz_3iHFCUvvC6t`;X#3x>xOU44?-9?!v+sYETpa`TF%sWfWZbpM+QMA8_#H+1{r}E2q8P z>Sr7)o$elS3?R<_4q&!M2z+h<*wxFOt1nDbEiGHWw%u2a>`4V)+KSV|3f~9S6dwr8 zObth%)#qb;%|fS60fk{ z+WRvOrEtO(-nV7WXOyAnm|nt^V|Lrfd^ad&RnQ8XFuzp_T-N}w#aCDQ?N3*$9pL(z zVKuSozo7ZwF?QiY<1ATxI&eRZo8{QY8f8e2?Pm(}F`w|7Gx-l6<>f(KA2j1?A1Wf{(1B>#4A6c1YV$w?K1G^< z9}r@4QXchpGB~e(Iy$L-7`?B4-Z`#L@O#m`=BZb8b-B;UJY(i!7is~g@ChY=Fj{Su zw{PEY2*h~7B4*~v7;)U6GzWne;eUFLv%krA;MU*ahXw^5V+JpioDTI}RUiIy$j@)# z5pnn@Eeh)_#1M`xQ-k07majhD-%89i#Z>S&Z|dILs}okG_N&>|X*D^1S@lj? zk~+PBf16c}N3SCoil0W0U}=gIK+Li2(F=`T|RUG1~zU{;>qmZ?~a{|Ldy+u&HJ5e;ua) zc)S;DddRYz3eex0AL&+8Pahihtx%q(3s0Dd5H` zlgAt(G@|aQuaI(1>1Rz=b$CQ{g||j%mJf2Cnp>qU&WvjSGa2yU*Q^Wq*lWvK^^*?> zfq1NUrA zdPxz-JtBHn4V{SjgTj10ftkKSELH&kjDmS(C@`IO8QJLTfTgUgeebiJTfT#mXn2kS z;2j?Rf5DRIrvXR)jjPw3W&Uz;pJ{XJ$$z1po^WM*}_!_UvhsqOoUFUn>k%y!nV;HY7OcsvqV#PFs z;3Vm7bDwG=W2rTg$`9?F5dxi>8qRKS=L?>%Fb#)c;5cjV zRS!#-27v;&G*|(|QC9UC^nk5DTA(qlgf@rY>D;k&aK6kJ`cwXe0)P~FVmTkmp#kRq zd#6x|W8#M)qRbd20G2}tHhY*kk6_-7*cZinibnvmH{TyOSM*18C<=h$6GRn&?YYFk z<@wH4bviz;j`z>154)$;@!$+=JCqw7`**-mmqSmy044#KhpY06AhCVzLqQ+Q;#ROrW@!6=PllFMT-PaJZFQiswq@T5#}+h^`OEDmq4Z6?_k#dWY)atgHMh25 z3xTB&5Qo|rD}Fcu^QgaF_Ueuz4%x$t5&&^uQ(g7$uGr(@zFF=YNphn9dY>?fY>0Cmv)>d|0=}CD0eroL?*sJf_}Z&rf?8 z&DW8v28a%X>`zmhDZIL&3%|_stkxe%L&D)7%7k$K*D4F$`|mM;5nC!!Uc2lg-4CuN zUz%0uLjJ93L?cbW7l4icjT0OIx-Yx&m{5lTxFD!vXso7c+qXVN2#9df8zaiHIlW&=84j*wQ;b9M%9qOsox0msdLTBbk#p3kMpe| zDO*4qEdX4NlMWlxDrDnugGP$qwn6_ETDwRIv~<{I)t?bxW92aeE+Ng+ug)d*qp*p2 zMYIssMgTh29;XhS~j~k>6{ww?cwG1ko08|Dd_#^yR zIQ#1jX+Ksj;eZ{Gg#m?C7pJ#j3xV4p;MgGCphGRqX*gjgJpNyCZMjSh>S3#!?eykrw0u_lNkCta?!dP@B*Q7OG-p z=H2yimnq}@OjHTbr6&1gH#PsMrrmb`wsKy#USX3I0JlLdJM6amS?+WBY|emroeF^8 ztTnrFaj0){u@hW-Bys}gW>Fkkco{7PSDO)i!oCWr(p>i+n~ z_Rj`GK=f#tc9{_OLdSLhy`j607p6oDfH6#b?$zB3b%5-9S^Hn#))zWhm<9i;AA_lf z*}viluXD`WPhjj%86zhM|ChTc0!&o^3}D7&wj6T`MaGbT97#`nGzI+uF(PfJr)ah? z5FRk4dZpfd1G3;84{!4B6Gx@Ot|jQv6%f`h04u2R3Sg?A0F?=G9X;^?e_GrQ66oi+ zj+HjZWsUy=h5i&)YrOo|>{p-FhwP$qe>~U0Y#-o=>n*}RZ5`>Gg;ls6=x@+s@;XRN zI{g4my0=f*5n8smjbV?uWD466N-z3zpgX)#C;;^9ppqv9U{Ik(2=3XR{B%AFgtM?^ z?qPU^Vg<7rwgD9Sv4=_XnC(KN*4f`4?;eNIe^CIG*=hbZUee8Txx!GYuK1sd!D~MN zDgb8Ci5eP#n*wApY6^|0Mnq(>P<)YnP@G;NEVi#+5d=gs#?V{|z*JNm{y}4~-kjn1 zFMN<-*{QjIJrBhC!v%oaAj2O@QvNFFN5E#N7tw2pO3_#AOQOMHoYw{2M80?=aIjq5@841b z_RAvdPgoY1A`)bN5()r^!Zv&v1V9HFN_g%0%A1;BJ&})Dg*wFht3Z`m8^UZKp2LVU zk?5U!0=MRY?fksQ_5c|*9yDVlqD zUrhI_H;p_0*|!Vxt^&Zlylw(08vxc9j)k%J$UjVXsirG@XRPX-Ah7;Cs;mEk40ps9$|J7*$t$tiYv=sIhX7TlH{kPOC>5$VhkaPZFb-Z#V ze1t%}_jh=shHn|_Jnnr}k1i3M-?L);Q#C!sX(`U*dRNRAEWc7I9XkvQ}gVudC+O-yqb|jw@J?26b5foO%3v93uWu;R=8i zEFH}fS^c*U`zXjNEjnV30<#1^*YU zavJy0B8U=2jp*n!h#cl007>FYa!U&T9tC>Yx&$qD0LQ@LbO2s+x=!x}o{jdPhju@p z!Z2iO1pxfE;nNTZI)s8Ir=b`O2jXWk1Zxz;)#zHa>=$o}udQ~-Df;<~i*AOG5?pHOfvc*-F=FjL!V zXJ@e7YaK!u{zXa3Uy-Mnn1Ee!H46Lw!%OFY2pl+2Zz-Af#m!EBGkg?CIKiB1Ur z%okoYC;`NWr6gse0ky6Cy+A-(fq>-d|LhdAS3RJUAK(nFVOrY7@!#QWuX@GNe>(nC z0pJz@6#zQ!T4yT&(Ow#5D;i zaWJed_r?f)Fki+Tld&Sqz*;hs-%DSt(@Sh)NbgR|?PP)gr$3T7j%xpp;fJI`>DbgC z5D-sL0Q{MSWKJhJ#+@RH$o>V)kU}EA@4Ip;K_Vtu^Ug{_>G+rqWxT`G-!i7i8G`AI z;|nkU%)Ipra}+YKt8i{>s0S~r$&3FMf&bTq@zzT|bhp9jRDZB&=9NdeaEnBL;p*~vem06-}M++1+zqX6hLmkbVx zIKh*@2tI>anGYIr&Im)1D9qIh_0M3)FNW2d*^BBW$`wx!k#-zHJ6_Ex$m6OIMGI$7 z=|gb_dI2}?!JsG!Q2?Bw0H_a90N{5`=YIpN0Q!4Gl!f8_U;N&HuK#xA*}mbcAW#sj zSRP4>Q~*eaI3{y;t^$A~XW##tYpjkqYPH%$!P@^FIQcskcYe!2V*W8oi?t<>t)E%} zJYS@9jop)3rpOr+CYVbXKLrPbXrkp7_XYcdg^;_Hy{JcMoTDn#q9`MpxZl?3X21P6 zZ5>qrI6HPb)$0sdo@tgpsdN(+0Lwb0+i}Y}$lv7eGWEGEPi@c*1;DjH&mEb7CV4Wz6jqFt;yx><3W$XcJs)*v1emJxz}@CVeG zJ2QiR#1;S)(!;3=#8LHvv&>&Lhe10yKZN!FF?kOUO$oY-7u|gOos}iDhkq&w75WwZ zFM?V?BcKyH{j0GQ(h}R#ANwi*+Sr;ew79Uc3T|J#$q+ zHNDUR00kuDj%9zggCK#__DN09p3` z#})vt^Zq@3@{_NTcFey>M;GgCY?|h>S*jz-lM9qBWjtlRwu9%N%SRW>=MQu;vSCS) zv)JDWij4{Dt^mjm`4)h7-;sIK%-dm3uZDkBlAC{1_)o2pY2-!2P=kpJ-B;fH{rz7h z`kQv6U&?0P|5u;o8#P6C-=<7yL}n7NLs`JRmdTx`4@n81Wru8jqXR|w6HJN%l2K-! z<0KmtNIhbo?L9k2{%N$U1F!V`|FE>?>)`Fw+x@2^KzjgB%)G*Z-DO1Htus4K2pwl3 z?6<;Qem0mc?mef_Wi(?IN(L1AlU7M89kpO|ITV2|oRQ-EE$~TZm)jwHCoM94h|v9> z`Ia`$@tYO6hFGh=(9s=c?G2Vy4g1t<)Lcd4Q|gn}a;@ScqV%`Js&wJ=5be6pZ;0o% zMXLs3#9Y$!U_Xc|lpFhzOHZSftB}1&Yl;A`e>$Pi4W5yH1ibx0Kj?)tL&c%7H~=h$ z|EpS@=v3=7vqcG@kB}Sxuo$xOZhg2BmB9qcHf$kq7X)Ik@K8&GB8}sk8DE@+(bUjQ zj>K$cj6+gZba*&vEY~jnL|{CH!jW_v03-B!Nqkt)*cYWg3Xjq4N>ThT|K+iOD@0Zn4nMuv?E!Ieop6q}cEgV74+)>VI2+uXMt z&L1T_YdhqhTSq=(dzaw=WmwM@A)nQ{9ry5Jy6Y<6@EnGn6^h{%Cjiti?(El%7)pSf zrvF_6_J}Q9_;gOkg|XMfSHa&EzBu-e73$dzV+NB-1-~ksdm-p)WfNlx4u2aKARrAQ z#(q=;VppeJjheBnj`J$_tJX83TLr>C93c-9B|gnu6$Z@u0xWciSMw_ONX~g9vh&c* z&kGkaiPP~;=biR`D6hCyz&|TOei2GB9X;EjK14TikD#5pw6{G&SKcs(*TJgo3e$dt z{+8aFCLLa=#%5j$cO$He_^wo0i}TO<*|SzN&)*b<{Xs- zpg>qxXknpJh3IvUmChaM2XQxq|7#^cQ33GGBLlD~1l=a&>i-q-a-P4ETIk?X4i8-I zp(NCwMfe4I^qN01;I^N?8v^Z^iLFSE3wblfPHdIY_XwjRXpUYc_4=<*k&*O=@))0Y zf8tp^ku<)QFXGZXu*zFSQ~4NFg&GtAsHE0tJ}E8jrIhikI@EF=vht=G=QrCjuk+r# z>6A&S)Iw}rU^>~DkR5beg|lPwxlFsycgyTFuOSiQOiVY<${P{Hz7YOtLe~mlBPzc! zl>|Lp>5r`dpa!Oz?z3%R-t@v99132S$+TpFG_=f760Pha+{QF}ThaT6Ku#B?DgeNn zK2C`S2unTo{)YnK6a(D}5hq?lyc5rr0Kvp-39xP}csIdx-9!}tvta3E^e^GQE|E&F zkVL0L#*rq_1Ef?vdz;r3+CAOdm6n?T^-2Pg0;58*@KSi330Zv6AS}-C715g_G=d*B zr$_V#roI0H1*`K}W zwMqf-e8!&i`Vw>7{%cITaqy?|lzLW!eH>teYU599}cdvWELQj4Xl<*-JNcuI7u9_KhPYZKRoAnzqMbT5EL^OJ+fJy*1 z=~hGFJ8X{vbp5|50#qWp{vQ=-zwz)1O`=(1FDHZ0ZiW9dqWSaQCA0#SA#iCp4IuH> zArSF#tN!r7+J5niArSJQN;9|BT|y@n{)xpmiO%a-`PaF#Rz~>R3E^M*qar#?{ZlmX z(_c#@zqs0K{(~ayD{I`e0B|gK6af#^iX!v-WqL@ZO&cQ5W%zE3nqA*(9~mm^@tgv? z3IK_(9iHK%A8;efx~XLBw%~K0x_{g69=zNccGE(3!fo~Te)pMfe(^Wn(*nQ%2f6_P z&0A>Oz}Xmhu0pe-QU+mr&u6yb8zBG;gHeOoc0X8X6`>QB^+6dtQ`ZP-dX^0gf+5p% zJM;p%_jcP4-`EFFv?e+Yje|haX7KOa6$J zU3~z^xa-VoogDz$Td-U(_A{9JN%aA?UK@Z5nE4Mh^JGANk8$(LBi?v;%ve&WJz($U zo?hUYi*swuyz8GiEeqkFX<8+T`^HtEC=4p_PxlbG5t~kb2|CoPPZ5&NFiui%dQbiX zr&(QcG6^06PzngzFsXi7=oHBG%H{Wm@O+Wy`}De&fx-~yHa9(5QF|3H>dx`G=|N-5ONDJnMv zqUXm-7;uQ#;ElW<{0{x`?-?<)yE(4qIHDIB2GN!h*^(LQ^rW&W5w?nbO_m_I39nv zIz~^l-JzggA&ZKi|=yrO(&e`v_;4`1Pf7|aK zt$b4y0Nsx00_(PNpUHdOw42XoQUUNOMCg8VE%IT0uHe5I=gnS=YHn^NoB%XC)KppX zFfnJY9mY#>kA15%9Lhj@9Pv&#n%eg8a_&mlW|4u-?WVP_c_4?pKAASp0vC2itp2M2 z_-R!2|AHjO@o1p{z;V~n)qZt!Ns54X#Qta%0J7}v+E#P!xb!aM z;`8oNcXds{Gxn@|)SoNT?{=!IzwB3&cdTZgqafwH?eOTo`=Xlu>R-ZdbIg`UY~@P7 z=KnAMK>Il3EtqfGYMWE>5j5B9yDD`LuwL~mqFs!2ao%<*{7Vz;Ur$6B0vi+nXv8Q# zWj;Aa0l;ebWQNnS38w;Z1Z`LXAV34_2`7kLy+`53QKD1&VaO4X(+m2UGd9Q5adn9D z@FiluzC)xOtooV1?-2Yw67USo=ou#gTntnIpzM%UcdL-8N<;9r z;0Nh8Y$31&0tz@p4Z@`@yr-{sVUR2Es6aZS=c($aH}8w`df7|8x2);6l`nh8qm?o9Jn7KwxXgD)wvA5(09@$$ha8BayLcIBA1lq- zyye)q{w-U_8UoW`M42G)OdO1NSPgL$AJi3PufC2lXcQBc*P7v_V%3fW)cx%Et@XT(O%5&B3@mcrJ15+~i?(cQ) zKc{*VIjR)lel|d98K&$AKx4-hoc$05TW$gPqT+bRY9EC_|2vcczebp&uHt~sR5iODG4+ZA3c_KgV6CWVDubSa z@SlKAC4ewYzOhCj;1R>Rz3(BA1WUr)!pPTyhR(`xpb!=oOgo`$7Ve%L;ue6290xeH ztla`I;CcOrXf;$607VIK?MO5$^zdn*9xc-fplkuSLioQ31%TTD^ae1){NGb86!=q7 z6=)#-8n6AR$ka6W)dbTO|Yz_N4%u@MS@ZX=5Wz-uKyI0EcGu+4ux1cFfmJ!C?iAn+PnX<8e$ z%U;8rDg3vKIC1oqOtDP%Hf$lV2!T`znG)Ul+s9;jfF-~V&i{JnC;(V7End6Jet%i_ z65;v@Dge?8KoqRuA7@If0A%h{0We{^-IVb(VTpN$6+k!v+@(!AUDBjI1Y5?`ocUVA zhCNo5f_s4mg|G~C!(p6ICQcBZdzjZ_>RnBVFuA>u%2}Pc!pxpkFXX_2Zyqksf61AO z%Gd$fzGmLE&mdjFSo?)FXgoTSTKta)T5vd}Drbo}n*29l&d0 zPDHmBuySC^cIa7C;^(Ae!5C_!CC3mpOiKWqMYwSOQWZ9nt%5Rk6Pm#LJD)&G(<9FJN< z0I`*U-Z0MaLE`bMK@_z}k`@L1*<#l+;0smzw|AWQ5*qC z>OX2275YRkV)_w5+0VzMF6EU`{87G?F8^C9vHafJmu|WO;8OtpME~FTSy}+Ry-~_V zzQ9RGhG$;jgK-mNBhBYxfOzi#LP2v;{bqcCPd~p;gkTb!2yJHq3BL>Ux{R0;O%lNF zHD!qx&ktbR7AFLPZb%qf!C!@u!oPdfc4~xwmh=?*742QEE6%#Sx^~x<@7j#COu}V# zPYZx4Y`u&=Cd;&Hrk%M`X!z1V0L(N5qs?gHdeqX12l%O+lyOyw652?nGfrCI;B@E` zLN}73!ebmW*9z;d97~)654jbDifg+i^Yb=}yAm=}6X{*Nhj~Zyeg%I%*Z4S4b!JW-{mnK!PYAR#qzp(1UBQTeQXG|L++}t21$+MY5Smm39I^NJfc^f5 zv0JyC+|7<{h*Xa0OxFdRHqbg1`X?Qfu~+EVr1yPw66U<;Xv$6z1dkDB&atAIjSx=9 zjG-|?VK{qhS6>u>w&8XN%sF!4Ev&+n6%*DY9OyY8O>_f~bHF|-m$BzCK!`XZutzWS zpj&+$$o1GmUVZ<8Edf(V8`t5ugkFTy?d*eT&WgqicCAjeTJqN*jfH1_PO6w4k6Gei_^%bkvIM|vt_;(opx@unHP-~xlrL5Xx!Nqup1%N&b<_ZBn%KfF9hpfPJNEt%{ zUaN?GV5A^&#Td~dfc@|@_Vds17oy|PKF8zffKh9U9Xx9uzGoa^J=C!ELZ2b8C;Qcl zb7%^1A7Qno^FQf_Dn)Gpy3}O#kiDi0A?z!a5%8dcW6-)fr!5~q<9Ap?{DRb+cq`8ODjZwVq=@1DyNkDe=sAS~>eAxOcT@8E z=xDnjo{QVi4VBTs+qUouIavQk!a1xixFMWPfU(Ci=5;B3guhYwCEumISjwO@JICSQ zDNXj6U96$1;bAxBb(jQVZUw5RjJzBNjc0vtKQ!<1;Db-SytBeZzSDL&5q9dUMsE{{-z|?e*=#K zw+eQp5_miTHL$->B@4s;$N%)(Uya+6NG+KW8OF2hHrrY@N+V7MJ86SKoutl zm}pIJYtE3ZVS=X|chzHcrjL1<6Hotuw6z2%1nFDqu>I}ELqPfgg>fHZ9N|SCN9|$u zzjryRUd@iGmmKBh%Ksta{~kF#caKp7=<~nW29&Yv-;!G&sKlJxR!5rX(Ow?=cY<@T z@2g)>16+}tA*1ZU=r`3dp1o%XfwlX>_uL2G3bL^cfP8SD>(jpVs0qCuj43oo1Q6&l ztP0WxdbDQhav%N7)qao*n9o=yy%K{aoCYw_-x1CLIbyAc6gfM+Ag#G(&DCX882TQs z8zQrt%HW3{*$I%_X>zWRpfk$`!E%PcKRtbcpMfJB0xJBo@(=FLnm4#4_`9m!XTLw# zOeOh`(65uN7aaL#ef9pY;BTAk|75&*`dJ30D&er#Dsy&$&y;nE`UH?Odae%e^@u}7 z`T`X{M?Ug6tN+83LG|*7gKFmjKO)>envJVB(33Y8P!f~|du$z$iufx9e@_D_3V>^s z;;P{-s_HCEb(D%hug}4|b57FnRFGfBz3Ru|p!$J%_8458A?RboP@SHPISGK@;!C30 zomD$~xE(vFtHBYti)BO~rIe@}wLMt`>_hc1)kJzxVq-tqW03lzvO%pX7Zm8lSI+Ep0JPiOfa-fdSJ!s&Au_XvZ z6c=OYo4>pNe%IDh*-xzQhP-Y^Lig53d7oKq_Oh~%ez-0Lo2CFrxJ6&L7u~!?UN4rl zk4Cb1uQjZzKDGexai6A(UG;CAfw?e^d{WxQH~PC31_|Djfv4bqMVz#G6#%7%EByF# zd9{72W|%$8!NBVF8neuBdWBk91;FeA6Ii@&Yl12NCh$F3CiY{JmohvsYCM zjMk|23jN}_LE57Nz`eX4@Ac>EC;ncd44AUF_pmx;HR*#2fPGe}S%s;L4xCW3xe~*4 zv@Tp_v}jHK1QCH2xhj|ZN|@2hg-f4+U9A3tY*Re{qX?KD<8<%juYb^knH3U1J*6Y6o*GP33DB+6fjd?H5($o_o-@neVO_xyf4wO}Fhbk_tBXCHhkp0hqiTFHsz&&HIABhC)f`s8 zn!SvZL=Lbl;!ZmU6(vA&w*mVV|B)_89kdEUB^8Q6{e!3gIAQ zShILkXfwdV1pJu2LrHjw&=&p?5dIIR)!@an+Wiho7EcEN8C3!}9716w6;hF9o8r%k z8@Hyf7kz5sQh*;sxy(WI!wFFZfOAsZr+0i_4w%$3(K1L2=-A(5VMAJ=6+k;=dqWgS zv5l(*@;bnpirbtBwufyZHO@z;$A_Fo;*q3S1Hh|=bZVTR9yzg~3yPLo59cxz(#y^>`*f}=Lvb*LywLpfyEy?xY=+Wrjz%Xur zauS>1j7mP9=JrGN{&h{PO&NGOIAah-eXrZF&3!Ed=utb>2_dBW7O*&0YPgR5Wo%xo zS&7k{8%h`xX-u|u$hIH87VuBzcgbWiJ0g@3U4_vM6DGa~lQQHO$uX;``!Mc%9QRk& z{|B*Zmn;8)f`Nz$7E9JG6lAA`@z2#hy?ZPCpJ4-Vh62FVXc_-2tN?0+!6u#mDf~FT z=EDCvwr@?~9gJxUAI)A#8Qb>XLnjR!0a#j0?5LEX8-&uK&p6LuFCa8z*#Jn zDk%6%7fd}GblS%v09t_YLUo4q+!@~4&+uK*gaAg0e~GZR6E|Gy2P8dA{%f{AXi>$| zBlsu>#QXW9QtIJa^$?KzifbUn5JfB?a839BwLEQMXldW#Bx#fNW0h;_pJ#X5h{HB@#Z!(s>Ib*9T2 zWoKsS<`W72m^bI?(zmt91+tafTrYiY{+1PFu1#*N#dY*kR_4Jgw1PIS%PWDU3|ZQ~ z#U#OXOfuY)86k=l;T%hbJ1*LkWE-A01Ogqvi%<@UA9}qa_R*qyRF`JDW1{H@mOY&U zwrto&0k1Iotn%|uC4fhIxh3EVsd9oqqZ7b}@zjJ+$n+zF9|{1{xlp)KO@5rphF}C8 za@7j#DaZw;2}_;v?O*|bNLb8IC=0=!)&2=vmoC686_?U3!4E$ivH&gw;+oee2!wDT z-cpWEpVW?}4v1<@K!`nZr&VIYvMfg_%pg$L&$XkMa zr$Ayb58xXtgBpbSqG$$`C;(L6xXOuHO*jD@(hs}DLOXOSiro+$sJXv?uY(jtYV?pn zia=BNr|=&U8c-AhI0mJ96ISju_rD~~mApRq)x$4}zmzW2yVwzopc^^?3|dNC6kd5E z$i_oA>mfn-rQa$558ybiBP#IAr?m4>08aQ3#ivjJkPr4ou%ny_WuWtw!QV-uea||D z?DuXOdGG`rYS>RwLl472sdN#gJKD<9(3p43+aUhP=S6;<8n|9{xt2AgBpDyMj`mqM zTAfe#;~(1^I|F9u63T8q?`P_p#js2l%kz38Qn`n94WI79o3*~}*=~8}GxZI2WFo=e z-+blGtK0$*767iaxT+^*eS{ESi_|H**7roFBN%V-6&Wy-@bo^0*9x0ouf zQwWeH{91%drq&I-VScZ2pup9&SL|RZ#~~k*fUB)~j?sas7O)NUt-OWjLux2VtAFSb7RuQB@E`mPfY*Pt!|TmHnjup=ZI zUbpaz&DdyZaHOf9g&v*Zyt9LHVCZVUN<^Z5M9L{5+7Bu0KQ5pZ`U^fO@aMnGlQQ;a zD1>GxhHB0FJ-vc9gp}$wOA(XbDRnkG__yd|*@6(KL${vJ5Dk(OP(2k^q3C z5R^LH=ihGI^1TJfWyoqFfpSj(jzDq0u!%-0>msj9i4cedZwnNDS35U_H3cur_mK4f zim+DmQRgaXxWa!=<&9`*x!py11g?`+%Ik9D5&w!5i!mx~<*jf@9DiB<$qO6&yjjun6FBz3m^o<{CIp(LA|?kEuQ#!DIiD)a?N}3&@Wm>!L8 zY3DP$geb!o^PM=2!0Bp#-Mogj{T=v@$Nz@+x~JAt369w3@3)8KtxG5X+Ir6UDz3Mo z0|DVd6kftjMSzP8&;^M|GjLl4TPlY1868A7FfE}f#N+=VPR)*3``3-AJN}ROdw@kq z@f~6ZF2Z{8x>Jo6WRp(l08odZ(h9c%U2v}7C8qyzBFKSzv9TN(AZZ4+iO*~!$vkPZ zhi{89n~5$?s^0qxXep22PeinL`^w-DrRhi*wk=-P%w=UOX!FWn={OWUV&#Xg#WkEM z;G2B_rpzmv_16meDgfk7z? zD=7ETYwoq63`XmW3FeYGzkjb^eTFZ~Sxmu1CfXU-eYZ0iTNpE(UNzNA`T&O4J!LRp zHTyPe9BwtUQ}{MkEGFQJzY*KIj7ehQGX(3CZE`#CWWs_Za2?M7^yh`(Kl^}?bygGs z_-Mn;HO`cD1jun;hj>swWF=K6fUezn62KsGIial|)CyzYgqgpN|NJ*q_}9BPj-x*8 z?^eIOe96&&lkogsqX3w2eRg=r5JG{bu&7CRaE}a#`AYG2aD0Am3oBtK|02S*zZ9k( zyXW+@r&m&V9GH1F!XodV!NhYK0BKxWBWUg*I z-^3yV*%2oy>;mhdQXLL7Det2I7@>%M(SKFFraxXGeT|_T3jfj(DTqqM#}3j7>4RH= zPEY};066CF3G?DPI5pX4tI82avf<@F1W54?Sk(9g2!*-VyrbTEU(NdOs>$hJ*eifz z#NJg1rG1^!9q|x!cjrZMbQtq({Ek-%f;R7)o>o@)VbnPQ&wqNmf)W0WoU4pFnv-+?x8bm(CJ zwAy{~fm2+d8`27BeHi!f+Bk4hC4lnvLk8(y(!P0~PLGOF8LiI3@=RC|Lowj}HqPt% z#1LiPu5Zr>Rxo4kc>FS~khEaLhK#5P?!W7f@SCfFr{5{+D-oYB6Sazh0WVXO)=pjLUo7>)XmKU#qYQ3V;Oq=K$`uXKyRd{r^j6 z%F?4Ekw^w|sf}+_iDKkCi1s-Z{Pt&xrVW&5&NKFzV9QY)mR%F}Z~xNv4WNyJNrZNM z%S>~GOwGzmuX@Ww`3@4o3K&e+Oy^sytkpPfYOY{)G>_vIG0&(&aB}pzym0$>lOfP0 z_v96n!ZB4aWic;dstRhb+VATBxyT_#E< zeq9*&+q$Sw#lqOT$6o~ib}xAPpR)2_RX-n&s=xgD4Xgjt>KM=R%~(eNO*MUm;K*uU zGeXeOWITf73=-@>*@n-DfZ&qJ759u@ORpp}tcX^?T&5_5Nd-zh%j5F9KIb^TPzWeB z$p82ZuG#Q7-z!qZ^$U4F;-)Vy{e$pO1Pb~PXMf>MTPFfxrp_}eb;8p>Y4oYTZ9^z3 zwtbx7n5T*NDompPT7sgmqOgYGR_}6}!$@|GqXAucrC)Y&r1=(_@hhmtcSN@Ws62el zF{1htDH{Pq3`4>_5v7!_@^8yIK^>;y5cHV86L9SVeD?|MJRNaV} zE3Kf`?BQ5ac!UrKdS3lN{A+df3UF6l{P49-c{v^7Ex1ba!qBd5Zm3Xm z3SVVoAL`w9A44{j%a`z_DxA5l@dx3m|J8pTRF{9@h|c#Y0WKV~DC+=HGsa@)?LRzFC~ylPiEnP(5zdx*Bmj#Sy^G_jIr*XLoogwCLZE++@#94`Jo*LtflJo|o`JUa zM{u3|YzKcf8gzLQgQ#ZNg9PD`(GNzR3MdfTwh;cQn2N}Vlvy6_waq-2p_9#`ZQ6nq zxN6Lb8VF?`4vblRROpt*SQh*b_ZLBEciejjt#o;-GMIB$SZh;ccScztg3sJq13KT4 zL-oN7;$m2AO5V5p)|Yaxd%v5{->+5bklmzkTc<2*gU{yk-F)|1pBq@~002M$Nkl%HGIQXN|)Bf%Dd0rQB+pFtmxp;se=9XB5eue*{0C<3pKbKDg_V6bd*S68la=`?{ zwDefXL|BVi7-=u)lFT^F^^vFM%b{SU9chk&mU7=@N)w8>zr&sT=0O0Qg=6-^J za>WYX#duU*3kx*h5v{_BWMD6Q$rsb9Yw0#7|}R|H1SIdmhdN$c<20z^~#hj z5S)I{*NV!OK4_>y=m5U}!Jyf@kO#<&w&H-D^d(@(cSke&{fUN#wVu7UvRsa{!0=5vv zFh&CGOTRfDP+xiudme@z0vDar*lrL!&SL}HzK+;tfV! z(KWkr6VncyZ~Ip;es)OMjDiGHN`qBsKL>&JIg#g>g7dp`>@T;uSazxq?tF+{I zQFsi&F|TPzgLO(Z#eWErXP+Yx-A3gpi8B3RX(ery=4R|n*$K`kl`>T4Z7l#TvO7)y zYvF?*fEr~$qhLRD{BmUHgt4l^u1D(DfH0K+)-~6TZv?yY63V8~feEYsm*AWyGQ^P~ zQ;Y}TZ#cRkPGg`7>JJQa*jul)2x32RPKRh)Jl|DLK634! z_vgEVrJGNvbj!$xGA-|!T9&h*&$iE({)YK-N?|1=WGl8@H|+cGd0dwaE2jTD#3AQ; z8wafZdkR1wE&2|z`>&8M5zV-s!KTa3YvSuB09W_)128ip5H>LN4G!iSR*1@ea2U(E zAi17xdQ!ETGrVo9k{J$WpE8kDCt<}YHs*qPEFUM(c0R1mKq=6Z2dqbQfT{3Z2IFOAJo?okzteqhlmVzdBC5w3MB8ky zdCFXsi3yr#7AN?iU0+?BC;h_?>c!aWUO#BV>0d>C`!2h`^e0{0;(_>?qg7%VP>XI_=r*aF-?VmYSbe1^ zu~OsY%0%nxh1znCXbJ^@+XI-4ueI}#AueNbw0s-Z4+735GA$XLIV|%O2g~xFWk$N& zX=DBy@5l3H^`(3CQlqzOd;sifj>#4P_i66IK#e&+eS|sdfHRenY1e6&76AFrPp@kb zE<(puJw1G<0$^fUF!tPU6#&%$QX4CLGVqL>r#qjnYj@qOS8zp6e;}^Ru@(WY>~mCO zbPZN1MPu30x}15M_LdiEwM}1 zp{CI^_Y2hRE& zUqG-6N;J7F$^ht(XbD&X2s>IJ8P)+Hr6%|DHzp(6FObV0U?Kbz@`*#oa|-gXxLWII zRbfoHN{{u$5@Xrt0i5si*%1~#VI8D-1qxmE_c#4hKtE-2fFIq9_1R^x*VZ zLxFxeKDJuGJo>`?DuaC+aPT8!!b%3;1)Mn1(`Sa2lt*K>3iVTrB`Z#hU`5TupHj5_ z`&kf}gZ;CfzQ2d&UG6xbSHlXMd`a*84hSAW8Bl7m*zt?k<>}>r=T%vLdwolxpc@@N zr<3g5+d_{1M26d*TeET|O=?slP}bn?JOzh~PHfGp`;@BVY^KR8N1RnJH~~Og#4Dsc zjs&dsZ~(aL5r98dQ%vwe0nNl1KY@u+;U1HrSo=Ac`;_3ej%{Jy2q7P)MceM~1^`5&_%^Ua?I z)sVfb!;4;ZSdXi>)0fq6FJD)0E^z?JDF6p?44{U*@MFQ!r!rvu0H@&Z%KsJ2)H@t| z>D)_4fLAc|$1svVjEvdaE7KW5==!zoN!KV~4(t`C zQg{&2BM)Lrpk$1*Ol%A@Vfrvqu6>750mAnvs7chaKe@%llLq6;8aMBg_6rKR3jR85 zBE@oI1;g?6)~A&*8cWi zGsoh5cfytcj@>sz7B`Q^%19~01_FB{obWJqP zG-|y8f1HP$vz&j7=C6PaR%LNw#0yT0=pRugJQetH*m(f2^6S6ngbq&aPyvu*HkcE} zagJ-pzuSPWnBZQ%WeWf}M_DuFWTW~6?9OXk1K?xeWFH;jIj|;j9AmR{#$h08yXlYc z6#x#1e!zCe;~9nVD&X9{H_49{2;rO%YlZ&q&wTrsG2@M^sMwgWyc@r)`it+7?KeOvH!Bo#F9u!= zzBVPl8Y;V4uvuwsog8G8okVq1#Hxca&d1(G@Y{VC6LIYlhoptcP{yOT3&G;N;v^OJ z)HXam1e_yeq!jes1D!&?$^gCh>#aZb@2eb;*C7hGU;|)W54=RBvWS)zM^J?Q@LeKDMf3nG}Me|GK*Y z%sss)u=nq((>UhKL%vQiKmEW;(fO`S{Yw~9+BAm2)B<3{DwOAa$AEBd-Gy8yW;0EVbg-Qz86);6J?f1ku;MYfg zPa5;C0+BhwkP(dM=$Ga~c>MnFJVAFvSTJVik@1d9KREm;=egm{K62t|`SIjog!Bl0 zGEY%w=Ol&KS(86U2ry+=h28I2hV_hjO?X15sLkJp@qhXg0)TH`3jnOLV>g&_ep9@?O57i6jhvJCljh5u_1=T(op!gaW$@fIHE@a!M5oL-TX%_61m7VJyS>GHh(XY%PjCWAN)#|whzh!H ze+vOgC!>!LB})N-*DeA8wf_+SfRAGV&;!7CD?I#m?Q=Uy7n~4DJ4a)FyoJ!4Z7An# zC3p%GeNHa}u49<~t&6mjrRf<`{c0QYri#(^W3ta!)GoRwDNq8 zq8i@*ba}%2?|R02=K5g5Llgjf3~;YD*6`YM*)jth+&Ziw@Bt98*GTlnbdKSpAi#hY zw-PL|%3#uqlwS10MK6m2iDf|0an{VN@$G6b4I&A%3eSfFN2 ze~2)?q1nHdADt8s%zqo903 zO?-8_fb-$e z{;DuQXLVB;Tul5!vazN+b8NQ@XmCuYIkz~NyJFH7&2xmef{!S?mcjD}jDpe?sA#1z z%8?4`08lt(oj;6!mH@!;d+l2P8sCNk1W^4rLhK&E97#V%;4;R9zU4b?E7)A1@F2gA zZ?zY+8A7Sz1khs-U*D^d(;ExJw)6Wnn4ZY^$g&Y8a)kj%D)a|nPb}L;nL9Y zY5msvcnJcv8LvBDdhm`eZ00D~mL05=OuFO)0-ZRa_SE{yuxFWe^}0UyMI0I74?bkL zzoiz##v4-C^_?mJsM4Ufd}bAsYZa~@SFx;LTA6^k0)VQmaDssh>(E?u?u(?W>+taq2yh3lUA^{JP2(8teuclcBo^^r+~TFbg=-D7Pg>fF z_G&{+a?kd$Eot&-H!xde1MWQ6Xx-rhX?KXP5n30yUx_EuNA!^~!lANVSJCpjUw38x z9|qGe5UJw;m`<`HPaS!kb9M${b>=xtfzg0iL`N zHz1;z;S|&@LftB~6-S5@u14{VC}$Xa#yPhxRWTo|r;6}hW*6L>AnqyHD$BC!GA?;P z?{iN+Ig#@OZxAn`r##%>UzI~Gr**LGL_wlVh+0!=rPP?WE1ecW+lS~o%|erRCE6q! zBO>W5l@Imj?>e}SLOdQJ0`Qh`*6Sa;Aax33pnIH8QzpKXm0mm^y2r9oyi4IW;p?}7 z%d(v*DwA$30<;i_WrJ%cjOlyauNF{mbi7NY{>m=|?CV%`?YG&G*MPgvUQCmmYrpbH z6cXrZCrGNuf)22(P<_(gTEp8aSHE6!ug^cIBg6BH32$pCD>%G2JQpn(@Hn#$ zYY2P@1p09w+c$=fS_`ob4tT=gzzE7rwo1e8cFvK`xi|xq;arDXh5${W0>dV$u_!cv zzo?!V8r$b+8<%PNn9v5iq<76|!9*Ih##Fhepoqmppy4!Z<8Yh6! zxTw}5>Zw~(-3h{g4Yp(2f->5MD$xQ!lmDXqSMy)~ZW%J4^?AWrgXgTK3~_%3vwwnS zsYKG}$G<%v|y1%!CqgpB(f$`(qWgfPMV8%{;kN?CH$TijQi^k! z{WEaE8KrdH{{{YXX6#SDh!6n0D_%$hcZzSri4W$>FlnUA{8y_x(_F)iRX{h{NACI! zuWh2~-vk8tZdfp$sch{kmsr=TwFJINvH;$~6 zNwA03Fl_nZdA(nc-uu98>MN^x6#YHq@UBMskb21y7_cjQfPpSpnVm2>UqqK&@pf?1 zllhkrah+nzMCe*Fh_tT7Q4XeYi&GgtCqdXphz=bRwfhh`3gAIEmrM~?yt*q>ykXxS zoEH-?N@-djtCGXD{YeAn5%#MDab15jY21RFcdhvX`Uhs_y&Q& z7AuY(fpYeHcU=@yX){D)V z%SC|^@N@gB;FlAm9Weg*FS3re8mu`lXtdU>m`(=jalbD!OVK^Y~Jjhu+I7z zfxyY4*$2gZgI4z&9GC8ZkG2prx^sxe|6-EY9suqNtB4T_j?n3!=KfxvgCovxu6Dw( zKirx$&++nq#JE4$nKW}8{+;Y?H)o_RHo?2uQKI4o@dHt;Sn-6{3J`T9D*kZJ6{+j_ z{+yk6^iY5HKXJ|aZnkI{fs4j6d4~s0^Yiaq1G_1{%M}2?!%hI=WDgi`fu~6WaETM< zYRt7twx-o^SD>uzg8*L%rWs<`a;ux2#;|qGj84hY@Rus|}UjQA; zCc4=nG>AK1^PUX79}}*Dv1xsUlZp3;0gMN6H%MKdM~~PYKtUC|A9d`0)J@Kie*^#1 zUn2DGWU_I%H_{O!Wo#bWpx&6gP1sx!m!YVMB0vC!yq? zQdpRj#?rkvRG!b#^Eu%)a6acN_w+79;)@L*&<8@c3jn;DJggv|>X!m8kLmvps~Qim zv~(*c3eDhl-Kxl$7=njwnYyzXOyOR0aj?;}$4q((+Z6yX366Im(!POE+U5OFZ0c@B*}M!0~3z98X_wxv14?DDr?AjDWJIb)?O+PaN1 zzPi~qKfYWv-&3CNnKm{5*Ad{ihyiwE3s4C6Rf26Ti%{~fn)2Fp6$YFl-8e+M^e499 z`j_d8=GEx5IYxtWu{&!{cK4d+$i*)9*otb0lkJ{pm%xk@KncwcLC>`m>*E>%UpfRB zS!!p+9Xei9cnm(7;#}?9gR|!Q7w65R-)GGR+Uz~StCPJV(KSB?1DNNzZ_9unpq` zD}ylL!%yDEx&4Q#$na0u0@8MKiC>&D)4Ar%Q5{0-i<1}h2YT!XLP2GYf+hRg&J$iv zC%lc)J=kx`QkNKz7IzQS=Bj_kA>O3)63jq&d0Ef z{vhmhdlmS?zFgty5%@-=2TBjz6#&>Y(A6^hi&G-o7oi}6ZuAAxX~)HA3$hiae)Nb4 z5vmgXK!l=|(G+#c zV%=@_r{0C&U~@c(v}p)-mjbA*yEKWVRIB$>z$}?>_bmbeHGOLRj}QbLLR=p~TrJS# zoo-+W;PzV(mz@Nr`*}wV1A!%BpE0z0bzGNd4S{=wK;{yee{cws#fak=p}-c_Wjo9z zd*HAw;x0nYJqFPZrq%G)jk~P544~qXa=hC?R`G&D0ELA{#Q<~6-Dcp}bC~O6tfsUE zIN4SJfCUxH0OsI}7TmgA0+0rv>{ppEufwo9=kgH+07jQ!X}z`al;rPu25B$*)4NCg zNCEBHZ){x$j&(^Ef13Vll{JRno9=_j+@3d@l)mMwx%$0!gm+|avw}v$@@o3VD6It0_Sci6te`e*^VbOhKJXlWHXeDKY4Bv=VFe!`%$ z_bIQ_-*)fPgAeh7-v1!OO*Kf537JnHOt9)#t3SN1_lIc@rg9IUpu&|&Q^rrGkoAT| z0KierF~o_|=Jt%q23o|4+6lU2uJO2>UqqO-iH69trg3{6-U9*Qc3o5ez{u7TAh3@G z0H-qkZ0i>f{s;qHi_t>ZEMWNO69oW|djUYt-0!LF_?G7o3WRcmNKo*zjl58eLCjWZ zV3~i{6HeJA`ItKIMa>eu%@J#T$`4S^ek z0JuovHG*W2mlj0|0D2z)n+O1QXPEvIw}`tisR|O&o5SL2{$JMr%ifew7@Zp|;0JuF zV27aqz=Z(%0k{Cqo^6bq6P5uSqit6Z&=@zx4d7F8LTt93ENiHB>8~sP5TDc_%*4mQ zNv&=(0auIk$7cwDkAWZT-Z{d71M-qNWvRp%6YweN?pv>Ex@cYgKYo14GRwzo4)VBC zf|~2SAL9c+P=(2+tu3rH1{E1$iDkbT;V+^=Xe2BY05o&vra4520stBJ>Y+GRZGOOb zB?RVuS``3f835$6aF699_wk+6p0eBvD@Z)S#_~}Cfbet8z5KOJ^+p!MEN>Fne#>s< zbd9_sRTW+oVw`bB{e?w{GHzHvcQvS%C2tgzch?~huvJS0Y|HbTY`hNu^s?V@l1|1u zSC6&7dAz=OmFH9HbNv$^P?W(Veq&j(LHbIcGGf2@Fzgyuwl=m$Mt;H%{c(L*L*V@o zu;*kw8z-3v0L>KELCkO!a!8C<{pF*5X zp+t(#e-e#db=oDlZkJlsAZf2jZ(Ro9xodqF5QuZ^P#0+U7h(Q+g6*bSmc?|!N&<3~ zE4HctUzh9agn&3i<}B;mIge$LxI-Gz)-9|D%$F8a6B67tntA?VeatUyMMl1B$Tz_CE{SvQ)SZ@VAD4kS7;A*= z#z2$sX3CVqEps0u=6btVix9$qI||4#e$);)N9z?Z(gD)!I|}l1zdWCp)<0h=1kmmz zND03AE&v4%>)#KC0NqfgUynRaBGF(t`^r4B zFY(xQiI7836?ue7r-QI-*~ZEFu~TesPbOyW_53Rd&au#kCG>M`*7Nu2xnFOarZYd# zbO;*Lg*V)MtJi*Fs5R2MnyxqEIofB;K21|8v`|ZdbH5f()E!=^3vmR|GX4glly#*O zwE7AHBw}1ADdph0)G7oB!6Z{leiA(q`1B2!G9eFFV|R`Ns6fhU&HuFkfUuv#?9W-dJBQes%l`sb7f33aizuXWt0x!x{qj2LUC+YG`FdIM+;h#I*u|O(qeU|7{rCt=@u20YLE{ zQpc7>zrXRNU{EokOM{Fq0VvA=sFpZ0xD*_!=D*_A2mmS$`~=X8Tg1f*9Q~%}!Oh|= zoV{tSr6rfFkjHMWV~xoYORa(3g=gbL-le6ZBby zFzL_hp~Bi{1qfT*7V9{6V!+=(JAMSZS2v7siaCPW7kJ_iM+dnIg6PXOS<0)#MVQ_~ zNYSm1B$=fk)8wrMfKGvCzyhT}7=Fi`{bz0;p@0zrNO;u1b18JaULPw2hTX8HJ%l4; z8*`zAo2-I8`zF8F7xDHEj^b4g0`z_1CZ2hKJ^-xtb@6@RTHpUH2sjZqyGXb=fqE@B z+2SpJ3ggdO#CG#X=0v3JjSM9dE)-nb;UyO@yyH^{j+o9d5jpw6IOWJ>nB!*^Zna+y z(+#L%oHS@F9dUdU4(fq^AV`tvt@fa?YX9G;&O*(7( zyO{KIkLkbFN`Ni>Sc#AKY1(O%_jYMN_b#4b_CNiRcKZneMJoUaBZ(Tmx2LH;X=<8676*v zz-!;#`OM1w&?>;KjbpD_$oZoEKgRU`1Y+|9M}H@KBi8-14WQ^Ct>jJGIa4!(Z`~kw#0U!dz;s_9r^=E9F2ZOo;!}bIpGtY3swhQyW z4ffD^s4hem0*FIO7>=vq`R&$9M%h1E=yO>AV}36~y!t7VpH&o}I1g{KBx|2#z14z36R-=Gb?J+QB}v%=4*@`ztyyqWIDHAM zUtqC?z?QTz%d{rjZfA!d7lZ>7x6s2nASes}1sa59cK|_scc3M+>qF3}w=4_uq~Md; zov^fF`V5vA%07;66@b$YbCw2NoctO02+W1-Ka)93fyo{)+vVC2VT>nybcv@uH;JFh z{HM*xP-YpXzH=+b>91EPFPtj`pie^!W!jYPaSC>;K4E%; zVWePzZ%=TPs5~QEGRG$Z!fUKP#>WTE_z+lJ&<7Vp1^o~ooy+=M8eoAk*IOv--xqKR z^cyVf1Ns!8r0*a|Nd#mZy)N+qRfM9_Gida827CScg3kz+cZCmm=3VdK>b+GL0DNlY zKcw;eHW=)o29eTr@uAk|0hK!w1Vcx!!H{4<0ZtA`lDn-xpauQ=XhNIO5iJDM&lWuM z#h;ov4&p`=2#fQ6BIFZJfMYb$PS{|j5+4vK-dWVEsL|0TqmKYSOua$?(jst&@o!m| zKR+RXbeBqaZ-LXR7KeT9F%f#AJP)wY=+94ZAaw?jH$(e?Bce$0Va_`U%We+=@0M#7 zr802Lh*rPbz#H--oJFxUlKU3tp68pSZD<9c28s5}J2Zv_QWf$@{G@?A^bOS$1S5zn zg*p?o{#(EQ+)Q5n(u@y&ZFXV!cjr6J-s!XE$@vqu0o-7_k$oqh5bYB0MT=*O-(0;Q zQ6Fc25cMY^?~7UQOEhUOF)clK`m8y4@~AoB{7B*+BC37-eY3zzbjKEe9b0@Ach!B} zzH%aJ^;&pcqI-uxB%L5U&9hHftL+ghfHAwuOxObOF+9n4i@oM2@CS zz^!`pcUw7~goe6F{AKI=BVcyKL66sArE_Z=ukd;wSv8o+5w z@NLTc!(4YyVajoWTTJh<#5g%_F8=eM5CFU&9e8cP>^eU_{X^3|?v$Ttsh0?Tp>o$U}Oh>fQUc4BzR_JgNb$892LQ2-#_ z1577u2bnI~fBwcmYF8qUF@kAy0UBb`#w-gwqfM~{nJm~A^7nscd_flo3;UoJ0SKi! zmhPoc%l=5=v|h1)-O+fuF*w}xhiL9tR00Rbe9jdx5xE+~VaDED>0s{|hPM^?ZRx{z zAKbZY$JZ2UBi3VWd{njTu!g_~LcreR1nC4QHQ;p^M>Wa_7F|z1rAwi8W@RDFCWHrj z%BzL$FbB_Tn%?=k0Xk!Oo`f&-r_K?Kx_IeV0N}aw8V-wE%>)qwxMM64I2FpBC*?q;GBNPkv5t# z@rR&+LcptkvqgKU`44qMo7$*LQ~&-t%~IQ~R;E0fE&zio1AG9!g80GBA3~wc z^Bs0x!eckhoPN zhf4r-AgUjLYC%-S)o^SL&tKuE5}s1>1%^&YJuSY3OM_1p-@kqi6O z4C@9>GG@$k8<@Mh)I=eGa8Y0)jLL^N2uI>DKLO;mf&tIXKkqO%V{zAxG^8~{zE3Y5 zu|1$h0y+oO*>08_U=1?Dax9-+(mRS7n<;f6b5`RJ++<^X z$hT@|SVdT@%e1NxkhrM9HE~&22LqJ#|1gvY1vHalVK{RiOp)u--64Q?oL`v|gLa%- zYWR@OTAzK0$Ixd2Kzf6DHUa?WTWJvHVz=ju0HD9G_FvEa^8?fCJLUZ1aMCQ8#M?6n zjtBrCD7PRkTeKS+%JgLFA^s#ZN2IyzYvad4^e6;ya#v`8*?I_}nEKl)?`Q=p;96Z{ zZ8(lv0F0uwL-XPK|Kmeeen6({{10M&6Jf_DOA!(MwIr{ncTe^BMvx4S@_Y@d^k|rc9

X4w+!1-h(*(N0#|>#ztE?{UwE$>xtVSWKru!NN~kLYvUKL}Ct~M^Eo@idkv>8?p^!66}&!7wO5Qc$dV% zjPr^lavv3Cu!ssqTnytX|n3-JDcjX(NAAZA~rkrLT+NP$BX5na;nFkgu zYhmCBeM`0w8RuD>xDuLNc><;>%HjnsKQGMsxCcC=EG$wF%?{7sf zF6i=1j-p48b2Rk-Tf_Tn}9JM#ylx^%7b|PEB5HB z-zOvCwO9bS-m`H1u}q8|h!M8``(QgF7Nc9^6(ARPOXl8jwwPSGHY-Hz^|o_aD!01? zwtYSX;P$MYU1wauW0(}?LAyR@xNUIZ)hR}$M}@SY3hx^a_TFOwm>QSAI5%k`CiDlf zEMXhB)z?q}mU;x5^_%0edeu5IN4gB$_rIx(X1;_AChXK*YhL>XooGDi=lh*!(AmY0a@P?H?T*qUNX9R_Oi7fvz4a*ujq#&sy$0RJUblt`0R_Vq;f zpTubQ0b@nJemtRA#hAcWLGho>INilNaK^D%$xfJE$~yvbfz!qj_PFGe_v% zKbjcCGA-ZS&FRFjk)wIGtM40H&PO9KhNC5m39IXk--m1=r^FxJ!pUGpsIj z>5+bm?n9B_Y)mkxdTq`ql4N4U%Kasq<xE)sTh(obd7u2 zBLF|om^Jt(T1L|B6qe%|(>J%6`J4`lx2j5xA-1Dqh8@VR*llbbf~RRuFdFDHAK-sc8SL7iV(?U1HDY#$T+I~Y6 z)PmiYXqM(ZAQ&NAvV(~+0M=@4*idqLXnUxBRh7p4kzy*WW zdBR-kxJ9)V%dIEXKTews6vlm*f?ppXC?f3~Pc3p&yR-9y7LLhFVO=pm;7lMD;XY?W z>GzOl-$#gj`zX84w^@wTYNnCg;FSDI9g4%WS=?(sFsAb_ov_c%>y%~87{FsJ_2#kb zd_1h@n()EUJxe!Qst9!y`e|rJ_leE?SU|O#%MN7*Stj*k)H?>sregX7sMzJAaX1+x zJwBqC?t)%s>y8WDL%)T z`XvKKJoWMk6&v+%AerAi-!L7F91bqwum3)?^Emz)xvnlgd-(7z;%UJWEfW)K@3dR3 z$DSi5|K9Qmjz!<~@0e95)26zvc1_6ijrQC{Yy=qdpTBi653TtA=00Q5rmM3iW6v7o zYUlys1Hz9-#FpQ8WCt%;8_60Y8_fT1q5O6g>-%p_CE|YRSt-s}{~d-J{31J^%7Es- zH5nSf$ldo$gLAi&3Z%hfqw>2B7BnoDWN#!YUf`q@_a1fKy45|bUXC90^}IMl)b26g zKw?fzB~TFSh@z@{jVb6*{XN~%+&TMhHrG_i$^_Rck{p<#Yv70R9TCB61N}-qddd=g zWWnwh^bYnNXP{;9x^3MpL*h%NSjj3aQ$s(7IX;kW$#q5y3bu&Eu@um5m(I0yOqa5_ z|0dM*;Ok*{A&PRD#H(jiHwo-;?cw5;$bn8it0%uP1Iz5*&6Hg4=9y3q8SvbiA8}-L zp;LEf)@i}O;!o7f$x#f=McGnyZ_p()mVDp$sW5}%Rr#%`Mj1U7QqKdgYVozjPax5I zU_)ZJodVacm+heHI_A#Lv$=uyjeM@gl#9AWYjz)Y2E?bj=_srAP2!qtP6B@1n2_;m z#M@$U#CELsnTy6=rj6{j@QhDi9-oz6+=!IJ=l<(b?q~oV8@7^#m##&tt7EstbgCauM5uXhjkV5ya7{a03!WGEcfE#JN16tT5_YOD_iWAR;E<0AzDzZU zBx3})rJn(FsGrX?aXcv|XH%(VaSY{1DPbKZ4Pg!q--rw}V>Y#X{3MBTgg7 z&x*;%=o`l>e!6MN^KLQj4UjDi)2(`zF|B*in*lIjKm@kdkdHcQq4#-vevwIWfW&?9 z!mS~3Xz0>|12a|Jy@2vdOOra{Mn#C;aS-jFsJHahMNy?e!Gm9iDy1Zg?J@GP0b9+& z{ox>Wq=)+HhubiNnLZMocV3TcW|1#>wtMnacDj`GkG$b0e{sjR|izJsWEiIm{CyTaQ z+G^dhtqXUknP|QQpxG&R=c_9sr8nn_dHa2pXY)vFS~ zmcoh+;)2X`tjNO}K+<*LIYL+fQ)j^q#{J_^G8Z~kE%!F zfy_UWp?1c*ChIS2d`E04%czAN&&UG8q{7+65gc2+M^l**M>={(2u_k zrIYVfO*{}~M}*81?-ZQ8<_<2B<-23q*YGL#Uv1z0r#VhcHyr(Can)|s z?qc2-`Se^Xu8)cvX2OaRjc{U!zl%=$p@GNNyLcA#a*Sa=4JGuV>T#^STTv9z z#vR@rD3bd9*^d>h=d=|qtETA!w_kpM&;9gF)9+t{01yShdeO()w4(@~by%%lpM-*y zEPY5}WX=A)^Xt2ofTsICDMtlb0;bJJMQ|&ww>IT!($#&Cc*ye3 zQ;-VP-~)lp7E{I1;x*yAH0=a64=6wpOLz3R;`E@t>1j;_80-!o^D9fLKl*X7J{4 zABwqX8CCMTE2X&4kZ}Zs@tcSEt-Na_3Rm#v3qUBs@HUnruONe8r#*S_yo*DFB$it$ ztnSMNLy@>ja0KOjg|_ibr`jX$4rdbE@2Z#(P^R@A={(csH9{?uFc#kL}99OMH4B1waLW4d(t? zskO2i7Bq;tH>YhmwrjYv^yts|K0 z#i2*j)0f-^bZ~LA$*)oFIlBf|6b)gF4k#U)c-7>wc>z=`JGmafjl{X;Ee=@lx(p#& zEnrMI&x@?54g7g#AM`VEU_IZ^3F&j6-Liv91m9~;@mm*1+&JHep04&4Kw}L6Cpc3n zhmoF>7gJq9zmpf{ruD33>0({f1S0MS4Kn`BTSEjU*WUGhtLaXh-1P$$Ll13`qM+c< zzF;!FPb>6J+P?OIPy3*rtsjr`_SasM(WuJ)tH6LQ|EY5uv~>T);ztfmt+O_ z-Pz{8%RLSmszzQ`2%b0K)Y}`+QU@hwC~8pU@NJK3fT)AWRIHf#0v?`{xE{0ykE8b zLHd8d%{O@b#;~Gnah^(Ni)22MjH~A1#gxNMzY$k!laCeHcz@7h{l4`R^NS~8r%#wy z6&|zM>TGv1n-?d)D4MU2_^SPPiP>O^UZ!>)J!mgrGu1o+7y@ieT%zc&EERc%>o9$z z=}nd`Y_dg9#jOYF5FeTaS$4 z>8m-H>i3%8@RLP(7e6{Cj~O&ROf8{=+nr5;OEfYN)N{R37HunK&nyjdTzPP>ycjvU@20r=CXu4pGnj9p$(Y?^vr-vZ<- znARnYVLLThq3>JSLO}hV%J9RlZP>-&+FwVNr3qP=fZBP}eVj4%Sja40E+Lh`b0x6c zSV7aa&MAWWtMHKX6?EQK!PH?y}=3J6@epWji$ zTr#nbKzwb-T6-$X;$&uQ+&8WFYwtbBJE^hh_BpDb%dTOnqrPLNACs(UIMJ(uXHG^x z|8(+U>0rR-LZ{P>tT`RtjRuYV5z3w(Te=@mOiI1&Y)`hw8oo4?ba(c4TCd%qDOx_T zjzA^e9ri;N;NF|*q5W}c*L|jBTw7_6HkT4};=}N9&CwYF)Dv_1629}im-3r5$>2NB zN@kNmm01DW6=0<7yp*MZT!d<4XOLl)I`h|Xn}%#H@{CX63Z=xl5(9KPObmUwW^%M5 z};(je+Z8^l$?0e$v|Q(5uS8-`3BS~@49Ffl~>hc&C+5Kw-@8AX7= z8XhAc{^;N)9L@k_kGvBk-2fys@6t{kWFHfitu0W0h;3}fA)KgbB0q#@x1(x&9@dR# z)|Li^C9x#*^`+tCr&9eclxd6e0i!2x*7PPho#Cv z4O0wIGyLVSw6z0tMY@E;KsL(bj+F=a{8DL&82I5@tSPEz3b;gC>?(Vn;%^shS1&Qi zk`u~5M$dEL&PpBFLv{Sr@XL`;Mctc>M|UE|jboIO_U;~uC8YG*T<}K4!|dgo>pGK> z@^DVynHw)oI;4Zy_Eqp?=7Dd1@BxFm=+*Xy4|G&sq@du3a8O#nJ*vLe7WAe9|xy?G3^kh*oYq5 zt~PAXFj<p}-YsG0>=9I=nP~f3CDEz98DXRD zsE_^cHw1$rwR&`&Z#ye`@i69yf%{q__f(}X1**ePe9yOr*7Ho31I8B7a7Ms#fr*Mr zXIDUwWjB}^`1MIBU^!I*rd-{%xJ@`_dAEA7xnxCeB1%7k-`B(F<_%)Lm56a#=}=)e z;`FGub*vl2_d!NK<32q*9HqY?doMUjK>w+(piVRX-txOSz|efBgKv1m+D4y^$Rx=r zd0V>tDjuST3*f`;PF{9YB3H^F{+LC-U`GcKe{2{}zs-0r3QFnOY9E>o-0Mi9?HCgp z|9ysn{LbtI1f;@cS&W~Nxw3vIHusNv6YX6(@{i7Gx`9;uQDu&arD6CoXR{I~n%A^D5G=jhjt-tIKtPwjX{6yE9K=qqL)VCOSnPum{~rib1rD1Y!l{D-04rm+F*|Up_v1Q zdu`DWwBFbU6`Kk8C+S-7SfTwCk~3afSy?PV3I^_sCP7aMN`kw7UsisGdr_(YR8gQS zO1k@*rQ46{7YKWpJUmiFGCmlaA*(?kqfT*)?j#wCG>1Ti zR0~~T_j=8N6sr9|2JuFq^AI6OAiD&oclfX-zFa0Feq0+;+;gWgS zSJB{5W-IO^i;wf9m?sxA0nwbl*dBE0Ld*DXh=&3MzK_p^&1f{LcQX&o2=+HJpo+ic z_8`^W{fc#?PoT~7GJGKp0*Gr|*Vvh+QF6R)uV-ha%rSOn&FflEj@hfEl{j#DeuFoc z=za!NJ|~OTwC)<*b9$p9qp~&KfO-muJNM*sW;oLT!qjOsQt-1j@2*_20I{}1BuS=6 z9K(JS@=r%HV5Zh%e1HZOSGok2mrDXN$4BW^2v!~byFmq}R{AY&-G7sh6DM}aH82pZ z7(PZZEJ9Neybss(Jc&MF&N(j6m9E^04DomQdk;`5{?B(Sk>$fg=zxT&Cvpsl`w{1a}930fY#(_NThX#A? z=P>2q%a_ji<4)7?I#=|$vrzH|72xgv`1Cc~O}Z!60TheRgsz^6CHMI6r&_-@V@_)H zEvtMBW2}WWM>gE9dOia`kYW6Sw;3C86GrUt-H-nMCf!%8O*~{~P=Q#((O)ub0?xD( zjZ8oJBes__%rwbI!jD@GFa@YSs>Tng#)RvING(k-F#4NEar@eQZCogea$l@7qWT%? z2~80jt(%$u1250?x5EGs7OCp}?J}2?!v>@vw<0QDhA4kVn!zpd31sG;KaHW9bs8Nq zhQ3-V3EZ%y6j@x!YilKd@gjHlFrAOPFaY-N%S1AiJjhsj;7%5A{`TR?St$%EFvB#% z)`WsFm;D%&Hh3Q+Yu{!bnFtcj&jG$JS8$x-ojpf+QUfpo`BXe+Ya{ju7k1EbW1b5= zTd?NXI9K|fq9rfKgi~gK+%z>5qgQqSFia#Avq>BpxtSn9%Sj(tYzdFmd+nw?y|6}C zo=2i$8z$zF!HO14oOZD%!|x{Ioo?&C3>jR}W{T?b zxE7MDH1Tx}JC6TNdi70faoU5vkI5G3@s{>r$V|23qlykIL1r@+fX1vAi>d4B;P%f$ z6om+?tW1|EP$(wtdtYELpea$u1)a@jN4aAH?53%YE~9poNWiU#TgHCl~e zB`_W$&F+lwasb_yiPL}W;BBActm8ZdeyK#LHB`ngI9ct#dNwG{$n__3#Qt9g2dCI2 z^tqZ)qNK=duVXh#Po;!}L|BZ4S3V2-W3?zg?EG2dW(g13GX=z;84#^4E#{`pUTx4c?FZCKZ|83N((hSh@8hWniv@ST_lu5R!Uje-`%@i}9!i^XkeDE-!JyC$9&SZ2A5zthY-N zV7dNn0doQS&krj;=x{eG`lKV;p;xXi0N#63Liaug6tbPIn*b&#G=)u~Y=NmyS{NVFKOl3IJ?CT6^sLB?C^gFpciYB*h=6#_K*Gb4DlBfq<5sp&L?&vPhz6;K< zzp;wUZQ;E2G^n55UH|?c4u3+~e+`ckf{%g#a(hQ@2Qw7=S2w944k| zfjRfq=te$ds}I^I6>}xcyVWM zNQjUMeduA8gc7g=;EcI zgTR@8l2s{h(s}a!+&}0y(jn@gUg|M;??)ROgc+RtUw`7B>1Rk7`bE|#oB1>;X8^X9 z@d7nk-^cxjs^D#*&Nf$}PWf7te2xIZ$MxwjK(9(Z>Y&{PtM0jLwvpcpfmFynt}K6y zw(@8SCg08Mj1f23kOIRT5@}8@C(WbX|Lj?i$8V>$QAP}a?aSfTf2={`^+6_%bL7yk zEwmYw{7pm=u90S|)etp#m=`}8SAd%4i1!?OpUDqvn=EExGe9|?7lB~;&~CoXtdL^f z@|O>P>UgSuA70RmTifi`+5a#W{I70ug{nc%xbLTv4a;)62}krJ zNZ&MMc_rp34;Ijnv|nNlxVuCTGilop8F(@HfKp^*BH$MJY1gl|CFm;H_G}%uZTLmR zds;z_!=7bL&n4O0R$4{pApG8uY|qqL!Yx_L4%C%1p)eHdjn8BD(K?kgvBMcA-Rl5= zJ;}3;Hr9t3B1u3^`b!@6Hx4x~-(Lwn&KUsqde>>E?k=+*!&>@2r=2n9+oHXHQPm!D5M{{L11- z;(6&1dc{v1q|o_JKA^LKQnGKzHKC>5CKc9eu>7*jdullla|Y&E6$GJH>d5-7Q{pMl z?wgw(-GRe$`H_DMlHO|Q^G|?wjl@#-rYh{l=s_p5#%lnFw-B7ut^8n1(`yQc-K1*C z+kCbBV}-}lxljLl-l~|KuOaVV6kb?odu4m4g;p>V%(J6p+&294)KSYs&iHhN06A_z zGR8bAnevZ~MqR+ZqoNqXbwxHvvk5VEo~@3;BP2p2_SP?6h9$(e2g$F>GbjY~K4tp$ z+w+t0I$PWY-76O(yLew7Z4f##9s@HDi-Miu=>FZ57p+TX-)^uf`wIvuJ za|^*xG;0J5vzfrL>DAcy{0NCqd~R=cq%Fe_qeBvHa+{RnHT`3e1yD6BDpt|!SVRL% z3Hfi*#SoIF;USOLd_<&z)M1HJl6QP8fCe`sa64(t4}rE>)czm=@%Yw3(`m_m4+daF zP~j2!M*_v~d@~2FF&Vv?ewebHd9cBD?uO^yclEb&wDqJ+(s(e@ZodGvl_9jL7AK`W z2!9IDNe$6HQfgnrwd{@D(I~J|(8voeYkF78P2C|VGvG|?8nm9$a=fNWUd;}c*#MCi z!P(joAStsOz&?TP-+x@jy^M7Oj0BF+;*ag-sM`Z|k>h~2v^B(wb?Z?mdRg&1TXg`b zc#(n{@_=6PD+)wh$v!SPP+&Yql#zDVKuOX%XT<%D-5F8L97r$uPs^<@t;4U8#97zn z8d;-dAf<>s4%!)D--BuEM}MK!N}04H?OW@miu)l>fY>NG3h!bp1Mx%GaHd*~(>OCw zYYIzBs{!HvGNLHy-ZSXzT`a1r?Y`NkRR(OAN7C#Ci$qNYj~*=afo5=xH;pc3S3`I} zCL^9Uz8?6gQ=MkGIgoB(ftFU2-!$IK;UYcI@J@j}=;I|qB!+|>V&n06~KN8`Mkfew9y z*PO$)-AbQ3>E@k9V|x5OACT{d@=%6zYT*6 z)~zy~Nr(Prp~HXFi?3!O`632$mnbd+_B?sGmq$}8CS?(3_ut;k`GZrj7q55>*s?H2 z#wX#Zy5QD_QDXc{{&Sh|_4MN-oxWRHwt%3Wp-KczbS9RsfHeg6B%lW-3_- zG%tsZgk)DTDqOIG>?iZGt8`>V*`Q5$xJk{ehFY6s@ z5Jz6wGx0wAnmXBSd;&?lZ^3Clc~6blD+cKSugp8T#t;XYpqV2Cw5seBMVE!zH!u)@ zf%#q@>tgo9J4VOv;HaXx->M{Q*kdf3>D5aINjp z{vLY$C=r+*|K}g&T!0OXgn{8FcUXm)&sW(`_?5fgqEMcXbq94;ZC%V9O{62p$6E%S z?10_;gDWIx<`Zo>F>e@?pV5V2afcmtL{uR|qwuLNfUM2QnI}f;>xbJ^UpKPfx2}-^ z>YqcLMHGtNTk-yWZN6^2`C46;yk;S3Rqvqn)cFVRQdMxJ;o|(-#qQr|=HtWVv&T%0 zS`5>}*KcvYwe;v$`-Bb5ZMEH&pAX4)(|og(9K+^0e2O6%(xZQfrRbVIWKD}#4sXK( z&fPKQ9HS^Ga-jB?Y#9hH$b{Jy!`(h2dh39%4PY)^uCaC&v4__=SsJX_~TdNF@57C7r z70<5y9Pvf*KYKn+3 zHUD-7A0I0dk^h~IXmNH}4W-Rj!N^Mch%w!YmoFPEz)~9v9%jb1W`(8E~R(t$Sg9OL)W6%(aZ=^E@>63r_ znV2&I)NM$JJ@T*ja^{unkN|H ziQ1bs50g*q$en{cjw2jU>H>Aq#|o1)#G-;+;rrP)5c!{OHbsMC&L9qinfOZ+<*8Y# zs>n+`Dn$V~cF6KI<^eiFoA0CZ%+>dYUM*X^4RKCQuyADKyUfHP&AWCAh!FiKO4`Quo_(X6SKCowm#uLGX_RXlb8E z7(#YuOz%jB@h}SLr6{Oo&7?yBvsCZN%O-^SfvR}=gw1X+<Px2wQq9^e}6(v*4ZP zM*O{4KolU|865M02@-5(>1WQ8>s%#l)xS}k9}JD;qj+m);jwGV8RF2o!l07)w*Q_n zzljo~{p!Yq4q#jm^|A8rP}jprFJ9vU(i~W0O4LKUi4Nu6m-=8R#8J&i;)yRlv(z<) zssW_bSs7NJlV(Pk^OEf#^$8b>^gKfLp#ssPazfe1^bY))pP62zlv<{FNzTGA0msDx;*ihAF8v zK7;LQ2nIK>n;hfPj=|E}gUtG1`?!55?C7e9h()RE{&G8#gvZm_C&O~pI`vk^c< zbo`xU`8t~zu4$>_t2u`$4G97M8IE1@qMU)Fnl*PND3t``@Tsx>S|{#$`(~zJ0M?Yp z>KJ?9X*|;i60=|f%~z6TI6faH=mP{-e}sl3|LH?T!fOlq(K^~XsHGvGrTxSM#lcj; z?k)b|k;Dqctelta{xNHc{>JRe<>i30Q6I4arCL{v#BGEmkJ=Z5E<)B%6=}$yi>Qh^ z^0;Kr-&OZjU#?i(#*%kLlB|(O#?*eXWT2$?)oC!{m0P178BfAgO^>fS$6!OBw+$Ti z)Y-jRXNO<{(K5jR`63?nH1ifg>xz-dyK#q8$PP>+sI)1wuCnD`#p0Jt_dVo^b1VYL ztPIX^**j?bj+Z#US(r8zEpgQ%fbyi*y@xO?;*qU+J%y1sTjypLe+Xd9yXVL<@=G_t!}O%r4HF zNYEeAk0x7DPK9h0)|MCeS;B<+Y2|(YP@fO4PkU+gupwX0@B}RqL`A+zM|;~JTn|bm zXUA=OSNV@@^M|w#^^RCS^oEuPmxlwS?Z}e=K*@RwxZkgfOM01e`PD7&d`vaJSs4!| znlBI^o~cv!V<};mYn7Kx*l;o&IDY~vs$T_%h-tL-OsZXS zS}iY2lAt?w>Ehp?(xw4B?By3CO^+1Pt&Va9Z(|c1kdT7)4&Mqb{|HRcR0JvH_`_f} zO_r(tSB#hkb78rKN+KaR^(SLXp^5i)>V_MJJan^MU@>fDMPC*Z0aeepZ_R2w5yPKA zke%4|wueJMe&^J6iMeZ}#?6cJd`xhAFeccpHC`W@DlClz)x9=OSe~AE<=M4;_Es-b zBQ&3`Og~_QoPc%+-KrG}e7^e8z(BKTG-fuoyb=^K|H>7nbUB7|n>XXPak=(hAOkdP z$0%w1d_esPb1Mr0bYf(=#yjU7|@~l{G$J+VUAU~*|^BW3>2DP%QG=m98Ib`;p-8PxR=gK7Y z6x(H2D^51AoMPQklItZ5=74Bq!#auN@38bFS=XP=I4VMkeznJ3mW2h&g^iv6F6Q1~ z!@;!GaTB|D+{SVDvai7ucK1EEq<{X^K7xrgs4y`{9*akCjeW5?#ln8ewnm}iDkW#Y z$EcLU9k0ji<$*~?v3?QMz(13!OigYLSSyLV&vo1z*D;{>-g@C+9npgZ2p0Y3|mS4Eh%ecdG9?j?+~(VhX2@imR8Dx zGerv?xWB(98!GL%a+e`8twGfIrj72lj0D3BA)2u&UJ~XjcKV?tpIu3Rzgb-zyT96C zrTQUpriC1<69WV7_7L9%ial$*+0q~OFuP%t+giy-ose83Pdz3Eo+Ym6kR7?MU9^_u zk2g^dY!!8`In*1SRu7>VxB>vvH^HRW@a%x+Rqw!O$s4!}{v%=rgBR~uE zA@{VJOSDO*dlFbjdI-h`4yeWj08>@opCLl5Joa2LH@515VVF6OL5 zjKIEJ#9%ur9OUJ?dZ18nIXaSIQI8yYl$_ZDd6wf6p>}L8&10=OSt|jb zrk9I&XFqXQQoM!p)XOwce&(!)PD7#entW z={Fs%a2%5!$F`iT^Y82J|HrKJ$3Z9kY;!zio&U7Dd)Tjj@C?rf_(Iql>{nahr+wD@ zf6R7&A53=H@^7c=QMQfNTTk#>11Oi2d6!u)Xx~Z0Ki_KE*{|2Qd7EjLnm203UCPU| z%*zN4>rq6H)%?rspRUcTC!5pikljJt6+}EyvqWgZ)^CFywZZrWK?pEMAUI$=7$4og zUmdbNCTDRadf2Ujz;bDZuY{80$Nn*T5#r^cmy#UjQ=Q(sUrl!r5+e|(71V@P2SOR=iU9VD_5X4`S0yV5Tn+;CHk=yIs}ErC6#^g{ zMCpTSo8yOg`~PUIU%j_}5*D95`n}emIs)8ccK{V3%c4nRZVdcZtY=}unId>UW2GA& z|97Az*rRD3hkxL@A_PFuhS058+e*@3I-tb}UQUIE(f|NJ07*naRKN$x8+?nX;g*w@ z#Ik8SI<1tcrKIMY2@c=|#$BX&U6ynDg>Z(B%6*<}m%VWD>fq`j0ES+LB|*TB{j%9F z%g=Xwug!B-(R@2*Sq@0AcOaVPpfukW2AFqik6#Db3_&)(LjHdvUO0%fB*Z!$h;}qF zh2n?cg6NI)Nif>;Dc-HQW{#6IE2KK6Ml)T61&Rr-KZw*t?psU(BKv~oael|TQO#?A z0F!$Ffpda}S4MvTk$pt@AF}uOXRJlmA^^7U`YU>oH!ONigNK9BfcjELd4q~?ro-Go^mLJ&X3wEwpr?o^NVG22DMqj_fyF+bfu zsKyUJs)paiE4$9QB*2@t5AV+Du*K<~VBGz|?RHx&1waDLV+gSTfO3<{$)Q>fE0kBU+L|ie$_pEjJN;a4zK_AvmTf1u{`3#2?9o)sX#V9nYvP5j{BH#m$Nd@GXJIg zs54lUdtMQ)+q@mur_~`I-z^)W1s=liKc~?} z6Gx!^onjU~$I;*5z4t>?Jl8}#m_u-jLV&%yAqcB}bQtO}lSe$2L}2;}CIy4rX+tu}^i>(%30QDpO|AoLxl%MLb1JCw%B z#ycacoyCpJJ!g9WWZv|0b@#RQ0NMKizqxgzqJTay{bBbDwhsENdd{v6_Ja|U;sFj{ zPj+{zfAYOws7~*bAIJ`H=UVFJB#BF$7u^)fGQ^^|)6-z|QSp%hc-}NHXW` zkY!$XKJWcT2cyCB9{UWhx7@tZa}MatLs3^hApS1#ZxR0?@t24f48GRD<3XZ1rpug9 z_j1ywYN2hXP;xT}8g2^#ffq&8c z|6jZ1pX)mz>|PK6*nTo=Y5sq?FSuQI2h+w-aw$bdxm$>a&bpcdQZ>Bc1AvJcfl2A_ zx9c;OUK_ih(V?EP0b}gbj+yp+q(G34h8KHxj?f1{y@45p%)ZP+Fo>RO82=ZT!KHuE z1zs3~koyD#iDR*yXY6T>6U%cH2*CWWBb3`5VfH^k`>&^ej@9t%>~EKG+GAb&7OA>_ zM6NtdKP9QHFI6l@;x~l?g~2aJMYHSm3JcEeD|c8j4i>PS(LO4)zLd%S85Ia9B4ATj zwhEnBhnRyuWf{PU0swIULV;?N@6tC0ntmv3a0B=w1OS`W1j~RK)*N-<3+D#TqwR|A z;zC30_{sT%?`h}#ygcQ75W#Ui<{bMGLIq$m2WfZo0f0GEJ>mNqt}Zu;^$F1i1y1kA zZvy0XzQ+D%$a|twa$I_cy`cP+eq!ITKe(-9pH^1@AeTUoWk;CJYS?4z&TZ0d*Zmg( zK#g!<%6P3cfy(7NzS0nFRdj+x+S2e_H_nQ6EqG0nqWEy8*Zy z)DUzb*Ef`Elr8%wN2v5M7?dwSI3T7^UjUBXkPu`o!F89bu!?i1G#k#MftP zUVg&ZOk#1~@;pa2&UxIvrk(eicJSH^`RSQv`6|6;2rzT5!V)212mh)u+a3UUUArvr zH*J?Yn4o$V1JZkQa9VD3Kxh6J$h$4z2rGbpll<=!FC0RW>D?lytd+!85bbH+BuZA> z5AupHvnqzXp&VW3ZviOpBO?km6o7QX1FY-8<}e;pmnU#egIFgG*OOWMm?XTJkhRV< z3UBm>nq*~y`{F>e_0&MRmL2Pc;&@ELSOVX*z3cqaDzqJn+A!xGhL?Xm{UZPfPyd|2 z4?qPWAKw1ez!?J+{HT?azrh662^=cc&RqrV* zt|FD`XN(0?TnIp$z&Hg*$*}vEEWZqWVe`+*=3M7_yt0t;2VV2I2n8_Z=e&%c$1?lg zFWYbI>oAn^A%yb)O|VM0cw%5oge@!7v7c$TQ;m8rXd);k<*&YwQoyJpu%>JJ57=28d9po{}O!slx#v*D#I? z__@z{sd-GKKEmVM5Uh*Qu9B&FgZ(JKx0RMwj|=?yir|$#!CymZ_eJ}I%SsCu>k+L1 zwDuT)>-xlj#|%S#KIkM?CxBy?dyHM`fpte%e<%oGd01F?C=h;^=7a*Y)$c8YKn~wb z>3Ko3NxP}}m-*jD5TK)HxBAohpN#){METl+0&-+T!LojQX;hq_2DeAb*a^#kWd0+S zdd};vq=J6}x=#$F&P$%aynKSuyudM<&tp?-ZE7%|F^@B~JVRd7F3WT6^y|*IuU+LY z34xUW;F18m;O%yDhkd3##sMW&W61I>^V-aN&b(#Dg2B$xyw-A`=U_H9=76@{b@uW9 zfB=4o5a7Qj|L2KU7ObQpb_dW2AQV_Pi5N6BsK4TTT-RJ|#cPOCKg;|wg71->PV+Av z!sz848V4z{f&r`p0Gm?d9T<_I=ecK&6k`g))-hmH{bf}574M)1Q8DV?n8gOu8q7aU zF4GZq+2#D4w(!rjxH9`)%wW-HhqFITc_rv-iMe3<=_;D?hKWDSSWZ%}sL4B3Ed2BX z5W*9gf0xU-DI$zN#6<8cl&Fk^nke+{vO4av0e!xcdu+E86E)||YhqoG5R2enVvaMm zD02yb+xuzqucn{v{Az(VgW(U2KTLl(3ZpE5Dt-Wv(bq&0 z&+!gV@6qTwzEn798*Vig95RKml!G#ThNK{8(Y{R^+qO1uMzU`l6u2oQ(ux45Ss_GX z?AGqo0WJ@iAPk+mV+YL;uarwLYxgqv{$&RHM+Wmo$C3@vq%n3Vcc&KHIM(XZLVk}k zq;2TME)TFjv_t#xrS-kC=_jO~w{O_iC#-!w!Bl!gKP&x7Z~v6z(_zrvLg>T#fBPOV z8?&~5g2(@bzXsbpEINR_Ry)C{v}>};uOM)J5O4+08hABj?)G(={vQ2W+HI4*tEOM( z-@KZCX*@?uj+l1(;<&lKdM}?uATR+Es)Hy32cfIk? z{~+z(+$AsI%jFeX7$}b0SSj=EYkY*&@|&Pzf7;A0EHB9q#I=;*K}%YCo;iFY=)2A!PGi4)iS<9lOw04EDPN2zO@ zqT%X6H12?i@1XT4X0tFdP~Bp`F+vP>>24YUh9_I%n(O+d#|Puj%cT}WyGZTS{L662 zyyADkZ2)Vx0`!jn(R$V%Dig=h?Q}I?w|So`R4M!XDx}CMzIj z`(}fEsZwuwfiM+@!b^rtUjXJYgzm6Tx`UcFEC8IlfkTI762$@lkU)tnn2NU?3{m}; z_3Ng)IZ(sHx}6_zxd*$Nf0_T;fH8zKHqEbVw6SwM*v}?AIE6dF8`C}D3B$m8_Sp7s zhcbi$vF1Na|3Pn|@h1&DVolz%&KBblLX%}TVdjs|lMv3u@hP^{IOH7BpT^|100g#_15j&v2h0`j=ZkKYKMlbvBVxl(RW1C=6j;21!D5rS} z!_Ren#(Z4weV!xLmgNL%44J}mEWR0Mm;89AwY~f5gDy%~Uot`PsIaa_Utf@DBGoXT-f+D6#CbwIJD| zFZJ$np1#9!gc`5k`kI+fV4=r+<-q$mt>BZ$r^ThOdfkEzPH5T?y& zU*^j(18sD0chjU{s#hljkdIUtFVH= z1t4JWG9qGz!N<=BkzpNi7aUdM1o~|pO8_+e*UNtonsbA`%*cN!33FY&Hix^<&%71r zg2Ot}$Bn0diH9!u%pCwC^*m*c@w2&*hs4*LUMQ%^_)nTU-y{7FQPF4$01^v{CbG=D zRex3FRGCg%*H~uAPtLTIe);$7&VTuiRmr6wz|6S{Hv|DYd*Xw{I}S4OSPlfsvyALw z)LWJT5+<(kTBCzEpXakYPTZKO_gMbNh`#}|KEMj#Pm}+f#0v(hoVAW8h}=NWcrabZ zkx8vaMv4X|)wSndEE3K#ky{+gc=nBr+kB_{zizX&o9q62Z0k0IxsR>3 zFejB5`Xd{s)k8EP&zVGY1~}yWA&&FDVEytD+fDg3MW*~3FT9RRgq3FMp{Z8eNM7&a z>;O;?j)^z|BvwR^C+j$GLcsB3R(u_yo!j8s)|hZ6X#G$3_o|bRKB*>b=``nfp}kW8 zunS?WhAo-2{1yqmCA3w(?&?$fZmaVuNKtTd!q$mTKLu{bFlj8Gz!_GB=l|}5!)kpS zLIQrH3p3@m_3nVt-KGzVQFA0-eMN8ViQtE`@og3m#WIp3m_WV#J8Wh484t4ojO@uS z9{=xhjF1d3_VZeu%svdpx2pL^KL@ze>>tL^zJ=qsU>?&%-2P<0lDT^u`z=?dXeY?a?1pYo1rY#QOdjIHf=7;du0 z6CD0&@-M#dxUA%0c@X{mnEpOyiO^g%9FF~D?rSVMYVm}Y9ijE7Tzmn8UgIQAr+*6} zfW3Lqwmjo&Lvsz^5Cbj8tbzudMb`T`AG`rwrln4VRXt=Rl zP&UxTN5R@I<5g32f?!&Nc79QKg&D_BOJbaie(ip&lIF-9S$JP|&Y0?$c2GUT*{ELm z#|VYW){m|Z#vcR-r?3ZE=_1sT#ph{+qUG0`V}uZ4P`jFc9A`(iC!lA0q@9zW;3m#rRs+S}f-S+uO0MkSD7Xby)qZ zAaJ!1P~#7_fw`Yo_h9JVy$K8hEmu`{q2Y|*#@XLT?C!M3QY8hax!vF1`j9QEC4Y-> zEW2tMFW1v`^Bq#TnOFMQh4$*M?IJrn02P8K73hJJ!qFeJb626N=i*5m zy;1nn()`@v1LOe&M$F(%-s6l}-cHRM4Vlkl%dDO;%ktQBS!UjHL#E|u^}93(*yC1V z`4F(fzs~4Af1Sq;ATYur9^dx&p=&L{S5JUh<}^-e-r;z;spYa z^~p`>NR5Kf)*$#S4zff|49ry*!nmHJnVGYN8Vti63MecF;%mJc1P5`~dR#vC%2W4! zg@g^suoJ`#q--^M>;SL{aizBWyLgVh&$%O_+XJ3JsDI9M(}!s9L%_NW;Ko8QW;C(u z)fE7!v6k^byI2j4Cq)o2go%}r<#+-OE+g;-9_yd)(nbgYy0nv9IZg2PfBNvlYI=w5 z*j$UP6E+EMO+8(o9j4k&NUbiIlhcg>;gT=5!IPQrQDH&R2vLqOkU4o4RsbEg59(~d z#NB6Ci%l#=pmo>ukpLDArb6%k5YDj$;3cbc+injAKPv^i=4d9}+HZQo$Yz^0g#oU) zR@*;i&$r3(PBnaVpJT`}*Z4!s)SC#E_Pz&`_Vds_bVABd!_vpd;|adn))FA3Dh)1S zTrC*HeED0FHhri=-|0MK7Y?`LbO!(}0Cf5X}kov z^`3KVbD!yy@oyT@GNSLApxvLK4bI~^)b|AEegg!A6Ltv+0YET)JWD5Vwqf828A0Fe zJ9w^)y6=s8CeD0=HjZ2TG5XA=FW8q{R- zg@9c&PE>03vx2~tLckuzFlK3HUEPD3H!5OAhK0rEsJhDz03Wi|--nwg)h^3hwiq`m zcwG0tg(U#JnI4)WW|_UUyi;HV%?rNnqEuPiKpUea0LLBhW%2Y6URS`^;7{)xJ15Esu1H$uJMs_i?T4u;=^Euwkn3Np!p&^}**>uvAWYfd7_;K;94i1kowHL95jemM1&E+N-bvaw2V=fpo?bd3X{b@Wg?ZY%4ZLu923_qs-HQN6$@!!EB;NSxU0N)0dl!XaJ)33}M z)grcun|A(M8~utOE*=9I9RzPO|DD6nix5cx0R5^1;{S!1= z;-3u&!kG*>u@6Ii3}fAAjLyKVvxU}GhTD!PV+|}DMm(795T<0geU!Y12c^%(wILMn zJ{Wwp_NEO(r(?a^E&F)>T;V|AfHM9SI80&o=4z-UP>tdQ(xMS=jxFOqesXZcaSPsW z+QvSo{S2)NVh0Im*}VtUfjYVDsiQyx0RDTSYwQ6=f zS;vuM$ka$37SUPS2r3Vu8Ulb3)<`F4?vLsLx530TvyNf_XCMUtiUSyd@#jkaqT^Q> zph>?1fC=J*K0<`&Z0P7-4sP{_^G4eErwHPH(%Y#HcQ@Ge1!0rc99!IbABO+odsuYb z0lvUEgi7=W#^`jPa+!axjdrEZ)FK2;i(|`HVFiJ!hk(qxJzh`$YX9#MwFYoGfJ-*- z#Fl?UECKom0LH=eJI1?QQ=$qc<5_6u&q}W*=P=Lbn~wlK(n_|A0CSDGPqY7G1zPg6_2&7~i$ffFwT4yh9GmIeU1V_3@uh+;CYARlD-%nFw+ehhpj3DzMPIei5Y(f@21_bRH4xO zB7(_CJI&I7@?6eEyU>1^eTVmcJ9r8V5CDWZzXE`4H(nDj@_3np!0r;?VO{KBj#Z~M zXF4?RU11&C_f#wyYabbUvdW$*{}Fr>A~dewP3k z6a*mJh`cjsxlY#KUZgbuPW<>CAqFVh`HkY50dv@xHa(?Hk7-B!!RX*|>U=;y>EHym zgTSd`d%uN02L(+CkmovfBrSrccVxT<1Xn+A3k2+S(qE2r=`orA5_R~eFre}H53bY! zpdqjT*LmMf_gd-R(BwlrC|uRAi#Xgh|B5$4u;)31!$E?@7hLM+FG}M#Pmtypfe09} zPCFHuSSCg?-;Pt10(?lkT=2=%MnsmCON6I{b4{Y3 zt-v&!jteE2=McYY&K7rEt_rVnw{Opo`C#Zca0|dKq{%J~Kz2<1^wRCNGHc;zW{-(R zn%i9ig5KvrdeU}@C;v+dzKkZ9S#6k$N~dEwuCrXCT@8*JL62jrHJC3oerSHqJa@~K z5mTG!_vXx#fQfFjq|aK$YogBq6X9ZuMI$m7(hpe)%X|zRjVuG{u3Fm!Xotpi}{jEBByzJl@ zEkpt%)sJD|tMOM*so8&5e9ARtCje9LC^f&LVfGm>_$$qKC%wOJ{oMOD-8*j^7!V_yhRPaj_X1IP)z^bUM$QkB-~^MBIpU`?bM@qncS6222Pm90^r3*Z(5`z*~0i z0^kUW^~0sJl=W)BrUg&`^Ue2g8c9_99|8dSmTUZFhJ&G`Pi7yJseEgJ_9`IT4`9l$bkO--2;{V; zaeN}2n=>Zs{vnR)_SmToe<<<&Fm}LZf&gF+Y}f=4Sh^+~oWnAmIojBov{rBu0ueYNl!TJl#}JyGVTfUeBN2i^f|X+=sBlVh76w98a*fONCq&=qK`M% z#57`uHySc6M@#v&KGs{|ia0EAq2n2*c1E1wwSJD1K>g3qr)8DrIs_acY#tOGskyz6 zQJts^#H;+=FMZCNe4gVeLyRq|#8MfB4&gY{Sr?Qur%QxDja@OqH-_7kL zegN~o$Lb@Tw;~Ww^Pe;78rNB+A^<4pOY5}>f@!BvU#mkvtpHA8{Ezs+e#I^?{EZMK z>C0hshvPd%08lTiz#OmiTj8lt#dux-@Fn2n$F9;91g-`G_H830BA9zdc%V70GPjBQ zX!iGE_zzh3zt>o6?vdZ6Y%~02sJ0Qimcf`Qk6CU2nP}ecR<4fL_$Zcp>EutGFW%PN zU!)U^f8tncPSpc9U9QG|9NJz2+X_hQi+wz9N6Q+lBxZ`3=RG!WXs}tNFUyy!&VIc& zLurWe49oI3&#%%YLLjEPCBARrE54 zTFwk#{UY(VKotKFA;4cJ|L+km5wg1NROAP;!&I}2j7*N4&)Xal`>gSch>k2wDX zq764+Ap}sdbfqDmw@At808ov8ABTV8u�b7t9923kmx@m@yd;tpfDYy~}o855H4Y z_dYI6zt>1WYZ0IjU_tQNbqqi!CZ%%pPW&eGAHEZ$!hxgQ@Aw3*EROy0W=Xxd293DJZfXA+#UHxqW5M4-6sF94J*k~rjB5w01gED@^X@me_ z>Mxk^Qa`V8N;mlgkiqcN=P|(KA*@knT+h~7>%aTGQidio`V&sB5N&uG6c;PpgXTEO_e;NWcga9!52%2K+Q?~vaV*${eAgt5k32sf&&o!a*ZjXMX zi#LU(uJ`YDaY%3TK|V*;pfFS#!R2$xoE! z_2oUaLWU3uTAt^87UY9Ot97}_pwJ_57lKU3FZT6@|bZm zAF_nwnAwA<*M9{M^9f@K=b5u9{tLDlA6@Fd&3MAc%*5Rw?tH>Bk^9w?8A1U5y7ZN% zN{v8+D)|lyO=2ep+GMfA1Enru8^J7{BFuJ6Kdl2ou*7vo`*`)=+YT#}@c&?60{_>n z^SA#ltahTUZGYRGXkS=`6$Gvk0`@S6A+|Bq0sVHDeyh3v4gxM6`+bOI-X|L;)kpZ} z*`sgwbOuPeP29zI(>i@VJpOafS!n0aO0O#yLsLz^YyEXl%J@+v5dr~laTnSvEWyC1 zI{#Dq?_ky$;1!Lrzb;MReBUpUI#DO1Zwh8wF#90T$OkHE^5@GEfR>xjNH#(q=XF`W zN^cniRsw*VZx9EGBmR79%^YA!UFG>#m3e*pTCX?e;Pt%k@frucsprfWj8j!VL;gp^ z=fpop{8eH@rIUNp03s9bx}GWC;QbH|Q3*YOlT!jZZ`P+vC~N*dCv}H_sQsJ1^NOwy zsWB6d=4AIbj^T|o>zBz_^A93N`aFg4-=%B_(mpYg{{rEKLIQUS5UaX|_gaGlukdq? zv0nal}-%vf^5qe+j$yzt8q-5XUYB@EVCa8UNVAi&Rxuo5*YD zul1vr^>8|;jwlq0xEH(d5|&foN9=Z<0FEypvOfbZhfLHs0E9p@h=G_V)?8gVh| z98o!vmh}l&^&ZD5pB`F%9r~5di-r`i0Gjbn&=!IfYULz!sT!?C&30?ko$r!9grSnK zL0iapt`Pvtd+#Fv_%5&keQ4!l-;#;UB_|R$#s~oI>WH1Ig2?5b6U;Wk&4c$CTP%xE z7-!!K$0w}LrmxLEIxWJ05JWlDWbD|EuOR}>JN{gsA4>s%q2B*x>=v*KILe4O9nU20 z1KtamMj^%GVV)=B?lU}&Ys)>s{CV6eTU=-RWr)XdFTw;~5|`(xk~Z&qvGDqi{7z}w z6kIZgDAB5i4px>_;K*}6!6s{nwbKOQ9?ZdP_LMf@J_Q2!N{HP7?4oRmS0g8IO;=Z^ zo>E9{kO+q6nB1!aQx_$A4_?2ebbX%ksXvbzFUn5MUo=P1){m2IJ4xfLZ~N7IwSTp^T7=*XJU4 zhG1`EmKLi{wVuMVx z#vVK9q<{?VV+V4t81R21v(U0e+eM-y~i?=vFpcPqE)TdG)bD=gdw);B@kK;jo%GAo# zy9OB((H}IHv%>iAKV1VG7LgHzLjWN2KY2ot z3Twbr1B06N!L#mtnEekC0?>ybaDowA!v{bQP3GNCC{qAH3}zHSDO9pQ+OOJutDS$X z+TQYuWUgVZYR8ru^oA)dwHBWc8)3kUUjpU}hPD~tkqE0I1Tf{`40ge=wT=@poQH3` zBpwE~C}}*$@;GdjWj5|-PP?c&fuwtT1Nm=7B{3 zoGu_l7=v)P+d;4k{A%#~ym62yD($efr>6R)kMbDdVSIye9;k&|f}G~SD(N7T#rTXT zEdVgWKS2-_%W9}6-!O+cs5U;}T?l8pE(2lqp}mhb_p4L43bP+&`^R8)fI3ipLDrXw zI>t2J_u3eD^h5Bv%TDGlApuq)91z$0UUqqyv5X|PjTDyN7b)jo#pp*p{J>RMLE!oz z;INZ0l@4=_|2`3q6)^V-0H)PF9Hzd9b>>5s>1q0}_FslyPyZX7(~2{cIoDUkuYWRQ zN%Q_LxXJC77bgGGxd z_9O|A{Nk&5^M#(GVhz&U3I|Xnp7pZ4$po{-f>NE%2<|bddCk)jpci`K8{bskAB=2h z7^!P&vIDjPn;NCo&*#g4xo+4c0TPNCJ?FIz(b&vDmcF|oz{iiwSQ9&>5u@FiCm|}- z8paL);ebsr(T{T!nZC`T=|W8hFW5z_L03{f5}y6xnb?U86J{bz4BQEq!&FRNrwrq7 z)CvGSWz``?I95!D>1aFs{G9AXZ8DOtb_d>k^2fp2pMPPV72=*@p?i2JcjJ@n= zFJs2ubgcSPVgJ&X`{K7TG@U77Av0`Hqvn=?vJZ1o*3SoS>i>UN0v-Gv=h;C zNnuH28^M@xN|@y_r@l7iwWh@6*<(!co>)$!FwL=~uqZU}Fyac*Tn0ehWz;7y=x(`K zaCmEW5x?trCLYWS>?euqUH)Nz378a|9?y?0BOQ-i8)K1k!Th(LAN|d*^LfNoSV7>1 zAz&|b>P7w@CaI>Z)*+&JL4l-~|E(ql!%w-aG?(0b2s}VdP$Dtt&LU$~I@q$HhpBB_ zS#|{#|9d>+Z#B>P8B%Hc#Bgl^fS9g*++eI1FkqIMdVPj0&$2xBe3qHF+;BcErK{f? zfxwrkk{hYU>ZNZ00SAzn#K9%@@c4Y*^Oi%tN66H2gZFul<>oEVyvM&t{Hc;dG*y3+ zJa*+*6AEqS>l$PSfl{_P0a+^%)%-OGHzcKj9Jv%i2OUYI@mWdWT}_p~_9+Q8FLZKo zV%cEQad!Z{&#qHHJugqF`wmEc7n9CC>MkHR_)Z&Q>XHD6DOL!?vCq0t@L@h7QnEfU znO7PA&}74{nHs!KMqllb2NHB@C3XB4l4poS;hcnCrr!I`hX!`SEu1F;H}k5!;dI@A zt%GJT2ns;t_Gx7cHDGAtmTr8zp=A4K$UJHI*~sZRy!iXcm;?`qdL(BnKQY9Nve^^} zXxhIeB=~T*3ERY)a1$$%9`@4qCD%5}xGaQAG9WEDSqI_uO$?5y*Bw`RU8ce-^50b8 zy+(&g&}9G4WAU1n0s1!BrjOd8Wr$_0*BRrR$C$v=kC|^UcniVw43qlU_=6QxHQM>I z1i-n8yIJuWHRz z`H~=D&yKE2f0o%d$mkC9^UkiW(^3q>B&|hx%r^{4kt}<6MOG$M#k65JT ziP!hLKtGJx!pIleFBDx^<#bfSm}ZpTWjq#(FY1*QzPc*@N$O#>Kq^7gOXFu0E4A}^ zoT=wB?=y@ZzbenEIA^*FZwUnGk*jb^AmG3f1)NWNMdacnx z?Q<+MZ<)uYN&w9pp%h{%z~2RdJVOZZs~rCg;-!NKKIj!PGW<38NiJ1mi(pll5ly4{L>!O>2xRsV0?gPKYzl)i8_;Jc)3g6|r z&HaI%IA{90;Z3f6-Dlp4>x5A&i0cCXLI3K6(PR5%aQLjhUmMV`51E7T#n4gU2QHoB zka0vj8Wm>Wc}W`DbQ65wey=zYEOd4Au6%8#YV?f?07j0N=2%oSWL^Jgi`fFUhOrV$ z%M<{h@vk>A{oi6tty@>d6Z1*naL1G1(YE5U4IRt~B+4MBzE3w*2W3IfZ5fZfkXk6dW>J=UVq_5b_OQ^ni=xa2YKSM$Gv5MT>oz>= zW6QsWo-E@tsVyF~q!3Cg=e@x92m*X>94lmmu0{A5%UosrDGyPgvn*4~bKteFwLD{ifjsC;l(Q|A_dn z5HBAkG&q3q@31Y}nB(o~b~Qjq&_{@&BS3sjQ+EUcR2%ZLe8-!9g5Pd4 zh7GB3;ZWvPo9qcs9vrdJGmEuPG1!oim1x|9LED9}+(Xk9W~69_+=|V(iy$CPLPHSX z^KJf&9>2rE&Lo@$F#I}C9Gw(PfEq_(ESu|Y_2FyLEwlST{3gARu%LE-dV~PV2VwYi z0$AVuS^5xti(Ng`tcGJa``IQ8Ojz#hxmyOY_{c0HgxdJn- zXc#xHV4hX?u@-wTc4w(Ks259TYP^fi_J1BHfZxLxfC2#O?OJ}G+Hq+>GVSFpP1Ewd zA;I&o>0?$R`dqoUj5iADC*d40gab`qim}K!-;+|!Rex$=yGoV~0ehvhi?fVt{XOpK zUkN(uJv9B_!5Q<%c>O;>@vV!jy;_HLD#Nr>_+USC4l2p=3hF^{MCiuhVK)ln*V%R0xeT6 z2_SmCG0QV=YG?yG%i866KGV2q^>ecju$QjF+XVp!kT@>Wti8t$yu>8!V+XqT7&7%* z^Lfs^$e^A6633q*Nz@_WpCJE;c*#&0CrzK!ew5l$Ro1V|^lJjy0r~5kN$#Yk+}#0! zX;#Y(LFR`oH3*R=IH{~N`Rst$wFKB_@^Q);A^a z48Mf2aR+TvXqP|(!aKt^g$R^*7JlxSaPkD$9TrOfG=de{!L=T(x5sYmF#cT~{^|S= z+r;jUf&hTk0$GCYHmAWWuw+EXWB)&U?-?uGk{#yl?sK|NyzzwzZz6|5q&W;`7^Yzm zC<>+}5&{ehh6RbVBp5Q_A2ck`HsBwEei<|%@Q(o-21o)95d2F4f+1=s&=#p+OBO{K z4w5+>lEaDby}9Y+?)LYs+N)39e&^nI@4J2agj;n^b;Vt~YVEyig<7?0@`!Kj9)dTI z{)17O!l0ZyLUZNbO$?>qB99eGt&?+1k$!sj8(~ghT0Ff&tNyXA1TCGN5AdG3`Y$5` zP=err@R8y29gB4R0afwK46J4JErtr?_dM@OTyqwT$a_NeJ21i1`tB5BJBHWJ38M-~ zZhP7wEuKMmRrdcgcY;r5hp(_2j~2@wLQn+DAxK5YJUGPI=iXPl;RCeMFa+w{D)ZmL zbgXS2Ap}q}pa=wnW8AL4#XPP6KpO*Yso|TN68A_#w_!~;F`Bvik#2h9qkLD~8{>YV z^6wU#8z1YYJMZtmC%+xOBW@Cw`GZ;LZ|H~o4wnx$F5$BNrJKWpwDI)$GLaQ^qrTSO!5VCzoOX9$`bDwZgs$?x4nBTkwAX!Pe80QR;>$J*FRJ{z0JDn` zKtq>WLJNTFoZ#lKexz6NBW>%d{um`2HH{pBc_Wl}Wd0QbY@?t6z2$v; ze}cB15J1+QG`uu^GWv^QlB0&!(`Vc^jOT>2n5HOPU7mR@yaEvL4Q=jnLBNm6`EW6` zmwt>%PG)(Xm)B*Ub@V#(bf%5#t?vh)^KTuu-1kHEq2FLa`6@zyzd-!I#lN8AcJc3& zU%Dre91`1LB2brNMZ}WT z!v?_X<^2h!g)$keEj3Gczm$mhF6n~FATF?0Plc5}T$bM$zu(s~+!=EQ&of+x&vKjR zsrxMLU79)z@QJyN&N=6){vIzrgGcD6)%_4UAMov?{*USw6}16^*301`0s!7=PXZAA zFxL;z;!seww!vJW1_1MW+|3_+O~Z%E{|OfUvAuor2n=wnu}r=PSMqnzsKKiL6fJ;m z4dJY|Gvd@0z9(&JY#eBVSh8Ci8n*IF-P%HQ0fK!Z~e;6uV2ikPLx%3 zTeLx7g%I%dlm3%N;wuTx74b8h*QfYdw}T+SWBzWgAL0)}C}90DIC=vC-Q3zg*Pp)K z7ckK=5E=SHuQKNt2RBAqrr$Y9n!r&Fuoz}}3ojS~yrIoqK?wLkIb+nJ!|>ztgEv1v#GF}7 z8~3Bv)#W)!7@F@yp|k$`@E^hd9{!i`{~`X{@h|9T+SbcY{DwV%kf0W3!ejKx0Qq$_ zBnY9n=mqcnY?m+I$+R9)Fd`ZQoUtNoAJqmp!JPCC#NsvxNrdJ0hAH_@^;)ZC1j}*W zFqU(PWax^&M~$h{t{}jCG!=qCl$ewVPUC;B_6tu}X@f{+RDpn&)4eOxN(xfuMgU<1 zv<1M5g3LhJ0D#z6lYJmP?*4zj5Fe!BWp%zEi!R<7G7WiEJmzc)<6i^-<<*%UApl_i z|74G2!8k5$HgV9b?#B^-GAAAxNm_8wdzuU$yVl;uo{niI+6p;If(rzxetE z+yjr^Yu5bRt?keWDlX*BX9uU)l31vNQQuw{+n)dgV7)M0)Wt}p=>1c-+x~U zETVDR)3tY~z@hzKYY6x`Azu%ANkM=oEx8Rqzk?>gj_Ut-wF0EP*3=XTTFZr*UMP1_ z5Q=Y<&PV8kPYOx|;(m)(eyMLsnqAtRnJ7GySTf7XPr7U-rN;|K>Ze8kuJX!-Sh)7w>UT@=`j7hmWs6hpKTujgqOR%+QL5)Z&OVNG)DqRv+CK;u?$s z0N8X~!a+^t`lv?Nbn7o;}eU_qz1v88=K< z$IUZcd-J>|UDjU=v%H0u00Lm3=B@|?{E%|mI4kbQCn=Jlb@GEWUuRzJE%)QsW!u)x z`Z?eFo_r_%A2Pvw2_e9LK>WYLFU>h|s+Q?wxdy>hIu2{k>MV+vtgd5af3lfVXn$XZ z;x++RzGGE>X}x*(hUjfn5@^O)=LvPRZB$8bdBha%Xm$khTJH|o-*6A)^#DP@dYlZf zMp>~1Fd@80xtkpvb7?g$Kl?|FqnBV5^SDyvimWRBx8KiAVP1Do%eFNM&buFABb{p6 zXaGovDkum+0FO9As^*hF`;ONmHwb)SBF8I~1vGnpIromez8L+Rya}<6CqC>j0LTi% zaENtq_WQ<302~1rhW`Yc`2CW@EQZOp6JEhs?GHv@rXS1XCwo{T-``-@1FQT91g6Js zx7kEn<&|!_{XteZu^BXlaq;YQ85T81JUPN6%6!*y>&RStkVAl)@ex{*%lX7s4- zH{bXBeSg>4^*n#?`h1=f_qoq~Ue`f+muMKh(EG_BZ(cE_1#E}R?`jB}z%&DDaUS8z zC#pSN|K(_E!CWs;=$Mt}Tr~-kyPE^>@?71WRPICWLJldc2%w5~;n2rHA**lw^)z_V zYKgT~ZNp&r^vrp34a{ul;aS_LSB=aqYcyL$_BJZekt0^wCGU6R@9XQqTLvQlaTTJX z3YMsUlY*mt{x(y1uPUiisQt}=mA&rqXgcZ4!~C6;e4Z_+O~>etvD!()3Nj;+!I`|U z2z%R{;LIW!Qz=&7biKTfx#DWnd8=W^UB^k!$;$h=!WapKYH;}t@5g(Q;KBNH4B#fz{Zavsg!T`5}ur5$3f`}rV^TkouH^zmk#oM%$Ba1 zLUKvM!^G1br4>DT@{+mZ^4_$3r1&=eU9b3fDsXqi$CW%NIkCv7s5Z}XSN!L!sR|w5 zi@b_BYVXLKY+7-7tzQ6Xj}JdYoZUnz5_Y155bPKSd+$6U?UW5nh~?+5bFVuJy~^X9 z^fy~>8I2sy7GJ10tl|V6-~gjk^{!pc)P0AuM>0f3(!Fo+`)ewYn?&PPCTYz z(kB#6zOezFpG?f8Gly!P`Px6+I~m@(+|EdYAY5^@(U`u9VlF4XfYAYIGx)D(> z@T;cWDa~am>dE zC47c|dVcW&yzTh&s1KL8r9$D=-D{^^`%$)atEkgxA-7%~77Ckk1ndk)bFc}69DK&K6N9&hUUU z9g#3D_X_TE83I|Ap&ts?D%YN>>la2U=A^V~9HkPD4W%+TR;+3N2tPaZtm>3e zpSOm7^d)FQ8B_cg8f99Q->;?E4HfXHmLN#o_&M39OHrf9kgR?BEM6xlK-HsR72!1mjCApJ?P10E^O(DVY+myt^ad*) z{8$FREN-^vh7~ke-cg!C=I;uZ#H9|+*SNOx+>T>@0eSbBm4|#VnFVO%1kzBZOh*)M z>N6bFwet-J*BepPd_D;JFFf6hvd;S1sm5i|4Lo1k@e@^vYr}{z#z=tdFK0)DrK^8< zzaBTto)3=jH0mg?CHwyE1Jmluf9OStPansif*cIv#6k0Ck{VaQ?y6k0N2NuyJj?a}k5T zsaPSl`ejz_+})f!O-I**GSZxLOIzVk#q;!zl4 z*{m45g@uG$`-Ha;{B^7N=T{zn?Ln?dZT;+P3pz5^gjH?aRs(OWr%$q} zl}3YnNQZzNlMk>5JZKaSC%1E~u39EtmgQ&@O*^!*6UBh25T#L5i42H6ssl z8)w$4g1p(YPog`UN{YFJ9lJha&lW$hgogf*oXe;*9(p5Wg;v@C0qUjgtlwW`RME?T zoS$rp$oh8dy#c!3?dfM8cmQyZ@ZWZoGB}nk%uw@K(Lq_6r5dn1{NB?cNM_)4H^QlF zioTf}qO*uf{~Ds95RQ)0jc2x(Fb|jGeG$1AwqLYA4?@_w$5O<_f~wN?bXwn!ypBed z$kH~y-5Y#=c)CNgnx_Bdf|yW9vSf&N_a@RPUuF%PdCjkFF7zbef$vS6kY2V#e7lDf z?01wSp?V)XAi!A0fcK$NDCgzIb?7X1w{(-|ddugft0^W|E@tq1ysX#RBnqiBNR!J| z;}C}63y;fH?5|vZ?(429%y8Kbh7?qeu%L-y;|5uWuVhBY3~{#xcrFa{V+J=_l9j&K z&a%>2j^***`!9Zge$0UUrY=0GG389KK?##SpX18El1Wsh`r(q=ZiD<)I_7IIE52c1 z+IJvck{+A`>up^yfHiSo1hE1dX-Ed+U)X+SyA(O#3=bTBOS?@wd-#*vrTc zi9;N_=i?DtS;S26AAUfPQhtl9SJz#(wTq6oRRs?lK#e4O!oYfNz3Ftg)=#)+9pxJ0 zr96bXDQN9D8hdyfvE!3?f6!GewUeYtJa+<<>YZb3VI^TwS}%qa%5XZ%8}jvu_1yOkoHMmrx@{KqSWkF(Q_%0ix%tmlr>d{(O5F5jEH~ zfK?lXQ_geTkQ(eAM)8rRo{?YITC~)+3{1H9@!rzl`G+#CNe-iSsvZY~Xa#kUe%<&z z1uO(%tCR{}zUwm~0F@Y?^cN4BezgMuyfZYlj--}2nEU*QmagM1DssZZKJm>z?;d;O zgE@L5RQ^}WJ}?ZR3^Nmo{P`!_wR;2ky<)(N+BPKv{W)nll@`>%>ET;4G=9l3 zmZwlmP9vyB=PqMty5SWnY*#L`_FcAPc2W4>!Rn%PPG(sr75lDP1b>C+vjGn+w@{-> z4yZnKmW_daGf?k-zrB|;0&d>AB(7RjoRkQ=zuV+7jib%e>?LZI+e< zrNNeuG#*M7C*@MIzmJN=!oA-m{{pX(+P+@h(eJ3BJMp-d_CWvLQ)rp8)F)AB2c(b` z3*gJ-s_rg8qIB?(p$A^|Wm##!5YZS1>+w(Uw%PCbOwCNw3iF&3)eQ3v@neq&QC0Bdpp z{PVenBoicKH!gf0=ykEt_EOHaEa$NYjvR|a{!<3d86KlMbxa)tJrjl=Bz-yPf9P%>I z9ltza#|^|dIva%8c>!bW=ec~mA5It`0s41}fVFV-2J9v10IbOrO<6#yk~FQK=t8T{vPzNj zzi#gaTh9p|{5RrGM<|;|TEc_?B9jlu5>!PF5!eq^aEVy4>U>fD%BtM^^ccx>ZOdpi zem1%CiI3WE&%N!!ua~H1sX3Xtcl>s|Rdltnyxd*)wyd?aw|blV71npa+E=OUB9Ac= zuASm^`+L_!>z_jc&hDP#QXUn2nMZ$e5+l;<_T{&Ke0s}QzSCNHoQPPpw7hi+1wfJz zkT|oi8;@7Q7@t)=8)dS5q*njYo}aVWc}PFP{M*3nx_L}+km*~!6*++dHnCd>7ZQtDlsygKmZZ?E=P_BxNrV zDKvgLS7@$leZW2cg=FN=6|bf7#n5=g$77#^CE^fZ$2{K7Tl0IDPr0{J!x9{nG(f@) z2!mH44%8whJ_zSrbGF-N)yvqT5lf7AOPa+85Jlakn#|V16`@LxAi8cul6x98k zKNvt2FpauAzD@}y_@UfekP@6r-eeMUJ{owI`AgnrIC^5Ln>PHXn~k8 zwjcw?6)INOPAcxIeyY($DHsX<-*h!gI%*||{rB?Y|Vcq%qnRxw5*R#CImI4jn<%RhWiC?zvbd1}^$ zqPT~Jp=|ESG8$BHyL;tn8Oqh89KQ4>&l>cu>MZB@?HH(#SjaFX@{d2S_%UQN#&_`v zJ?(iKxrC-nEhzvySciAt5r6B;PFSm&0?ut59sa60A@4no0***FgxLG5)DpY+vmagBc0QQZp6cCxT2VycwZ6|0yh)U8na~E2ey=b0>7Dv9+A8`~?2M?U z{FLq0fuL6y8r}!!?ON!VT*|o@8W8@fPHjlN!t@FhT18ljrKQ|xP>D|Y8sw$Bs)+%q z1BH<%o!?q0)~0%3G1ro+uH{E5#3{XMf4|l8vpan8#Q93<(->HO?}?u$99>|{!Jlu} z@kxaq;$B_fdm}1ivRZM0>4Cv36Ia}2kKoY&C!Awdsqun~-=}NuVSMJluYWSMe|%|4 zo1)}C1_A;>yw>*{kD!4BfIHHS2e>-Xi}0N_gV**=i`Uypsgg1q0fp8~s;z_pL8!11Eu639wg4yLKl$ zhpZo=b;lU~S89%pGW$_}U-8~cr_I%`en@*ehdt-~YZ(VsYHog%XQt<+GOK=}X7

5jCPF7c3$?@XwZwM z>2vqx*QjOHWC@vy$89q5zG;gBuW6E^Xc5muoXOYc4~do8OtnT6tn_Du=IMAP!eNOA zGD*lysKjXe+;#w?&TjWt5-Rx@+WSOZc8T2v8POCrx2(bA^C?8&yx_=q=hkWZ4mhKG z?*+3$;Z>D29I6du&>C{hs%E(@OE4#i4R6q&4oDO&{K49xooUg|J%C`eygwmj+d2G8 z!V75Z<%9mX=0h~};gR=oeq#~0RG`bQDW+41y#WRTUaE61-PEmHVn2D(;}cfI`!Mxj z;Dv~oi=AVM29Yc|469iR~6JbY)frCd{E#;V!YwWDIKf*CQr|Xx2BnKs%C5VbC$EY*}tl+paSqO zV&IGCvw2L!S8S_|s`&l%y!TFQG9&zDg~qea<;D*BKMR#@$Xm9b5@z_v9O$TjT}0?1 z(7x*cAr)&DoJcC>q>$#OZ~D4!-U?$Y+@{2Ph$5%l+CP@Xnl%%3{Gq(tGB<@ZizuCK z;D@_*(NU&enTN^KKBrTa=H=_cg`0zo2r5_G>8vHIRAK5sOM0_r6*Ok18AG~g&qyWc@PDv`QnD7 zSUDaT=~oY&E$5};?~EcoP%~qpljfYgk3Ct%kMDcym{FIgRXxc6RZvxD%E^@(13O(% zefsFEGPICOc+A^(Doroqy<)q?%*)Kt)&;J@gX+hy97%^u1^i2*WP6->$h5{nlvtl%0kREx09DZq|YL@FDpT1DRwX#=$S(EU&P z3V~sfiGBgtRr0~`lmxqfLv>^0gE2iw5ZE#8qkB?N6xct|{(gyfqdv{PI~|lh6}wXx zzL(+1fBZhttzrOiO+L%eK|0)D6bX3@^H97qXLKnAN#pJ_x%A@S{&}`^sKGCibF0an zMDKXRSM8hfpd+1wzr=|J;Cx#er@qQId_=d>Td|1qF51f2!*HP4=#P~WU*z=l!-o}8 zG@}Em_sJO-dc@>NOPw0eszBn~$+$AhW|pBUV3Xw|=_Lnyd;jfa5WHVdg<^$LqZi~P zLj?G6Bo&X)wnjTATs>3yeRS3}{vU(;gTZ0_7^S>LNsvc-&3whSm@qukWm$4_^sLFx zI!NfzxS$XJTZ=aGpC*JVXUB1JG^HZ-lcYS~o?-40skbQdY67*+1+j4dh_Q+O)t(%` zP?S{vzObU~p7k4U8>mT&Wo>R+*j69+W2UHdD*DEtC~TJSU*Nf9EM{~VHX+DiDV2JE zAOh^Ccpq3ufPu*fp1&yvbYYUVtC9@l z9xy!zz!`gkqRKrw=vnXQMl%R#M6F z9#Q#6{$ipKL^O;JqG)7Io1BDF!FpkP?g+C^6#KpA-<0jc^fq>KU*cL1`|Lwqd#*&0 zeZZeRY(Q~_`ev@QR#A5qv!TGyklx|G5x&TmXQG5k<42{hHiNvwoiU{&tD;>uaI9#x zg}N4x$eSyGGCj1X;}}A2)^~Uy5Ew|oEXB;uESN!(-75Ml!^iCu8#Sjc@tAS>ykbky z+CU)g=7;Oj>Lyj9DyAc6-sH&&%JOto0!c^S+WtC|1L;56DlD@Z%Dcu-1P}hZ=)C&h z>--L+6lJ&Mg4J0UM;Ve2Fi#0fUaqsM2Ugn2%(DhVoys0u5{nj4hMfA|>IS2{t-O?U zezB;?zV^WS#Afx;FUl_LfK;P9T(3-ak%~owg-9eT*MrLHf+C(&a0NB${Vh?!z?2-_ zFf{~NCd^}!VcTw>ae9$f-Ysg{U>oSJNA>S+hcTK?drA!!jmUfY^b!d;YkP{b;q2U( z*=E|yoosC;UaJMkY`T$d|weeN3OX22$UK|%5)>Irj%owkh z`5D~id7L|xA_!v%1Mr1hUJZot2uEZsn&wT5ONjLUSceW2S}eN_A=nP2WYC@tqbMQO?wknp`k{mBmt!#}j|Kd?cdy{Hj=wD~Z&oZm3{ z+mh77^6;E-75dof6l4Q|$}mwTggfR$d)p@VO$n8B4vQ}xv&lpqtqyN10ik87e< zL64E$EDB-GX5$l2YMQZHpS@w#6i+ptZQG2RuI6KdEv^%MX*8%+-XZ7P%Y7>&O3oE- zY6>ZvapPCA3FNB{+@`KD;lFydktTGEl|STPF`M@3WU_)Uhn@)w4oXCy*rsEqvPpO$ zqvfmh_yHeG3xHpy&K(b086%G2(j=7n+jI*1p}YPg$=6`j{WSqWmM4D(ZV7lFjcENa z>U+MdDAYbUC>g$Fei46)JN3rv!k%ug}oyy}5OAeywqP{*S z6$Y3hzmWGvCMGT)zrP=F=5L)=Z>Z`%`~=WNwq%GcANI0=PQsVYAtiz#pS~@7BvTYb+@5*@X-L1sT$p)Gp6#w_+V|82%Od)3W)bIut;@SaL!C7G4 zvjw5NN`%lJWkjgz zeAia}FIVEY+eLHKrQX>V68=g*Wed|F9z9RCO}7)7YTl$uH}=@3)f5^SZ#87nzdB%}3N6P=AcH_lEEHzk`K+f-kI&2d5B^Y6(w| zgg!iDdOfb;=rFfkOPL0FQy2_&OLs*NrR7n;0Z;wpO}@2EV5~(-=TDTZguONi8ehV| z0;qt1AUOi)brD|{^zpJ=k)MXZ6`3RJ{%04TA0*AknVNWY_q zQ?uVFVkD#sT`y*J@(gSpHTm#N6J2i4(R8@dkrG~vM@i&2hV#zkbQOd{Gs3@Ar?uKB zOZXWI6t!{Jk-2_mkxvzq!|r@NNrwRis?jYzW`H`nguGiOZYMsMvH|$TxL~%Ss)1|v zUI7C`U;kFfnI&Ka(wEb`YcH~Wb$;r$#E1diV=x6m>jAsopjsUMI}kvG%dWTTwcDRn zQJPQ|EPx@(>$Md(K;(dxtK$FHc^TjYd^h%BBAY5A^N8Q!>gz4|81RN{W#^oIh@TT| z@hL;!!<*yv@DfybeU;LA>$%2GO5(0(70HKK6%t}Oa%fT@74qX!*1H@dppvTC!d*7c zSV25Yt#q=txuRQDKvnagpeE~)Ve)VQ{a5;%G+R-b1naa>*Q&U^*Lt%ioDO>&IRE0e zCCMRm^8xNYT>}-G4RdPPH}F?^IAGgI(RN`#Vdwp3ixsW!Kho`9HD|>Q@!3ka41|^o zik>u7gfsSKC0Z30X=9YRg4FM?Xu`e0SRhwy%tzYW?AJ3*S~X&&*fVKf=X-xCZbM1MWjD@~ z;L-lgwjOg4Md#D8xXO_kxQ!3`H}TVuLm9jK_y_L8%ZLH50x8|Q0fNF+9f;%$SMjE?Cjpn2L6fw{oRE5Us!7f>9x&5A5^$8qXKY=(=%; z)#X1xZW(^#!*XN3X8LfJ(|p`?aP$ELfC-d45B+q^Dj28yrH7*ZlM9hgu4`+&;FE&` zaMe-jv055n8k_z1m5&?A^BUWIQT!2yW19a71D$gIgW&trj5hw- z54{2&7_OtHYCApVX`^SuHR^0M8EzT&2co2VgJlM1YDU|cg=W^dVhSKQ`?}fTIbQP4 zVX<2LR}-Y_SW|#f&N5AQzE^Rb-r4RIp$;7Q){*GfNP39XA~beaZNvTBGxuk(OD@dR z3v~*#CNx*fQCSUyegb=gF1&n>=v}8vRO{|Jj*lcK5%vdhEt6m^N;Bm#o(*-VIq*q* zh8~{;NNR@ltcpM|03++($6u#=->eC--dI$zK{yi6-uIwhhakb@-SAl3LpzqchoW*s z%L#-i8bw+H1jq>N>ml_dp*p~l<)Z&wcyj|V_(-{UfT5+j;y2`6@UWq~D+CQm(W%3t z-C*j2ULb3vM3r5vmS_p*%Se%El3LXdI-@Q7;S!ix_M|@Pgkf67w-vlMlVQb3t0P$1 zt=R3wpRv~%AM;+(nwBRnARYyLamKO7jde^(91u3k+T&DJ`RyN&ktHWI>`TqY!5;m* zbjoKr@od=TnC4#_v3#PtEPOrUUhr`t_t?|yL$fDm^Cx}Z*eReOh>d(? zL;tfh(e>Nv->$Bt243OMxx&r;1)2&eH3VWAFSNm_!^KVs?w>jUFFEWSaLO791-3q`HL9IQfp()eJwrE0IrQ+Z)SKC)R5t zl!lytzO_o1;zVxfDMC*;0qLMk^-^(+?pj!4{Xx8A0hJefj9}jW=A9}KBRQ(j(6Wa} za`wHRc2=1Ca=g^H+t@`6?E?1FpG@wDPaOaGZxE_4TV8B&B`}*+8jSH81U^0Q%#mW|T9Q*((5Goyx#l6tsP&wj zQVy{-K-X!+%icr?e?Xc`+k*8?;@Rknii3ItMd&{ay))t}#^fp_EGex;)C4j-#6;uNn996u0hV=vrv0y~`NMFukpw*`{=g`1YE;+wV&$u{A}L-?O|BRsNfugx38 z{O>fpK9a})_U6C2IacjJc3#Ha-?@esTA?6HyiDG7rNJaoY1{vc_5OQi0)S}&)P8BG zcxkIvoREq-lu0eIS0qf*cdm`EeYGvv8bV1c)UP+|N*mkL1b}+XpP#7b>t(vuoDV*> zoxEE3uGCrt9D&}XOqkIwZ@yb3 zR6%UwP0DS8ajD#fZ`2#b{4sB`;_$Q-&&P5l^7P%!!?phhJ9Yg}Ds>Of%sU9|7&WK% zwMTouN!J;HUqiJyqt!8r3aE|H{2}VA>yenM5A$Q9R zI=o*Bj|%M~n`hN*5|pK`P~B^q7BL&oQ+XZCDe1o+*1?RGjVNmfvT3A?*NN6SSBP#a zgrH1P3hrt^Xv@i!4qnzT@~&$>EKOYR{<(DzC{_H?merHnNs+9E%-M-)S3Jx#OIaeB z-o#HWAX&h}Jr}MqN5HXUCVXYin{k2d&Wqo23$mn6EOh$9esIaf3S>!(2@Ty?X+cT# zmDY!BIG6wb=*|uXO!WxKg#pA6M&293=2u?XFP%H#et%ZEumQ&pY>dN?f&otC_N{Xl zKLH&-qK0*MKGvCDP;W8V)qP^WuQ6Oa~I7zPR}OAt&35T+O z&b@MVZF=<%tyhOhV~| zjmh}&12)EsVJ-OYFv1S44agxXi@~Lu9vXm(Xah+1LV~XwVSIs!i6QTAyI-05U(y?| zB`o}+{hwwB4Hh>a)>G1aR`FvO+-)T5$^%OH<$a$dYS9jRNq*Wa8bv$KoCgL(+6=Cs z`lwOS48?h`Ji{)6<|A0o8ez4#Oo1L^Pom|c7{j0T zbZmWWrJRp37-R{Dr?N>PHCMB*2ph9HUt^r;E$nanH)m|^j9(_9Bi)dgYPH+dcfctVZx8N zR3KcOIOWK*da|C4$0E^yCkIO=7fmqLo*I_*z_z%(#Rp)OSx3<};Ns6EO-2`&Nug@V z|K(M!Jz(&&=Zp#!W!Z|8KR6#Xu0jZWWhfwf5q!gKe?b-77MX;u6WOY@YAJ4Eux{w@EX#wPT=7ZaL{ik+b%!z6Qb3#4fJ;S0XOT zvl;M>t4||>%#pGiJaWH&qScfHJYo~#U-_dOUZ=!` z)~h;}DW_ginRoD+=Wu^0GYz1@0$?U%?ULo}9E7- zwZHL&lxNY78}o1X8Q#qOQ<}bR9C1(9NZ8zL}&?7tl+jR9- zW@h^E#o5(wjp(t+AMiyev)-Lo&a-1;lDlbS_t!ooN*zANY6xIa64rU3z{=-ksvLTq zLj~WmLi{S)o5|j>)L9ioxb!0fi2%fv2(tuO2?_-I%1YRJ=dGQed=#i+*x>SRL61h? zQ2%zmGVVu;sfsiYzwj9El;^x<`<}Z7o!{Tf;9zLk_UqfX}o{TwNiwMX-52Aq-X$YtL9wlYw(b1pMR2PT{@$^QWxqofrN5R225o@C?r zp@17*Deuaxi|OxDFf+OU6Q%?IQ@5|!w@>WNON;WRD_}!6@mPPngsf| zBYZl{StY!0%?qpykt5#I-)@KQYs@66tn*OZj|PFtiX)4jt%P|O zpDQ>PH{k^Rucc69yp{gk?ow$7C*2KK*S%}#pe(;~$y-2)M&mH{N*~{WB(`0QhyZpm z%br*m<76MGN3ZX2nWldk7pM+~ZlyD|Yn(7#rHe1bPi4wZO9=vR1CSt8gyRp|4{(z2 z(jkyA?}IR4Tvwsy52Nkuz@YYRj9KCF%37B;nAr!GFo36|lBC@Sxr0ABZR%NnJFG6N^YN4foKF2d%DfQXTRIX1Q+p8?c>IXuu zp+@o_r)rBfg*qr$1d1Oi)r|rpaZgo0`G^sb4KghQk`gXXm2y(Km^;PenYU3_^8*rpf2qx0c=b+Cwwr7UdG;QPXa|`SQd*^ zK35^1RfA**NwtOUST2dTwCoOi7Vj>zYW-xY-QuM>>uGfV--^dSE(g&$MEZWW;PR5HuSyK*?|RL@E^8Ok76aF|%BU7~r@#K@@LG`qH}Aj| z`ofnL%J!q_NVS;==W-`WtzIz)x&&J=QW50}hwy2$H(S8LVStb2 z0(hZ_8{OvP5Tgq&c^e}C$5HBkn|%MCveJi4hV$ChzV~8V5<#vjJ-}3xQs^ z%pD_jZD>*MItV!DQ@HVi-jvpor5I(by+(sa@=CrAB>s}NoaG|oX6zRr+`$>!RV-WL zq;BII&<=MuJrzP(kEC)^rDXXM8G!072yw{r3HMd579IAN%OGJsAH-z$@m%uteBcx? zvo%byP_A1|!9YX!@VDaIH%t%x2R91{OH^yJFse6n z$4_r3?WDJiu?s~*z6Df6c#)z4?!RUv`Y*pX(99?yL*rDSUR4Un{(w>tFTU*G+zv8h zjqTb2-7{;4oR}c zy)=on7GN4I&g9q3dyg4a2HJ37k{o(S6C#iiAns8PF%7BV+zEUz;64plXS)nFa`pF8 zeQ*OFxr2SR1GS>~7)dAb1MXgRVXs)`e<&m3ucU=t;31zA+01EKd#au$vFT3e`fwV# z>X^N}QJSrhhJN#~``e+r?^$kgi zjb?}_iDSoFvwK;G)zvgvVgnuCd>Ww#&Yi_&Q8t>mxViLS`Pf8q9k2AzC_bvF10#0? zmi0|Q*_ad?aOqx90h&&NH$9J^Uk638G7f;X$2=tE`ySbV8C+IWd0^zcDz|c%S+>QU ztyEyYZJ$B`CqN~=Wk-D^bKnPR*{}0>vk31gN@*#{6*M8V;`E+<@giEu))+P_V8bCj z_Z*(C=%gJ(H6*&iXFsPkc24{k+B5oH6aGT7md>Bxzgcu9Hb!)Dx5E>X?+RQpL=SuQ zRTt<%O_MJA$DmKy*yx|aW~?8Ycm|nzDgdX36&4=cca+~T&3sx-T@}jX4?PS;x7X#Pxv{dE_}DeIGo652KeRJs0_Y{ zqFD~P=gP&-QmX=NVj0#3nWuzO^7F!fQH-pkX6PKxy$3~u^iP-Qi&EOW!^rtY2*&f_ z?Pg$P@iQ*#^W_IHf${lKOo?;+ytqNJf7bdf7IycIF{UyeemhW`gFiqrshDzCdrtZ} z-}-=<*FIe{zpR&ziNw6<<2m+IkSi(nFeOoCz(cS_)mbxs%GZrIzJM}QuE_8}|!m4XM|rT@cU zn3)W6DNzT6zqj!b%YBS9cLV3CFnT!ZaSW^;Ab7#1z7{NV8s-e%pmcHgZM~RgYS0Mv zARs4^Ofl_L{Jx^HSH^zNO7|HT6Tcj_cs}X3mr4<{v6FAnl%(-pccI?qtRTVx)_-qw zCAbY^?Ta~h>d0>zK^?E6lfhOX01KO?!Wc+3*0Sh4Yy(1Cv3arjn`agKtp&){UrzUeKw!*C zpNlvYqo%IilhOuG6&~G0tKqso0ZqiLt>9x4o@W~Y_fx*{6_rk>0h=2JdS%tUzI%Ih z;3K#ulm54qI*WaS&TaEA@gjYDQtyfgbsmvc44{O1Z32o~orvXqWOti-D_JbpCGl<) zrjTjRh)i-L1C~6*&j&WBk4fMG6ns8aPpe-Ow`?e$95mxH?rIQwZ?m=Z;}Taf4SyIo z3LpeB$cpn>hDjVJt#J|g$!69)k99L0t;q4}ygz3sulmI68#^7%7o3i{^3q8wL8_o4 zF|opPDu7TwbB^Z_qc|hC4by~591Dj4>m9oz?7uNbj~XMFAnFCzjZ1LGYt2H570vKK z$|0mn3}defWCH)&O_oQ6rSR^7P#H{nm@>U&Y!`ovm@B(i4`ZgLH+e5+eEbn#$Y4xUL&5_h zgVfWrbu(Rqtnk;)<`a#HtsaZioAAA|6zgqkgO#z$I1Y-D+RIo736eDNYSw%ZMR)4b z31LI})Ae@-psX+3Vc0(FpHF*7%=Z(U^uW9l^8|0oCFt#Z=#zZI0NQ`5C29hC2TQv` z2{xLf?=jr4EWJ<&5R2Puw3@X!vccl^CGy%%5Z@0#gDc(x3kZJg9|~{*5{yck=NXb> z98N4Gbc$zlEjGO+7$PGg18!t8$4!4U9k9|x#xp+YX$k?aB{{3TsQMXJn2-L^3I zfwIoLIW@Ru2RIQIL_wMjquzB;am(Q!hh=ZPNnLvEYq)0q`<-4gGwmnrE?|hU;KZ>Y z-@6N&?@nK|5Xhl^fdI#4^x>@1<%rd%D7lTh96Y9OvxPU%j)^WR9J-Ic@{MC9$X*&; zx0)=eiVjbZRu?k%yE0jXC-_BH`Z!lkV9Nx3BiB3{MsJWbfE;T{xCHWx5% zX8WYMtQ4JQ5@x^YV0?l!xS!O-fhY5SvUc6N3Zi>N8e)s1|CurS33_j18{E9r91$Vc zfTJ&?yHM&B0WL3NN|}6u&EaMJ$PPFz?DxtFS|H4Sc6cD?@b~zZhG3n}6SQ&iB?uRU zz2;U0@Q29UMWDKMe#okX=x(ho6r>s2ysK$>1^;DQh=iz=8`${ zT7X@B+hksNKAqW-#~ zS%M>xeIFnd^jhnNk_im%f*r+d7x)36xG`_}e<1-!(cZ6une6mCQ~wRMytzgbZYcfM zH>-HhIW^HaWb?4F|MwwZgPrAl+qTE1a{m(s{fl`-p0b4o<1*~f4G*ECVCMS>PJs;1 zYEHHy$M_fL^%+JPFP? z{7B49H)51xN*u3(e$9m_GYb@#RV`5B3N^H?Qoj)z_Td%hhIqeFQcQUyA#y3CY#3F$ z?v}}XAQ`%kj`zk3lS5m--&~9r4!Jd7Vzwe`0<}n?WyFo4*gI<$Jn$sLanM`v`T}5l zF5eiqXWatf9%Dv|k28Z%ocI~!QprsdGqRX@zXp}3PNHMHMS;gtD*6R?H# zzXMQ*pQ2dI&o*;VokrzrZQ2>nUpR=OkNN2tvqsyBpLtKx9TiZb((!A8^yHOJFds^_ zZP*?|EbILP{87dLyRADGONrM{f6 zm8gQ{h3m_O!Tb0JLXLLpcGU8)c_tJIa4H*$#-^nO+rn#~g+Xlei4zAU_zkhmmBl1T z_&?3c7qDB#jxHPdUvxUe{GDAin4A=q$|YOQ7fdW1(|o`ndl!#G3lM7Axa_DQ64b(s zSr~I0(=Yyyt^68g#clSnyK%K)bR)>9MAq-*hxEfk?9gpF!Zm>I3gPT7vC@jPnrHgO zO@Q8Oj?7DZ##4nbcv1R1Aga-lM4ca2_iK(74IfM9%_E*Xz2&MySpt)rzv10%$W%_m z=A`VnRKXz6=)p~3p>F%Q2=55j(U)Pc;C0+^`=0G(ZQ|yeZJf`S+Z>tybVqVgH1>}b z+5X-Q)FR7E>i^c;egllRWKjo-DMGdkWBXT%)>0e{?#aAE_(H2X4!IRfG;q-ap6}!N zGNlPRIpc0{e}E6}IWdil`(v?BDbY8{FiG0+)^i)>vcZ;zEtPnt5y&$WKuPr0OZ_cr zYPTPL;usR_D*~`5{iB#z*HQ^YSTzHuz+3ZP5=fA^-Y!9(t;#Uo73N^2Mbe|G_#CbC z|BnQUYJ*}D{`RJ=@nwGJN0!v5tziqiJJbe3@Y`n)D#_;VhSmLZzkS21Z)1lee!*6a^9Do-rHtZT=czTmRCMyP(==O`9 zd*-}DQgtVL0;Xt4w}9y_(97VZmP^GhqpG2xE+vDV>9d{yp2yUG8*uYf>__}AFZq6d z5!9@k@9jVHb2vatcD+da3C(EG!OoNPBm3P52L=w+-y;OxpB-{tSwonR%^G#>ldjme zVv{@T+c63l>mGcgkB>s@wTx@{Ivn}&zRw({sl5-LmDi+^arZH;awOuk@)PdP0DlzZ zNeM_{hw_-md(xAl6@{`R<_@%oCcHQjbQxrknkHSxYkv4s7Su>K4BDG{J;c_4zAs83 zl-NIOS-^ooPYfn2gdj*Nd-U((XlABPXkB%s)yN7tN=~Tg0~!a~Dd8?Q+o3eSjY|-SW#Bon?g9g?XRd425ecE~c)~%()`wJ|**T=l za^$4W82^Vx*A3LdT$?yIpQp{jj@vL^Mvu8&IJ)bO`%}wXpF2 zFkVs&MLw5_=Gb=3_Xr+NMl8%kEqE&<>By7CecgaS|vCh8SJ(pS06VabK#K$ zeutJxcz*cG*Gw+tolwlK?Sj&`ftKtY`5~<6`KA4t^$5C5#7aZ{UDuh`r;KT^_bJWr9h;H0)`7nmK3q#pzd{i^sg8$dz&{obF$_px7m- zrQ}}=)GiDbOYHWwf4(;F1q#2{di_hzs9g(XilDvoyZ2x`mhZ%-%y)fQ@+%3FS3U_F z&V`Wam6$+0K?LPK|FQStv`;6T<%tExH#{J8Kv(r!sn_!Kg=o02NOBPkziRl0!dJ-z zRnpv~;5QHR998^9Z6 z^&{>TCW&8BuhBJ_SVkX_WJ_uj;EFGO6Dp7byxQbpz!i?k+oA2unvZelr6N;7Jp1HP z3_ful9ftgwQvnqKEYsZQ#UjxPaiDr1M^h@}2zgsGijPo&!2fZiYrH@)<}c2D$s`}| z0qG%`2mw)OFx*D}UPe0PZ)^UBlZ(}+VwP1Lq%P# zK35{~L1O7p=A((va(TpL*~_VX_kkxHlT9?@A1NsBfoC=fgJ-2@ZC3FeFPKyEzd7c}-9xXWZG>2Ua=VlxIcKr(7# z2LN$lVgd9r_)mOvLoa;uy`>_t&gZ{XJTDg7yOWMnS5yFeSM%JNE*>-fO&GShT`|)8 z1)%PbueM#Qku?AlC}9Zq?Xdttw74ne@(;AXLpY7^w8srepI&ya79`)|L^0ATZigiF zeExmK^Y1629o7D!>j~M?fj;C3Rqewcud3sE$H&sWX24d(a)D+-^B|v;$pbmYlMC0@ zCdsKNLK%e(U?LaaQ2&<Tt0`x z^xA$t&|W|DL6Si>8N-QM^{CF|+-`o-@%X*X7Ggf76Dt1WWuGFph-$n%0NTZ7%5j2$ zEzvQTKHqU{EA-tIaQEH-px5%2D$SI}@6C1Ut{dB%wNWivvFZhMUBUNahOr;s? z60zA&*TmNr0Xu3T{5MsnPP;@=7J+~nAv2V9;|MN>zKWUu(&~*|_~1B)=00wW!%iEm6qGERP|Bc&Y{I(n)1<~`ZV>AN& zrBX6a6rcEh^5&j(2+?|D#4+_I7S)gJTxorp*NXbQ^;@eVulm00R+90QE(QrSe|9J) z(fkIg_icu-M-y0J`*+Q*OiZOiv}MpkpDC1s#4xvcA^-go^%ia=IhxgE(2v#J5$@g z($6v6DC8WB5AJShvX2}T>d@YNcX(^INc7VV?Fido#X&{V2-Z1nGdG8S7)7f`oVoS8 zrUwO>o4ljaBXd~)S7Vex%>RlC zH?(#=Oa(YTQ0V$2WE4owoOS~Cxx=$&GOn42E&hv;7Mtr^`IZ^3%ZSZhL# zp12t`$^;)d#_->A0A9eOJKC)QItxFTe@@{iC3l1J|Z0D2u2aXhjG4p5u zTFlyA3}PLkR$}V;6x$=e;IEFvQuevW#Ld%2C6f&AULa<(Votg;gN4pkyJoLcc~>dE zb;W<&4{X}3RMep@qtUWrl(VFDB1^(70)^%ItI0A8WcD}2)O|r0wp|#cI^1WZrYfis zeWx@x1(Xco?4|`t{$b|#5s32B%Le>iv=lQf(;%Vs^MIJ($b)3_Ml+uL%so?Ii)j3- z%DYu=zRRfamp}p^-!CyPMe*^CbJjaFfsa zoi|!V7xzLbs#T=Pn?5W&W{3Z_k;F(P8XC2P2}Dp*=i{?LPJX0*+$ED?DLY-inJo0t z{ExByiy8L9RJ*6Qr?CnaD5y;`7#`AHKTcA0+BXq0yeIf*e8-1{)OmnRr0qR)a#x(LlrMGp3Yue;n&xtI)vl#@?gG?^Yg&i zf5c(FiLQ{*Lh;zmmM>@c&Oh>OD-23=p*i%mA-TeQ2Vbf$?pq9^v`VsEK`KJNSx8*5 z{7$3-`{r1ejuT`HnK>&yrWzmbvZ)$IhA#Fq)f6B7J(Xp*bp^g*)|lOGsi1vulPSJ} z|GLiijWXVa3G8~Ht;OF|-!T|S*#n*3Gov+H(t#4J;!{Q;dT9wE8qg!qGu}YCvI1IzIp3*qGX4kj_Sd5*+Hg)6L z_UO9O7rU$*e819ng)EfYIZj!}>g;~k@5HTmD9x7)=?i>sqp=1uTk#8LgOlcc#UDecXcbsH1JXoe z7)j6mP#TLQfHyW#bIuvl1U9iaTz2QZ7<2TTQ9}g_oLhAnuljjVq~VWzV$B!ost74YVPjWIaqq9h`(NDcgT`#j&`Y&0(^< z5>bTyoo53Hfy;=l9JfK*MHoCiAlUeWa3awm_qp#94lN;bD^A6{)bC?(ZjjCUu!HZX zHl06YRD`ukSCnpRbP}PnIVfz@;b$K2rZcZhgxLq76vVVw%fC zwy3dtG)1=a!Ygs5gU3$_DNjc(mb&W7acKZ|OCz=j68+&s!^g(6z@Lwnol*|9M=rf7 zuWCmWq%(<%zMoS1lQ(>1?b!5*7O?SI3JG}SJ!;~T@*mD}5e4~+E+n+z&A1gEDpTTB z>X&rY90`3SpngnZ^=j{sm&Zl(u{yUvCu;w=Do+iYX)(Pr02DBrhsqh=lvc_YmLV+k zo|Bs<52c4x-cTv8kd%wh4}#6Uo9@n zn@}qpjBIf=_@cL<_r+^MT{eruKW#;FBPyV|m0E;PYNBtyhyTH2=$H9+cE&#>(`cm= zD-?oaf!0y2Ei=O~QiYtf*t4z|hJ{?((!K~a@osp(Yuob9OS5Z>`;!uqA~XD8uR86v z+FvcX)ovSx$VRFB5^pWyQa$f+y4h;yBvOpg-WTYKW%?VymE6!V09_<1vpHoXfZCY* zD-EqtaalPwky=Sse!3Q@+nH(s^AmbJbJotjjet%8jn?kyq^Wi({Za~i$%xxI<_BrY ztCPY!zkcRO1L-6KS3ouHF{VkUO{Z1<8bP!#2;kUG(`Hi#PUUB3etz%cfiN>|4<)sF9 z`ikV8ti(kD+g_>(QO{Ncdi1duV$@76US^E^srip{twd}|NLk4Rl2xYP?VJwjsco)U zUzP7V5ROM^8r*f%OE{@4n_-~)PTWt9uX5@?#5J|6AS1U>=5|uj61nSvIdxyHr1pfr zGU`^`avnYnjlhroxw<+Xvdh7ZXwLL_f0WGwaj9kizYQ>^Va;#Bd%L;Ndk z1OI3I-p6RRguyk%7LIs_Zy4xOeq$TU+txSm@U~|RULpZ(O8W|%W#=6d`$KEHbz>97 z8D3|mduv#MNGVDkZ$$+HbjFR+MSAoY0E}dcqZEDE@>Yt}&6&;&ha6MqepjB?I#Bqz zorB?W*x!prM8}(I(;zEaGYX-@NKA_$ zf~4O6{%;*?4nP}i+3ShDC&%z>8l}8=(8M2Ejr!UC)H6vI+KLpJ=xq)qwoLP1WkY=2 zVyN2rQiIdA6k_CX71p)Okg{7$GcFf1zIJ4Fo>Er*Glmpj#?fqC--Tve-ApnHR5a+1 zfTJa->+P>V)t%VG^9x^mSDn_ebqY!HVp|oQ^5zuQvS8a3*Gez5F>ivdXYF=t-kmBzT*V#L?xcgsFQR61Bhnp+QrO zF(DC^2PGGw`L?ewuj`WydMS2GXGgM-HCD7{zu+$+7a=AmGvToyweI^?rUHEdC;}pn zGJAT5nT&O8*Nii+S(Hxt7Omy~jT-54vRxqpb~m1_hZP}YiVc{AB#W6VXr({S+c7WN zf#%Bv-1;{JXX~cU7jx!@w_`r&1{2VyZZSPHPI5X?p7BN3MR-idj&Yd8naGeUl){Zu zPom(KT5WSepQxUK@Fb&gc1$6B{&DtfGIO$YV3%%Iz0KBK5V=k9Yr9Ts=C@Sv%z)pv z9{HBH_{F}PfQ#{tH|md6k^*g13lzCEO6ixmJ8HC>NJV`<8o*t28IliFlxOKJWfMr$! zey~-A--t03*z^Pk1WghUCi<5|2(Afqp=H~ghDeHr++$O9k}n=jo%s6+%ZXTrc0c$t zHS;|E{^!*@M>jC2k5ezM2nVnt)Ub$h0sU8FctC+%y>s!jnnJAuM2Q{3H>>>jZS{RS zK9aB;zCOl^!Ksf}J~%;y95mXSpYrKRIJa`r#uD;em0r5cl^mrVtrD=D#1%uj4`QeP7WFcuCq2#kCqQwNUj0+lG=Bqk@)hJ+`u7bu2LMyq`RN z=+udMya8YGFj&Oq(IJh1o1Z_6^TzIQTzoTlIUx0 zzyvL{GYIropM}vJzLP*#zgxmg`!4C~5PIXusjRB^;U#rK#&;>-GxoIe9TgnkR8M5j zIEXX7VR%iy6?F%z$UhSwKBzEhuCOs@s6MFk3x`Vln^jH#uZH}nK%yO@B>Nt}2E1|| zmV!8h+;hE!+NgOy>w1R}ExM6v?tCjRj|7%fmZDNp?p4lkf!D-naOyMgN8}TPsTnYF z*%FHNqq*Y+;jGBsn=v>ZE=}O{z{}AnS!N8BdLvBWxgGjoDF_D*b3~4T=fSgZv~ZxM zi9>fA9HX|5^)RyatdBn{yVmz zF)UO>N|2Zb7$Kn84X-P&+>fx7U_Kow0n$WhCDidtvo+mi}KU!G}Y9y^p zM`kAr*30cmz%&V?al8?l+gk=Tmq=-h{zXt~z3Ovnw<}~7CGyM!1X{w?*;pc39MhmW zy1dxG!>fBPZLMVCgcQ6~+63}EnIcM)SqgZ%Zr9TeDyihFeDi_bUn=>)-HIQ{H=euG za9RKT!3L(cr}g)-iK%C*qkyN_Y-Bc0@jz!`>bxTDOq_h}i!jRJ!{7X~T^`DQrNV66 zVa3{iyS_#artxo!m}TjhH3kgL@w#^uuNsyl+m`qqi|+l;Jb}kz_`;ZDPRSwUC^ts) zK+sD9nzRm1h=l`KAP#>J`L{{`nw^O6oiZm;j)*ALKT1KPTe`zK(-@f@F}ctJnqL}p z{>MW3toWJlz0I9N@8J2%RSRPkc%Y|}rnSB=tub7@c;xGG(3|4gLjkZWT`NQ>f9^vC zTxPQjN@wc(V5@xpO+t|wwvRNhM6@C_{{m64lRU#1cV7N;_n$`;9pOei!>vnmoL>_eZzw>Fdr(c;|+`FH}6*DsB7+OvX7WCU@=gg>7BQ3Lw)32 z{4O0lt3zeQNs=KRF#x~-IvVz+61!5kyfnC9IJF}pM2i@W`P<&iTf73^8lr3fi+_X8 zyZUUA|8u}Fbpn-bKD}-qpojk`e?0wcwa2v7h(3ixOcWin(cOq0pTxXau!gB7JTwwm zVml#wDR5)hOh0`-)81}>2gq3`(w**U?riCk4tcV?Aco6#EcbFG9dR~ONsJM3FXP8a z9pvWv%4AiyJ1HFNM(|gve_q!EcLEq!T~NFW1hok~p>;iVYnjm`WOlQ>#%9Zt$WS}hV0k{X zgd~Op5^2{;LUye|B)7O9v=Y=7FLQC(Em)L7)Iiw$(D5!&<>`?BQ1Vd zIb7Ixag$ro{c4M&_QnumlueH@_V$}*Eha1^G^uA|M(_T zB&k4}>aKffbEhn_f+~9iiWV(iSaLyoKxg0P{%ABBgrYXmBHQ_YI+4LlV!(t%rGMW0 zE@-+N6}V>wk+5-{3Yeie9KSYH zbh2g*qt{y+~YnhpjKr`sGY5{y^8s%4DIlTW)${Yhtt6FT@ zUZQ0Agl}fjHr^%tl5o%2ZI$v?w!;qu7{_wMgHm_gsshEXY_BN*)B&xUF^?;;z@ojl zM__5p+iwcieBfzylr}MVgudyAg_cCvC{9z9puuA!Zyg3#M26wMz`{0MCAP`#hG*#l zSeR+}MR(zhd)s1RDyZwy+O2h21QqVFx8RW5B>k4LJPnoNP;1WckH|aAe5ygLntGAN zRj>AMbaV^b*EQ9!?4`OmPvst}BeOh>eSDcE{I^)P;M-s|*}f6)gXL~_1qvkEb@G*g zAh9)0T{}g=VYfS{wD>L5*q;Uu&4~+QCPU*c?H@@(6~1lEWWE1eS$*^;lm-9d@7rZ+ zs~D1&)Pq{3)C?%aSEZR&NnD>|1z6dAe~7ZSC=4f>i!FtrDFprf&dh!CTXzf$kYYr1 zA6i}k7r1*cFjY43b&_|4Sd`g_8w0kvbCwQQE2~M2Eyoi-R7r~-zq3@#H z*(ZJal#x)m)neH|H1F2@+xA(=!GT@6g=(Y@bR(JMOZ1;FoJ1B2*9HMG5)rb@F7+Ro z2p)pv7m~+SxGFhEIC-+l;k{R>PopNk($LOQrEZ;#OJds__KiI6l19ZP3+8#3NmqmQ z^S1sCAXNWQ^+xD4S3VHPQAEpOD_K61mTu?0fHQ$3ve;i&$U7ux<}p<5%(GI?D`GyY zdxU&AYadWVK8*lasK9+ssW>n|IHJlMb3`KOp@i$U0E4)zLnfwG=5A=-aNBbPjA*Fj z7!~R%a*cn<42a8PeXZ;rI?C9{ORO0Gh$eCmQQ^O(i@(GAalU{dYP6vhpu( zN83QJi+(|(h{ic+cvqAg1{Rv10M!~cD}6_JEO7=iGjnGmGqjgzu9G+l#GeXn^79fo zH+&b*;~3BFn7NoGwBzOLZRX?L=2{6p%Du`r3l13Ft6F%QJD;1L_1s`PzYzi68T>8i z`SfuOzCC~Jl%|&`Ih@2;fZ+#yP>!vQ9KpZ`jqWV5x^-u1ThdV=4o62#Y>> zFTQm8B|I5@_h*TTA#VugBz}1{vkvNGaHf zO&oG)uGgP&qap@sHRnq86na4oT=H#}83edayEp8>sIRtvHvE2hNyX#+bk*|_bniZ6 z@qQfr_S@;m(IU%jIWcEA_&W%sDN=T=@5&#M)fC_U6b_y#-Nd~8Tu2}LTa_RU+`k2X6E`ty zao0+odjUS#)D=FgX;KkRsM48lF6_`4NGx`8M|)AC!?lYrZk<1&ep>eiXXmFw-u&X; zTQ0t5&#!VVj{1j$C9BuRg6c{L89a^}JqYLd17H5Jrv#Lpo@#6mc>uM* zyhi3STJq~e%2nOdwJ8UiOYFXQr6%c3^$64BQ3&9&{3f#au+a+`efgsxi@vC!Ll%~^ z2o&CqPD`5_^YkbFoJ2Hl=GRLA)IgMQV*R z>Xi-@@Mn=8!_^yE?Ml0B?PMqPKQTgfk}0TW8}ta)qB`;WLWW~C4;IF$jQzH!@r1eg zT9&vBx2|gRV9vS)&jBlx^8tkFa83bnetd3b z%XVYZL4Uhh^tt?2v@S7>B%vYPmDO)5?G^JhO0mQ;JCkB zU0B~)96Y_LlBv=w_`ibja6)Ss=%Iy+Ddr~;3bnrH<-r*D=zbZ6od`lT2tOJqX>n&5 zxm^J0Kk#~)UJ8`~J^r;&xlQqK5QUw zmG>NZ-Q%xy^%jMp%=oTh&?4{N>q7A%erhTg&Gl6%Y0e7iPc|=HNz@r+8Y3)&D29P<$pLJuKk#P# zwq|9YxpZ)~=h-wRRFmEw7_EPPU?w?$V^Vj>$l{zPbc2fp`FKA0>t7U6C98j2ljNY% z0;aw7@WuQf>Np;gXn<|a!915Z|9gMTwy2+E`mE1pUz&B&XhZK&B19{@YC!9SWxr^V z>$6c$UdE2wPi@1e61QZ39s~2v8+qcNbXZ3+C@{@Xu;0{?$gZ}`kD39+3Gl>zx;gjw z9cU!VI$s+Q?}XyQx8fJDEoKRE0SnY0bJNxykF1BR(#p|uS$b2Y`_MVTK0Zmg1ogUT zlGN;)8bC+bHi^GV1;$TwSvy&3%ukB?RNnYWH?5yJ?(Gen=@*=`yW))eU3sTja?$=* zuYl1XqL&G<95%$qu8L;1X1>rUKhFIjayYA-k#;12FWYgL_LGPY$bpkjh;tJ_Z-C1hs!Nh_Xpj?~WcwHPcEWGQY`itMPVkFS4z~SH% z)>iwdA~`~YT(&63X;VqigeVzD)&5JBflW|wPNj#^>dWvPTz5)F!w)|d>z@wo;vCJu$g4+)YC zA22a;v_J8rT|DDZ6=_KkT&+yV@eG0;QU?;zVs5^5aSJZEDA}vJ3MU>jync3%WxmUR zawpzBAv-d!uK3@*!_u>)ZlscWQF&V3Aw6~%jnJp2!FHoIxTLrh%4Y+dE})}~35T)) zuWt>2Fk$4vx@+rI1un2MgYGsy!8&BqqLchsB#cWI=4v%Qc7ceiMB+X)F65&jb$li^ zo*!+iCi+?ctm4#hdBU z3a!@+tpfNhemlTqk^^G@Sa))6`B;aZ<>%bwhR+~t6575_!R}y0IOsh8(LjRBd9G7h zV_^qQ8oze(730=^9gGcr$!m;Nq%_1h3lMb7^sFNOP7F*UWVS?13Ms{<1^D;KGH2@wX}=w7~9n%=z64 z_!uj>N1AOhM-UNy@-khhUW-2wKkKcy2)1N|zK~^z>Ap@_wouA|8CsId#NwcL>NhCU zAT?t{qyeprq2@A+{{G zNoP5W{fA7{T5P^aBKO1c+M;X*@dC+@lBvDNut$xk@#`sXdKrpc;t<0~caL6dTYKOC zuHS12i@;^M!cu|$eZB*I8$(z~)n&68k`g}n7LoBMQGPC|5_$SP`1b0d{@4?NWSM!? z?!OS1ZT)z-p@Z>v*Q9XFn2y6@g5ddMmYdf4N9pJAx&7GbkPDkY+I_##J6D%gG;C#x zPH@$I=`^_1$!V=^UTkGNbyahBiLV4R;_2V|&USwu)8qHXuBK`feU*NZ&TTbs8BfI; z_GXMqOzHRxi6k&rNHCkwU<@hMR3WIQ6gGX{9A*@GD!klDue!y&ZO}r{qtqEIH-Ee6 zZlTU{0DpqNo(39Rm4#=V89*DcNIMi;8Tp%}Ku3bO#BuyH%^Om&>q)7UBh?0gffB&bsPpTYQcb zx;>R9q`*(&gl z%gL|i)y4t#!-#aS-=J4E9pDAp?pZgNLUoolFoVOm&tTyTN7M;9)EW8v{6uT4x}!b) z)U~Y*13`))2)4r%F(<3QHKCpl<*R^G+c%lU>D4g$;7Ypx>s`n=9IM?5AmN4*o7pp! zVH7Q>V1Z;TK6Y~RJzP9x{f5_Qbysx00E;c$>dsZ1)G<#ENFT7Om!Fv+*|Euud*c(! z!TXmo+3!dE@6)2(UDOwu+IFB9^nA`*_ea zG{e+OX}g~d1z*?jb&QUyme!FoZNU}(2|9DG$kK<&5KK(E-oI8TmIgYhR;w(_n zS>W|wLrUCb#|4Zb_5 zzSs8K1swYt4%`=)egB?TYr(Is$93i}_(qyOE`l4s+DNu*z+R5{Sk36wYa zZ+-Dr=w=ZD_N&UU_VCv*vB=;g?Btb*=z(G%vptp16`n|=Qc1Ccs{2S(YY}0-Y~kN) zJpobP`O$U}zqF9A0*J3&ACo~jG!sBljUFW95*ILO{D-Lcs!eb&+tWgV0{p%?AY|hC z*4hYq(#!wwmlAbeQe?bHr?g+FNl3%@+oJjGdJ*xvs^{4)btz2hkle5D9~9uL(P`dc zq5}n1Y`MNH_|0GbZjFNK7|O+DPNC1Ro{i+3h zKg1;&Ya)qF$H~}@Xl(-^KU-|rtsQRlcIbnELhshhhF!XrusHtWkmK8-r08jZM4#fd zOkAfKAikFz;x!c=u}MR!XRipfV{fok*&w$#67=iu01j%-1M~B|gMh>Uw>W5TJWl%a zn|-g{O&YZ@O&=_7RAlk@n4~g`k4a|JKQoh4X3hRL&kL!B(iSg{H^4h60ynaJe&;(q z!ep9H$*V7?Tx*{XJx469Gbtm9Z>2izX?$VMBx9aPZRd6x?EqTdz$zW4DeP4F*N}{X z{WW#m`#7CU$A%v*ToI3)=>#9XY8UlT{q@IyJ7p<67O|kVW=x&+Xdyl7w<6q`rf-fH zJm$h^291Uc7IbDy@JdD9i^)9id?{K6xqqTWEHIqcs9`;iSs?H&)oW;Ig&q3K8j6bZ z=XGC&k0H1jMlr(aJ237s;mUI0oZqx_%hCoH(3V{KWXFyfG-{yTqu_?`;kQk%CR*%XESZ2N&ui&GPf$~F_3f9{S=sNn zI=-m}K8|C3`}N;Dgn%dOVq~>62*PHdxn*F<8CxP=15W4EW#BRCcnBaDr2t||@WHAh zgZ<@6q>c~Z9VPSCN)7@qV53q;{Jjg*LJ7!$AsrmPVyvguB@WmTrgRMn&lFc?=ezWT zfd$)Vyo%|pd5=4UioQhLqsRxd?i2u*O&IMUW_A1}XV_@N4cd%x8a6EkFoWRy=W`9`umOsdtrINupTr_yIU0Zxhk}jro7x5u0c7Uy|#KLvSwnPmTFA5va0+d zF`cF`g$}FqVBh~CE_t+$fjw-vqR@nSdA#xl^d08!-OTToJTNUNQiH4F_dGsV${Ek0 z&QBUtHHI*v!5N;otX^xaJ;KeAN6NBBEc~sT!WVTm1*&>YIV1V^#X8MsvERJwUYD## zSBz-|5MZe#^V7#n`@4@_aHTqJzGn^fYlAhoR9=p}qk>LNFFv@7%6|)XVFzt0g%+9;iDUjN z7e-9_V2WFc{S#K`sug@m;T89A<^AHV3Fy9lscno`P;>tnYLUnB_;xWm&ESQq6V18l z@~VneAYL(aMc??^fTdD>OD-#$V0_^b$7;DT9IXvas* z?-n@i0+}sQZ~c?S5BK)d*QxNYkUYwNJB>{Cqt`~+VMtCy`RUW8`ZW_Aq@c=9 zcAH_VyA`HL<#RteTt3N-rcNsJsstHaegA*YQR{!tQ4Zxn^9dUrXve6Wk--_RNhW%6 zXMGix>JUZHTTYks@1gpcS}(mlc2uQbGfLW%J3-Ad;)-zE}Ks?j&1AYxPKpm zs@I4EQqZ!JPxY|c{ChupU`SLVpKp$7kuYl4h$bO9^=abmx<2>b_zENyWy=NEzkG2j|Qyf zi09DSIy8YMX=9cGmQ@{6`!NjY3UTYEldd6^LB2YCu8Kj{D+) zXw(!rmZtoSQKVMCa>>N2;$u!AJZziZ|7&&JYM;SC+@<3&tLmI8t6jp6&7dPjj;W7G z#xR8X;tj`G5oAQ@(RgaDNe0Fj@fK_VZ>^eH1~MvS_YgwN{B&|2v8yh`ShT{Y;_p-H zdBLxla`A9*AO6g}g_9$GUXP`Rm`M17bkQ2vm@$GPf-2!%&6BrGl2d|BKnGP@w>$7e zGD;A^N2+$e8mAK1MvSoAD+c({uUWv)+e}Mo0yfgkDNPvxVFiVl`6iiR(r{+5JuMO!{aA8zh8TAar$+YwvnV{LXRFe37=g(Jc zPkD0iH*Yp%LP=q9UG9LB)JGWF1}R&em7lSod75X0IcC3RmVj?>GgrkalYDUv@vRxj zH3)FpAO>g%dpC+vu}K*5^b$jd8ds^*=9wJG%Vb5A?s#VcmJ>v9&=j zxBLKfSWCr@Ki_$_jFrub>!Jm3qBsWq0uPLI|g|MWinCBJB z$yDtt08d%N+RNd%NaJHL<{Gm22%8f}t1~%2$ezls!`T3Nc1-Sua&-`n*IQ-BHSDvt zYQm+lB&+!hj@BQHgT*!$@plm;!WH$PqRf05qAi7uO;&ggiEhA-sX$fn@~P ze?>$U|k94P~S``2h2 zghf*PF2Wztv4uXNaRDm21T$75`$7tMxDDJDwD|+BCkbL$3eokR*#GFnc*+qVM2^md znP@{QvQq-U0RJ>>%o5xqxdEm%NZ!Q028x%dm3=prs?I~&D!kvx?Uvw_Te>MZ!eTeS zI9l|Y^xa&t)n*_(Nj%6%yya&4N-xSXw#d{#%D)NsTSb3HNpKT<@a*t+@=Wo$N@ir! z!T;LWC{EaTe?Lvshwsja-H4@&lj;t;En`-|_A z#Di#=@Ptp;Kly)V!h3XHpfW^judZD0@P36i6<1pAM@Oke7uIwu8c|<$+FK*MypfBh zosMP(Jbg2;_`Ds0Mi|1=SJvT1t&A8{fRM?V>J_HprWWlrIpQrc+1z-5m>NT5io#=o5S5j8_Uj zFw+z2mfQYTNnQVcG+kv}lTq6rgV8D7AktEzw4{hA(l9ziL`7hPG;AQDw9?X|bSX7p zurUObwgAb|4WkE)?VZo_KEM0(KI}gCxz2U{>-2<&e4g!mR-L%%K|S0Rye6sG(mKtm zq(26>Cgx)JU#t$OmXQgA;>b#Jr?r}owr5AmjbRd&mQQ=0=ku!5IW^R)B-N*C86yT_ zb>rgtZ6i|s(n`i;Q~JpfNeR3_CAhGQA9{|e30S55NVz-7bj6rkwu17xJ*oiYKhQBd zPv|u!$5g5oJG~v$?~(dJg2w(m&E>FCYjr>OeBb1I-LoTmClQ^kU$+%j!wR+707)P1 zPPI@i12TBcNTx`k)VFfiQgc3^*B`+7<>bU3-adVl^x&IW8((;@2gBEfvyx61Z@}Iu z9y%nM)UQFdFb^>W{yu@i@bRM*g`M_^0)%S}XDT~E0&5?JgO)xQhZ$qRG=LsDJ?PTd zS&0)oL*crdLrxb~YA!DJSKL1w@2LYgIClVvCVftD%YQZV)4L9>ni3ef(;!I->HuoY z!J-vr)u=pFEa-o-zxQ$Qh}=qxj@J2oIxj^g8ydIbejN%RF3Iy{0_F|y@%zM^gn%-~UuWCFQs-GzUOi^McfpYYt7Qx_j$3W2bZ6-cf&7`x>m?&Mht`%G8 z$YqfWE9y_An2&!8esp6LpJ8&5QA#02iAv-L%&9@P6#ze_C}u>jq7`@Z|%G;*sL zb{9W0zGofzVPV-*p^yBV%*8Y1CxTJ){>0J7St8@wxlbuRnKax}f-jpl_x?skWR#9b zB6`}Zc3+Ab9$XE&_V|HF?U<(N@{7qnK|nu_>mta7QzFyqMxJ1_mV7ONm&wV6VZ8Ap zO0^UHhh-VM_yd~JmICaEqwnHO)hVEhB~CF2b@_L>?2vaYOLfmTh-stg>KDD9hHsM< zyvmgY!!woG#vRL1pDc=>L}n8(1e7tE1P0Z*EHxMfVK<7VK|XB=NVE2PruU9ak*%(} zUGNjdy`eu)cX`2nVv&3y6?HE(2Iq_-8sanCT)t^KMzPSY98qP}Vn7uzB^4HvsP1KCr=fFx;jPVuxd>gDpM`D4Bwn=8vQuhn5Xbv z52h8RB=^JDX#2AsKph|jSnuqNU~VCA(H#q-<)Yh;IjvChz5*L}Qn0BL(`WcAwWXk^ z^$?M+zz!&!Hh9f6$*2xIDa;#UYS7wHpNoLOQoR6dJiNRHO{c+Mx|5lBc|t#?sP^-Z zNQ4E34=ob2bEk@LV!}PSh|_mJLy|r(Tex^Cz{r>@z#{$M8O@G|> zzFyu(4WX;v!2ehcythKLdtg2plt=7nn5lO~t})}yGX4DNs|gZ-CJ^&|z(CuSkLsC0 z&AG+gLP&ul^+w7pUDq03_@-G-!zKCmx3Fmh0IB>=q&=AM}#6n+>%{J;pRTH_jcmsAj z!*7E6=1VpbT|jdAz7j;v@i=xlc!HektAJj)#O?a4;)hR@3NF4s$p31Wno8G!MN zHLMoNHrt9hZ;JZkBWebYW8dxMk-ui)@^SQDQNav3ebKdAm>?MV$d`b_(!t;93`?H$kb4z5S1x=O%O~%>3YX&;&?WQYNB_fjJ(qSO%!43nzD- z_oV1mS6V*AE$;7p&o=Sa=l0=(7{IED$jC41XV-Dgg9dq@ z@y`#7-Wy#Inn=m8lz=^GN;6&3d9GX%ycJ{wJzS&y3=KE{sQ4Ff?``JT3+(z91 zEc%u1Q`8f~&R(T|pNJGEsGCYPRJ#xvowc;6#9pzoGsMj?be8SmK0o`*qW*7Mxenr+ zbv%YLk`ZUAcLncO80>J%x1Q|*!wR=t=3^DCl24y?&s#;bp3JXoPIgEDPRszorbh4u zfdl|MU{{E_%mN2yDYnD;wh|4x2l3=ZX=@S%fv8n)s!gFp^X*5;0C1c3*yn!d|+2px6?2LUqDoYBxv(w1=L zQO;^kZ+^72mxPgXFuP9=`k7wB^#NKR$Ax59ul9a*kZdN9R&n+vt-~!4AK!|`%5$s( zh}9r?!7`VYzlnW!dQ8JrZGjPgyfe5k)kME&Hgcf$@#FXYeJJbQBhi>GEj_-C7YBk% z_1~J8qwi5eyn~9Qn5$=7t&G{2C6se-O44o={-@gS zWZ!w><13l?hncQvv2fDN?AAZ+`eZJ`Mp3u!#tCqR`nZMpQT4)fy9R*u3^%(5hXEHT zLEU&(>t9xYb**?TQM82|e%w^?sG>$-R1C4c6z++(tt=9Awb>Dr3N%2~a{h996^-n} zJ9KM3+CvM|3Hhf`;@Aa$y<^2lk)^=T_ch`5$oKNC1p8H(>My+%P<~o@19G^-nhZmF zB@H<}X}kX=qg@_KVk%Y^TFCowoXo31Z#*Y`cnPb|yQDAodaH;W8|HxEGUw9BRu#&I z2Z$D2*tuk2Vz+pPjOWpVg(50;mxs?-blWwYSKaL0@7~d1D`r7Hl(|^4fP=g95~3s% z7EA%K(&|va-LrcJBX;<+)~CJD`+3_dbhy3VX)Go(hW4XntbCVp}TE&-DYGsq^%U35dxUwsqZ z$arQaa*72L?C*94nhd|)2%TarNy=2&e=dFKt`hP0E^OYt*(nTAcnr>I1=Z}1wh6nS zUq+>~YPunvkgKfYO_Lyb)kk31eKK}6T73VuP{Vc-0?v*a2#NFHrLdE#Vd%{<8Da@UsqS6K!px@0-zcyw3e0;ZGNkj|`f6p7^J@${Ue*mvMUL^S3TaO4zgQW1oG<3^(0DSCZH`_+Y)E2(Cy}b|o z_6hP7C+4wn40$LwEnu+Z_XG8`MVXC^8qXRN&LCd!1F0ycAs+BH0%&wC_s-(wwH8YO zn8@uDSeswdVAa{sjpg3{JGQ?Rt6o&HJ?6DjEc>m(&v0x~(?u^SI8YbEJeNBZmrSZ# zk)if6FWd`E%ox{m$NEYiEw1K&8_lKE7YTp=@`u`BH9*4W^5oW>;!{#l`KO6SlE7CqLB;fLy?-XgBm@`l;N`bKxXz;>+W<1C< zwx_X055k^8P0LXt5*UDO{=+67c{=Me8N}k!bAHsyYcB~>MlaeOzTc{6jNVr$2ug>HWAy8LA!R7+yJke`rw^b*)v*0yTD}`ZKITZFH{RDf zaPxDxa21V)u22eVQ%s#}Jou*JTLL1R$C%m?G$387Vz8$`>m?~)5_8X0=A1F>JhgjT ztacVw%(%c2-Bea;bn*6H7HEZ1U+31>R1>*5`;OI!Ht-*lNw15#sbCS5Y(K!^PwNd* zp3(*213%OBW$&9j3LM|8A!hoJ0}w?mPV;7O$#DhQ8wgFtg?w_B0$BcB4I!w^*B6@3u zf}~XFbGH{HQaSO8y?#wqu!!TzNOXKG1zg^!JL(ywA{52}9;^!@qnb;}#-EGNqY#VA zaaj=zC182!Z|cI5CD7|waF@!B=0RqHy|p*uVS2cQoegP!gYS}ovUk-$;|0K5X{!!G zROU}(K%|@R9Exk=ciT!0f&?#Fj`WhtI{Kj`YRdi&7S(~9xc&ZB=r`=+NrM8|Hk^Y zA4~&CqwEj79lpi^tir?qzkxf?sa&B<#DVdACd%p`lhjxx04UOfbBYn3dK|GsMWHX0 zeq4a9ob_n!rGH<2eaukOhgpST@<1%~MS5f|Kgi+If$ zVSB|~)S}wI7Z~JI20{fQhaH+G_w&bn?(r|ay(T)87h$>DcS88a8gCUD+!NrR`qXJp zT<$F~kuzL$pq^hLGLIud#J^IGLFR&bVPfgk>=iZTU)fi*;TyEcRMq@0ef`f2tLhO6 zt*#4A!ulWbA=9RmT-? zURsk%<%P1B)thN=YoZOJgh$(F*@a%2(_sB?$YuZp#RwL`ndF`eUqp=fawLrO#;6t( zidw9GU$qXo zqW|rjI*v>*E#CD`Yk9?cuhn5Q%IcUKl7H>y+-6M7Vy1~%Vc=KYWg`%^x>I*LF ze2vo^cLDpK2S(QfIzSD0A4evq2YmZ2m4kVp6I?(LcD4WL0?l!p^xrMms!x^+M?-Be z9@nMs*05-SaHrmUO!r}`K=q#V>0>k68Q1Mu5>UK*1+aQMk#)Ck%KMa} zWE-`PeG#}IM-cp5JQW$@{jLMvGRPt_NtNyW7ES~H<;j5#0^Q{#?CgVJKc{;lVJ|~k zT46y{^d+tGZAQ9s1|2#F5*#NzS4Qp{^B+>*LGqu3{_c%IlOibA}qyM8V;- z-|~E)f3m=%sYK=0Df3*r)p66A7oztTfedj`1HDffcLkLXGn%XR^8XWT32D+q&1y15iz@`}FhdO&|0G z7s5v7Ao+T1FEc70(|P}VqT*C@KMZv_mft+n4=?srEGRd!b=6YJh8yvS3q5xc&fqN^EwG2t!v(5cUKp3FBkoWwsOJx*WNoC@~- zjTqgNp7fmYDf)aqvf5)R@jIu^s5-iv9cnNU>iyMi26{+A{N2>i!(G>3_H z>M(%#R1)pk;gr8f`#E-z-8j?Ng+$kRPsCl5vjpY@y{-1JROw51jo>4)%74*|*@DL5 zm==gPBN=A2yFOf%NswTrP(BG8cf1jIZ-_#;1=pB-+nR^%D$6}9uGeqVuiTf`cD|E* zYkhxH?DyBPIfGHErgd(EYkpuDYUU=b=w!N7rV1MiEdWe3S;tY{2Y^eJ9N%=S!|&%& zVZ0YI%O8|wwcpw~_^uO%Hc;Cfkb8;BniP;^-cHZpW;xbvE+M7jtY(Wf0_cDA%T&wUUEr}O-W736h2ZsY41gj9PfSk0?qTf ztlR8QfpK}-Zg^Zfd5RL)P+Rj!Uy{;_QwXBXILzIsJHv_9Gt{}JV!Dqs>RU4ndJ5t) z2`Y=?P_CcC+to&zYgv}6R9)}CLi^l^H^YBrQ(EMOD-%@l!Jh=5u*>fcRhz~=K~NCy za}JGV*DE`1C{Z9_oZc7RmI&Q_y3yb*yL^s05+VvFT_z2HAArYru^em=0Kb2QLd{Rc z#ok$2o?z0B_0r8`C8*RrZaZiAb12osc)j6ammmpQYnoumA$lz$V~B}3=^)zjjkq)` zme_O2wH}67pSr1%`v#(>8Es?7L%SxZ<5<+BO%<3w)Oyf1-la3(XR(V6eiLJL3~Wwt z(1E|u>uPbgI}0Hd>oLm;(0T{!Z*Cy6!2)dx(0&z`S6-vyC9gBLMT zq&rDhoEAv=B;42FYv(PYC(_n&hunGrER=khnauowCPx-I7&VG*^O*s2M5}C7O zXen7&Qt1L7nc1uhwRG=2Cp8KG9)VP#LZ4zJSBq?VEnKQ`I1}1$*7=OP!TO?kwSFaX zhg89ZG62FDayN&LhvB@=9Qe)w6J-1&RA^Rfr|Ck4j916F=x!SCFdyX!S9GbbF3WDu zy=dQO5}C`5uY9$BQ6CA=n7&bWSI$Nw4bITT^&$I@F#37k#8&*&l@*gQI5FkqK5)%= z{#B5;I}MTc^2@+|UQTPsuaSBB!93ZVl9yX_PWwvN^OZi{QyJVC@|;!inv=4zFC)$2 zbs0cWgu^qD^B$5GE*i-A(XDPp`?|6;SVac^fea3r8Vjw`Txhpi0e9QYNb#~`4Jga5 zV8mTtZ1)!8MJbj{SP0j<3Jn4n9EVi#q)+eR%d1g-LgK++Z_@(al)aF##2nEgma8Sv ztAC`)@6S(&R+YWCl$>d{ULe9n6Ds&MDWt_E;WUaM(hTT{}j4lhEA4LlJNAm0;fMF zb1+jnpCj^zwu6e-)7w@>kb;%zdBZ!P1_8cH$@`03i^SI>=@~ zkZ4%_Ls;k8$TG7Ai115ieIgKcmx3MVmhiyV<0ccy#}FEsak_N$cZD+H$qgrgqR-X3 zJeP;Tu=}J|r}a{Lxtf`Ibe2RzX&lz`lj(`)ACvti51ssvL!yE7Q7(k`qxi3S|IL1* z79)`_U9qPofL6T9e^!TAbXp8z-(KKeolWo}G=5Lyx(G8C1-L)T)|LPmSN87^+s^B+ zqHeV9%vJ`qRhz0R2zS{FXu>Gvm&Ny}(P9c5V87^VeJ=xN%4LcG(*$|q!9DF69_=|A-HXGIK8mgu4X0wT25!{a@(#ec z4}uYPl>!~C!jzw=FF(7-EDFPE*u-{w8XY*5&afPh-+FbYXE-|R2j9Kna^7d?h^cmF zLWFa0?WG{%-X}f=`JF*_1L+@5EEQLZHwQQWC#9j26!M>ObwCW>3*_u}c*2==$}Muc z1DgE@uTD+cbe0qqLN7azl$R&*ikB(Xi=kP>+mqMZmaL&$x~`Z&D46Kuw&7d~6~?6p z;^_3Xzb5uOOb#6n!m``Vi=>Z^;y$ay9qHgsH@hCztt873UZrX2|InO0xR1QCsa$hn zG0Nsv_gNj__L&r9Cu_fE8f4j}^cbgacQ8Ao&|uBGD}ukIL>$&0&>oI7+L0vQi#dCV zawYQ(2uSYHQq1u_X~^iYjUPdbvm;`Y|7(e{k*2MgfHYWt+(@={qpdmjwiksxBz2&& zFETj|aQdz*s-rCZXUVQ13kqx8=ma{jq)YoT((v2^yZzokE#HV>j~DEze-oz2R9YZ> z{mIj=`vBKnp!Q@DKT8#W#5;h(haLvhn>^|FVK!jVF06_%<)a`pD8jzazVsU$FMIU0 zMV$U6KsVIpC^eJgfTlp0`fwaJ$*X|L7do0Zz(L&t@CmbmbT6a{1dN z^dP2*kmiSc*?#+MD4Z9rPNpH2mZA7s^5AYo77TH_hrXNk%$l zrd{%pgi37PC8L^BQ1;ihel7`CLHGV~zNroVo2a{WvpzqmZ+=Aom`2XoUCIlmiSOT^ z0%7A|TE-4bu(>M@l-@>m;*w~}14h;c=4%_n-1h;kc^v}{le?)-J>RJn*{BU{(US_y z_1ytoX}8w5r=Lfs5Br(-O~@oG<%~Te7ZRc{wy>f%vi(cjmWP<+*A6A`jx2i=V>rW| zYtO}bH1<{VkW+lD!c3x|D0!3B!_b&1n{_taSfl36lTbkM^@<4&2ycmh?|i$ou_qU555NFo+x(1gOs zEZO4MU`{+`q>hR^;(5Q5{X3CAei}}*?Z>fG2N-_rx6R}MK=OXyaRl~<#>Hrkj4{fJ zf^=CjrjeXI+Js7HJQPpRQ9IXb`cvn*LF~Z3xSeQ4u>J{yG?eQDG6_~Y0(yrP4)2`M1+1gC@BB>tKSN#}={C@bwTD)q+vCHMt zR&VQ<1n;2adiGC6$fZ1HIsZ6g(Qg+n0fc_nn0gk1fdtSJh^LMmp3!~+ngR80P^K%a z^h-)l)IAm&1uik|Z>)0LPZTu3p9|++U(XG>w;nib$_U_XDPHph4qBM#p@aFDGM^?I zup*@#fyQHVtCRJZbfCMVIw0$A; zc&_&^%n2M1yr}Z2R9;>k($Ydz6p0so{neM@#4`;AYcMLY0SE}i?UmMjAB z-k2yZnm)UARIU$=*af`4wAi1KX+3+@7;dep&ZBf^LQ6#}?fn5NN4FhOOgS}EmAXlx znbraLruU6$ZX*y1ip&H|1-vZq0I)@WW-XTBBTlNiI9ZF>4vMdfUDl?4*W?D9F?&4DU5*0*U{Zj5 zq1_v2#|||af1~eC*DU(zPOAfM3N2KPDRh7iOk*v7RTOWzbJsHs8LmpwursztCxSWX zX*sC>W2!|d8ju;p&p0-1x4UIL*Xyq|rAXtj{;*Z1o)g#P?zn^OwF%7oJZKeR)cd8X zh!)U#xaW#6DTPV_=x2BLyaB1ekHyaD$V$V?qxWk4md{G7_pLx}(V=t9ug=He2?vwD zAh}quu~|m>6>a^F>Wj7=t-y&tpRdP8Txwqie>=vNen$E{Njc2Z^PdHsh3&tqih-^f zi(+}@)*5-cB1Uydb>BXaNseJA`tHQZHoi(h@egCu6i`qvzKo=t_8^3tjR zIFT|9YgW}ObGGSJ{!SPtUUDKgFj_EmL7YdSOh&e?Vq7kU9Oz2QxX zvPSjMPm@t!@PI7IFin3&DC0fy;i5@5Q-2U(XS+fw(HX0TW|g%&03TKr$}(OF{{6!@ z6vxPay}EKbFa=PD@lm8~v;EfO)a~pRZikuBMcxO*2ldM?g;AfC@Ci9i6PTDcolg*2 zZttau0_3kVBiR6>uG@R#<7U5CUPel31(o$nP}GQz9+!U*-V#i{uW@$XX8v~iz~(R5 zuq!G#)9y#A>~}5OSp&1WeNFJitG5ZIKo?SghZ@~7cFbmfZHJ`G-GAg6=i|9EJO3fJ z4ll?ka~Z13K#)XbV|@^806T^(E30;0SD6|3_TZOH@C!y$)I-ji#cI-k?DVg&X$3Bl zpbLnXBt+(Js^^2*Iqcv^RFzMg6>u_(qx>Moak=-|p&w&Y%=g;k#T@WPbR|IEyMnWP zafo7M<;`g-Rx5Err5H{WCd_x&m%II3*NVl#ucS4hUwE%+E%mAX%Q{>cMX?|Jozhf4 zegf-$S{$Bt;K4r*!@QF7?U5BezoRfm!_--b@QmO-uLB=an=-LJ`s4B zCkz-?GjKR1D737FdRmMoay!9kVc_lv22q$Y4SZ!j^Rhu)`%KPF1)Fh$OvI!VmUVWc zm1ccOiL7udPi671Pg;3>u7&CEzWZ}80$}Gw|DeS@Lo(>*4SrD2F67OhkY6+BJo{_R zGkaHSq=!0qwOyS`=J_9t?#-mKhlBS>iOuum#1QLq=SlO1(Ho2X3V;Leg;K<^JkV~Q zaiYw-KZK}5gF56FgL21GXsVKw_B3V>1qH}$nKh8K)of&C zy)wZI_pApqILl+XC+O-C9M=0*Bs@8(#5jN4c78J1x9{xstYpIp8-#6>R0hRJzJ-t> z5I@|0cXBaD+@LmUW-MUKj_)vmg{^St9(cpZy@1e?kZarO&VK$f^MqQvw->54=QyVY z>Oq*`_C8SK4AICGXDurC+vQ!8EftRwAAAC&tB5Ne-bOGVm;%0H1=BN8twW=;yi^%zFk?K$2MJ0@@jOuMyx_-YaddC zx8Sk|dQ8a(?reb5eeYASq$!$66HQ!8eNtj-nk!UC3&^B)#?Z|QC-cOmDtLi3v~&H8 z@S5^l|Dm5Te@kJ=@JmMM&9TX_R9$C_1Tdk@B#OT*xpXY7wCKdyP$fqj!AkP7H(MVaY*G#6BF7TG!q7Met$ z=VPIaq|!@sSce18jD`0E5-fceMm`PXWqm!5w&F8INg;Lj1Ik`zDmgVIv_5lfw`v&L zfRbB>`q_r?kcMkkt%lw#D*2V!8)?Ml?e7g$ z-XG}1y+fk16da8yD}A+Fha(s%&$UQ#6wLcXy80jaxBSvXiNC}QGe)c~)>WmsT#roT zixpdNCVK1f9vz-AykZbY{*5I|TDsu9IP8|~_xx#mn3fTQZCo zPJJ8_sFewrGxbvo89gzJA&pv()KV(x;k|z%owhhVF5=CGeH{uhn@HKd{MVv2{FhRD zV)S~dkshft3!&{SnbX+%I_J+{f zIsQk*{@#<_1EzSfPF>u^e&AHd52<>gdgXeCOEx2QWR)r30-9c$>c^3wk5fB;}OrI zeGB%n(T-15p_{GaCuyUn1a|8=wJy%RS^(7fZo(Bz#8)B{-eBKzmGTS6OE(4fBYQb=4NKo$#LZ;+Kscw1A-zCCR{=zbx}*OVv@u?@<n*0Ul~Op^k- z>v^B3h=7vv3jBoYt9M*iKgvlwgJ*DB0O0l_F4aKdE)C9=7oZ0#;ev@v;j1Ymz-PJM zTi27C>29NOzUP~acV{OSkRYE{&lM#5!E~@RF1x|!>EHXQu~6IhXG^9wbmH79ap;#> zKdjU&as_&<7uX|7CfGVrke%y_U0|_tyM+q~#E0mg`9gWb;S_u$TE{%u&#Qg$IOl#n zZLK}!io-xV$$#g?`~(sHNt$if=g@v%4g)2NI|r25$eb7T)Ym%#c!EA#EWf;(!CDZk zUw5bR=kjx0?p>hAB+w=A;w~2jo4q>#A;?R11>6fel<2v6_1kA)tXmWu#r=rp&DUe1 zo`-|Zp}>nZ8HK1MCmlueuo^^LW+1O!L4%@8q8HI$Y-99QMBWjeYuza#zzb4P-DaH~AxK~#3+5Ei zf%R+yl3ET!Eo?v3^1D%*pIdp^M51EBQMj0OAOrYh{*B446Y-)$QJu`0%_1d$1~83- zAVb9nZ)1gpZ}DutriMQH#$=;2u5^ST7L^cbw?-nm7>L3M{|^VN+{zjJR#Qynkfg0) zdv;kH=Ci)uXFa}}e|zHF9$RJocr)EDHH}V6-T%)~1ljo~5ue!2Jf_qV1MxLXtG@1i z&g`=gE3TJzQFk9)_;Ow9Hlws$TAbGLQ1tiZm}X?BubqSIIh20yGhhd(A@o}orc8m~ z!{y5`+dk;OBaz=pU5+(Lcicb$oQ7Q7JRffwme~>K?-n21pdfnMQ#39D4GWTiY@l1b z=If^wfS0XuibajV80<_Qi^{Vg&)O1N7`<6cL-zbMg(cuArwbjAf7s2Vg)+8u3>K2$> zbzX{eWq@G8|Iyu;!~h9RM=9^?Mm#&6?_wZZImJ4fqu2{ihLR$AY*d>g(lTVRQUa1k zJd~h2{SKBCa`S5@f-(|Soj}Y!T zMf{1%BtO*ekAP^4$LZ`2M@ZX1y%mwc3jiPRu?=zMB9t=r4fc+4hs$myg)TAF$*A%Z zh|D+7ew4%(o)Wp{dK2xA<+2v=K6RzL4{Lh9U{latiQ_Cj&?%))Vc2=iGFFb z?w*2kMBBkbcm~cW2>!uhbcaDKczQxl*~COMg4LB>SS#k7`G9JUf&RxWFi`>Q_l2Rs)v;kWp+0tF~T5R@y71cz~*OT5OK!JrJ@A+%apc)V(gEEX{qfek;C`IH`N!5c+EI(y|LDwx^;g` z&kK$?0`rmTp4`Q}OCB`F=7Q+~QG(%$H7)s18@!y&JF&{yr97`N5%=VT-j!P0FiqrEDyjD8;ZS8Tg@!f|^$E+QZ-glJMOshQuym9h=wGZ20 zDD0O_Y;3gL2Aj&gf{}iWT9e!+i|!hTvSf3y08FxMTr}RMh{&L!K2gM`(xftDwM-&T z&t6zb!C5hBSTd84mvOpLat^&Hbn`x_!Qdb5RY(Ein_~OQj^F$8VQ)NQbgSbbl7#x% zv<2}(w<)ycNeFC2AWho`i57jU5yxVuV zbO#gM-fO|p-%Y;_2L|%cN_-28Ey53RmI7hym%|0q5&-yk{rABFGWQi{{iv4|`xOJF zkb^t3fG`UUz}C?kvP1!z5DEWK@2`2lf;bf9_V4JOZ*sD(Bbmryz$dnc41-h`;`}d? zOu-=_MZ`CQsFEb#eLL`qUCzG3oC>m>bO_%1CnK;!cFp1XKf=gE2CZbQUxm@hY2+pz z@;WZKZ{p|CiZx#zS=w@EdppD%)kCJj_w8ox^Pb!P8FX>(Bhn|Ga=D(FTp>E|6K_Wj z7ksR%eK+VWg*9Q(c8j3Vhh3u<1+Y$Xr+;Lih^Q6IYwl(baS~sDaWjRrVQP^hfIu&o z6Z*!YC(jA@o^?$ok24+n(HO%4+CdIPZSDh&V=5&TKjoC^SuBw*8jH6=k&EHVOl<#x z$*^fX_!^UkjNKFKq|F$232-&Sh0t7Ir~r)Fg1s%?v~CuKLY@?v&~5!wm16iUgbaS* zcXqI)7Pxsmh(Q5o-vuMCcFuKsX6dxE98eDgOp-~T2mKvK#y9M3LaFyNri-fBRCF<5 zh2rA9*E*L{Y!$y2{;=H1k+sHKO;Nhgq-tPqB)ROD56A*0G<8##RlS$`rEyd`kKCPw zod*f(>BF_N-{@Sms5b_*UT6%kTlFn83ymPPrHN9P2eBPf!~)#uV!`3JtM?mxdJ;HO zN}R0CyMD%vJC^LD6`Y)Gdcm=e<5^9_jkl^uzHZGv-nG+!a#V9U$^7qd0iIOH=CDDu z<&5q1pQrsh{(2;YJF!&`ye+}##2+^0EAB3RwWXJxwN(~2-P0-<2q=uHQV<0NQsSi+ zoON7IR8XYr1)^K$MrbUS9$n@35ZG{%00?nCOC>XMTuG%#mlmULGlwbe`43O&&E?q8 zyn11*f2hxqOFs>ko;wambdsO13XVPL98akV(z(J++aJJ>r_kGM4cP`~=184UkrRdJaT_YEBv#_rALl4@P zMa21bLbyv0J4i-!2vU&5{X3@%lg28*KItN}be!kPcA6|jsP3=6TaP)XrI(&xD>qHk z?S-{x)Vj`LHtFQqDfd4xyL6hNXlm4H@;wVGRhh+{e((M|=sgeG$5S|8Ab*y;EZcf@ zv#>gP%ITgcOg@$(nTFKZ=8anJyKJ_J~tY{+9~ZZWq|1e$TJ&+8Ec&iXTagJ3b1 zm1E~u>uxem12LNkt3T&?K?gf49rqlbq$3bH?6Pl5Ul4yuHjJ>DDy;5#d2&JVi`jEl zfl%QMsUziFm7ad%t58FBAk`{+#En-S)L1!R4rf=W3D?U|Cn85QzF;{1^X0rFfcAJ= zVvmveCx8`4QyldOQtulv$AO zy!mo|!QNRnV!`m>{q$Gn`H!BmmMYb{t|0OAvf%Eol{n^Plt+@|LdpUO+<=Hkk~&J| zgXRqwtseXnZUt;GN}@lNC2tdWVyvTRjlDW&jzb647epEq4j z92H!s>Z+Se9m1PG!ITmE}f6UMK^DT`O|DH?`c!N{PSbpXM_j7?~A$M!Q+q z?NfWC&KP2h9Ql*DHMu6&?{!wGVpBD`otY2?zbwU~tR|7eTsYdh=O;LKT)zCdL1Em5 zcYhWk=7NOtjuQ5s@{MH@DtotfX^;=ESZ>ep5ws`G^t!gA@>!%sdGd!o>Q1S`^gW8 z;#DRO)(S)z|z@ z1T%ND0rqNdhaz6lTL{x8&Zo*e-!6D1l4a8K_g*bIkC4V*-^O9v?LU$bb~aONkTiim zW}6f1^k>aBA~q~}b4Mg;Pb5J4Yc(@O8RjGs5mq;%&KSiBSu7lt+d2nX*cOiwfw;Q! zFv7g^E9o=M9!J2qn_aF9JCgut%%uXk8(!vCH~@0x-M&(>4>=ngc-oN#qJZ@hTEk1bIOlhLh}33OUh)>rNP3jQ`x?96i^-K%}#VhXs<2F(6Z zAB0buFN;gPiX*O?{^CccF6=G3f1t%KHLw9im%&}nv?TQY8uQX}mQ8@{dC&=o7F{l} zo=*$wHszhhpg;0Q|u}tTFc)i6M3X!h4h)&v^ghGg~KrtV@UKcStS=% zuZc04-uq!nn-Z4rLTl4c92UaEZiz$2UsC=;AC^UJEDQ8C?jF{qoY_`Dg1`0bu|Vag zg_h40o(Y7q>qN-?h$WO;U}z=f!?X41@Rp9r6KX`qNVm`Wf;qaUvgi{p>-9azlA-M+ z(?T9X{l$-bBHIeAFGr;T8ly$`0ar0q znsHNvpkqNB%RC>9+PfXOv2|!cTMV#sw|aj*;Z%`zoc1L3%6Y+BQtYMG2L5%nKhLjQ z$V%ohptWz$xn+7KjV<~{<_anQFS9y;w7iAf|NN|qhgD$)a>X!uq1Ag2yNvGGbSE0- zD49^&tV{)DiiAah8>$A!4sK{Kjawjl&}3{QUskh~9i40>$&$7#rNXJ4M4|*}(jT(A;Dl-BjK$SDv;Jjl7pqR?x zwWtpfo;0s7S*|yPus}NB9O7y{zdx4Ck5RO6^4Ez|H-G1v@4lP*_Z^P86^{Zf|J%bVh5KKms%yXJX zWwic;>EVF3%e1z{cHRH70HXYJZ~ypbMfz4h(X9d|44NZ1Zj7y+M1XgDeroz2?tZxq zEn*KH-MXMN1Oaq4tuIdDRdV$kOWCYw4SPbj>ZIQ%=U5oB!jI5(7;h#I{hP(gCtNY8 zF<8)F|DLw|r?S#xhj$bAGD#~44CkYnw3LL22e@mwL@`k%XaoUl>MAl9Zp@n3LhL4| zdJEj(Ias%&Zl<2IH-`zNG|yHETq}@h!!2YS;#=FJM#7j6WAbEecvBWKm44e=2brn) zXCH&x(Nf@ze~}IrY!cl|xtjrdFUnD`fj6QRJY-kL&~zq!rSgs{W&OdcoB}@}nRTYc zzT71@{=ykuZ-9L_ZSRb>4JgjfH*VCUNfJs5LZbY>puTn_=e}S+lr=KhQ7>BGQiosp zqaF)D)h45?6NrKLjUT9sttxy>AbyKU&<{75BO=oCwW6#=J2c{)5+BpXEjCl=J^sW-}L5&OU?5mUY*HK z)!hEcvs3MVvG``sILdyT@pSOL7{!k^%My!IN_z`R;plf+L(2!#B}K5voc z&y_&~$3%3j74w6@t}A3H6Hs|^@lLJ0E*%BV}nbL?&GcR7X# zUjZ{~!h`jou0`hCj1N$pP9b;5CzzTJKDGF|_8pU2Tz0-DP~-~TFI!`A#7j5C0Phkz zg4BwS(*GL@b3^`gmip+Baieoc*|JanjTkI-avD7uy6M8)KKmrKvK7bg-osc`=Ni)| zm5N>wp-a`_D?91LOPtA~mZ+Wq4OZqWF#=!I>um2){!7($5G*v*Obdz>fAZPNpH&nV zNXC4>U|={`ezY^|I}`)=6uS2^n) z<74A9P$rx8jUB4(C&^w@wgp1l2>y;>Z1ohm8nL@AYh(>FPFi^I~o~H#hlMmTb z4Gh1jzCyj``Bmm;uEyyELSw3df~glEVO|h)Cc?WZ_yte@)ne^2qT{#(ruBD9@`|4B zubaq>mF#rxvnPk5h0s9)9t<@+&a|{CaxTjj{3YP}AghVeDi)Es( zL;Kqkk#3XWSK+)8N#Z?HNRqu|n@TJ*J^SN9&JQn%>?j{p`>&M?t}7FYxW=0oTE(f1 z(DwR%D1{Gae>Gkdld2bgevqZ;9pNRR5pQ!<58>kV6!CL0c?rbov@hI#4?M>;R~Ck_ zz~p{JF>o~&em@;ozdVv?*i?R-PrxhE)elQg`bDRK6qfDDP!62Q($cvAg>w)Yo`Mj9KMok0LTr+-EYW1ihIp;peT*pK7Q#*DZwQeL zK#iOmuXZpW%NPgX<>Qc5`Lcpi72dD<0`jB1@mGXa1b3+g}A4(s!6w&;F07@9?MkkN&^*NC+93QAXxX*<2|ULP^LbsmyDu%e}}Rmz0rl zjij=Zy{>WZRmLTSvR#{S&3muw-tX=6{e2(5|KR<8z0P<(pXa>J89cvM<($n6@qA0H zWK!7k7I1S(7N7Z6z`U)IpcSw5D89D!ou&Ul>PQ~vwcC@!PVp8}ptNF6#N3Qk5v-=| zsScU)d_LuT=+(PgYPOXPrA8h>1!Il?;pjtmJCV+aY<}^3vjiB6LuRcwXuMS zAlqt*>cD|66PN(^u5*t&o79hYSMmLWbS6>SzK1L_Q|0M9cGObZDvHE+u$Tz=maNFN(cmD_R`@fTC4Q}K*?bb&r-7-)RaKjg(5@D>v+--r&Imbi$c zmC>#XvW|Oy;OWj|G^k{he4}Y7%Xjs09P5@Hc!2l@Xo#q%Wk5k*7%cpfelaDiTK9mj z-%4d7N5Vi)osLmw&r*pVjE^>}@{|{ng!^fJUzu()O3m7~Fd!-cQ$zl&id7$jrE6lb&#`?!q#9to$!{=S9 zdsYSLB3WlRKC@3>%t_Aku_Qbs%o!9NhxY_-LY>BrMTlaV_=hmTpKLRv9dj58pB1KN z5v4!Ub)`99M7*6ttI0DPS*=I%>|M5C-D z9L5B0nMUa~;@y8cck88+@J|eYFaxC5DJ<`U=v6(w|1usS$n@}3FCRl2ZuqG^y5X7Ya;(jC z?T_>PgDq9yn;pbhtJ;T?0#6?0KfEDf=I2NSP(ycBX`>9ggsDQ#+b z)Ot(6V_nUur}MXF({~PIt_Up#e1#Di`W;z}?-|`QvDG`i z*nIpuxX4W()hl;40vXtOD_0qy&A4I?^S{Bd$bR;mg+KL#Pgdd^?wGTfWiLBJ*M`>V z!Lfsv7GTA2%hZ-vO!ykB~c^v_BwUIzYj@^;CO7%U)xB;y{@anxy z)ykl^&56Z`7<=MhuY;+u%3=4fe*66L$4yeA(Oo?{Qzzw>Ykt0g4G1H0n7#0Yim0Iczvc-tSw-uR_Awmr*FH5K~I+Bf`IC!!3uKlp< zwYd8|_W^=vZgX2&13tw1QO@v}R&Z-96Fro@=|_eC|IWsLB3EQN@^1(S@;Q6I{{>(1 z+gEeS9@jrMS+sU~EC1vHp(nM8HaY|6^0F9ul>qAwzgY&~ zI_$UX3(u%zJQ!KEZZYW7i?Y13WCdfxYtAq!KDzod57uf~bMeQb^_`CH^H;y|eaZri zk%Z*8*_S)d47|P39bZ&fw8XZ6fFMGmcb8M?jmhi}_?{9*k1ufw+(aLpP8+&(9^Oy- zVn&s*k77w->oDjl%WrUVQ;hVc6zN=AoR}B*;w>jM(|g<>Use=&c1&o=ST5>uXRPEn)oyznHQ~+G&I0gf{x?>eh+fNI(iPLq5B}XltJ#? z&jiqY+6WUA!X41fJ3U_0-I@Azt?OJH;Op*A&bIANPE>%z8^*}XhK4-}4_hzeuGr>v zWr5FAs0wpGJBovqxu37?sLg8jU0LWle_&dquHdJMyWcgW?zqoWa!%Pc*1efFb^S-| z#D~=EeNA^y-T$7|RTj}S=t>C_mSFa4eCbgsE$t~rwr7;vzgJx8JNHmEDM`R7cF`tc zk$vL4g4I9}P!0dMnf+vW&}&~_v9OD1PY_2^uTpICS&JBV{~$m~RC&TC4qfl@sPmDI zRsJj4$^+W`IO%z?j|5>lOVCr#nq7Y=zfvkF3!rJKykxM+`u+Y?-a}~8(nLJOuc=HR z;*Fg%8&K-SgJO1Z{BGDy_9KyeP7m03VTV~Ul>%=pH{nkFYnTrH{0RKx%e-T?n|sI3 zSGf3CJ;BWADQ3QJd;|@Duo!nn87V!n(&}sAzOEO zr`b=6hmW%S3Wsi=DR**}c^K@<{XKcSdiuotfSq`84HH_FPOE_JEM(KvYR1aJm*&n4 z5p{bOn$Y9w?VUJ!nBpn&0pN|KJ}%-4%c4T3^Sw9LbVyEE?FiyKV_v0b!+rXtu-Dfr zxA_d^JHk}`=pWD)-3G-8lpu`TTt8WN_`0MGED(QPjk^Te70_WNT}g;90Mu2@iG#wk za(zoUuW{w8Q*-fdB}H{u z1s(MK0>SYWC@xfcJ~iMMeuFO}?wuJ|!4~R07sv7H#t5UC-Nkp-Kx51;c}Y?eCONQYCb!D^`i^R%ScAle(w3z5u@`sA3N{@ z+xzDNu1dPd&>-a5r`9vBdxh^Fu2#US2qq#tDK%`2iA zf;FNQ@eZmNOWYzX#lx1kKNw_>N<1WbyhJh&P#%%FN}+Ggh}DK!{p1y2Plc$8ot#9H zPM8b|Do(3OZ6_9VPBi%;8p=j}>!}e(WPTobFRUl!jJlHs?WOqQ8hhgvCl&A&y;}n7 z--Uapf@mo|h&_e&bcemPvT*Ca>zBwB!g9P?_v(~rM># z#q7$CUnFQ}tv8y7ZC2 zZoNA#kNA*(`o>m_%Tlh0y9*q5E6xc?mMg!X@9(7=DcP}af$uuMl1q}C^s7w~r!S1| z3`ahomzDKCYY_2A&?V~(gk>^Ije#{#tsVHASG?wnK11xRNzs6skn*T9>(Jo_UOSjF~3H^I#{r?VgFMnuj74BA%k|9=PWmi z95QzLKyP!;CQ*1#b^a{Rr`6_P(D;LWjwmPLPgjw2zz|06uHLpemTFxX_ffYs9jzbz zE8TokhM&cPQ}gPn*9nxBIKNdy2t4UBp-22Zemu+Hb|$6Gug@~u{jze%AD(j~2 zc_y+_lG~j!7^7@#*m=MeA5r`B^D~{|D%c(SRz3i^vHZ~?!foeayXD^1=dUDPY?lSp zzvs=hzkP1>Gwd&wEPOEERRZmWKij+hzKdxGwzxaaP8mKE&~JZ**@PDKm1FxStNw#uNC_@6Tdl!Uf}cz zx_+O(W{>@e?W|0$U+eCl13{;7_B~v4Z4Xw{f01?KjMvQpZLiM|KURVr#8KcQZBkV? z6-V&e<`z3Y&Jv}ob#uCcQD*i6Y`&159N=_Sd*P41FYoR{Kmjoefe>|-O?PJ~1_E;8(MSWKtrFE($j4vk}O3p zc$nNoKZuCYkeQ6!eb7YIIuBUPhgBdE#!P#5E8#~Vh130AzQ6b9q588C>@TGBMJ^_w z?XtDc?yU+U1cOhe@rN;b+L0xC;tNs_MWPZa>RVO+JfH0OQth1_)*5zg`OD+7A;FCo zR_HyUd)+0EKfJrZtgm~K<*gy5<;63*GP(0Vr3)T7>lyOdjMjVJjbI(OlSWu$Wo_?g zwSQFIyn9hE)*s>X=Y}_}Ymt4UFCxu9_C$kOA|)&m*l2h;%7kwA0(fdwHMPwY=|dSW z_}lNFr=DLy)yZqGOunk4j<1@lc`mE|(^GUAl2$G8*8C|oF9;lJ&bDTW75^#G?$wSx z4`HHklcdawBa_M^B0;9; zYQT^6yY!b2CdjW26nr^$|LET~B$?@~fSiC~q+L^3T2yS9AaR>7r}(ytcWl&xtFG;h zsCTHhVfO2{tQ8KXDiKx&5d|?CLNEnYOOff%Qm77v%p{mcp(VbAlCY{;sXg}vYYwa_ zESKFdr#s94s40x{GxgLiq-!tRkA_1hO0;u_57~m0e7jCyssx+-VaYf z`lP8{p7DiS&h${!RM5iLVnkK1J!h;P%eRllImB2gn%E@UjuOJiJBOj-*CcB@>*UG6 zc3NAB7L!sDQl-@?eX9FkWglLG{5%J*1-Abql<(}!wQ+WR+4Z@VO?Pd6=bv2`nS616 z?d*_x%^{QgW!Qq?6OuX}1PArVb9cqhLwn~GrU1o^{$4Fyr=KIHv&U}FsxiHrU{IV>a4Hz^E4=UK z*}fg-;guAoFV9;S^rMB3I5`Q_mTC<)et@Gt1f(fW0h$nf&n# zE-nfYd?M0e!d#i2p{YWr=CHt1|-YagPwH$A1PEx`>R&GhIybpe3GyN69B*Wv5%kojRQFRnvi;UCr;9AQbFR;SNQ+G*?5bu1|<`5p7NHncpg4gNb+v2rJAb4s0CT z$iTscD}#`faP@%UG~MChKp{O(!Z9kek`renZdU)I)1>8d8`xIn0{)bw-1!?gO$>#L z<1V=61_laB{ZXy{ThDk{3(8wSZWEcKRobsqI}jUrT$2`H;IuK6{WSd-0AXk zqnGf3w0~K`D}ApgD`0G*1YQ5Oa(Z=MfG!@2r(P$kf474wB^T{NeS$h61bw?Tn>Nz( zQ8;H>wi`sycmWO=ThsYbdunp4CS-F+U)7(HL4+LY#r!U60Eo;U zh4jJT+hAF#A*58$bV zHVl1qC@ks{0Lx5Z7^SwYHI**ka1m2V`o|?kB{2P zdZUV^>|Wn8tpTLC926yzZ=iOq{OVF}m#NtxgEC%d_m0r=GMo7-z4vlRU{!(o-6Iv&CHnkV%~`0@CK>Opa@A_h&PDS^&j88_$= zq#Na?uxs^ByoUE^U@t{)a#Se3hq^AiXM9oIE3alfLDi?{JfISjb4&2`$#Kh4VFlpG zo?p|I=dQZf5 z*BjO)!b=C0x^${;2+EblizKY{GVH^ysezp2q#44R`LaLl@o<-qMEy7cuVf)!53sN) zVSrL`etg;zp~{z<*k2)XhCDnwnq5*GAYVDQoRU52N{d8m5J1p0(1WjmWtEE4t#9vV zO`3SAZ1iUF)$#3i($Zdf_e)b(ZJqWGH=c_)hiCIY&^`MzID=4L1}URat62jrcY}-L z$b3|?;PoFA-Rw?>`VPPMsbq(_gemmzV|?V30wHVz>d6mIumB;!k zYiB@aqtAj5f4yZGg^H^)v{yuweF?*=3)YZ#_g~dYFgq7 zzMJ($n1?ox4tTAM4V>OuA2Xa`F8E+^XHdyV_>R?unoh<(#D%e@xQe>*yr?JhBFr!7 z=S8Bmra44tcjgw(q3TLp+{<}ui8_}Tm=J?;4m{jcwaIH90y<{3^o@QiCX~BQ;m3Z< ztle}AypF^eQoGmuR`jKk#^yvwJ1G>$(UzLs@#|`O&Pk8?yhMstx}W6#y8BL}&B9uY zrL^5Yv@qQ8BbfQv$?`RWf0@3BI?9?slP*2`Y)VG%^$~Taue-|DZv40Sf?Rop!97u< ztk9+kPnQoiFZq;4;GW@U1M%QupyA7A!tWd0?aw8?D6qvQ!cO|G`t;Qwtvd4R;q%8r zf`aDTJ2aX!#UAAJ%IJN)3{SZhXZF@ZabP+;{iD+!hz%n(T41fY6Ou0H z2>h`(*&6fVV&YUoYTlWU@xz5CYf%JF&}LZURPo<6-e&gQsm9-?zc9|>0A%n&$ffzO zNORf+`!A-->E3_mgGXmP_&EPF1D*IgH4s@;v(Z<#z6KIF6*q!92eJRKi6fYfc5$3M zY*0WSV}zcefgBbmt8!G_GiqPy$fG2p0I1)Pr?eIuogt|p4JhoSMx_&QVbUy%3sK4` zt4yyRr>LMcT<5yPyY!G(`4w1tmS)|rUaW1e4fjvp3Mu2*O_J^!_;?ZuOa64v$=qah zc}wTli?10mAd}xJMt4m6rV~(O6yr0_ZegphKuK8&egX(VXg6RAzyJ4K))6wTYoP6Y z>wWPiQJwj;rZK_g?tY!urh)cHU>!3jp*up*Ny)-i3s;09gQ-*DX|@n1&6dz|zbC75 zX$hcRaxPTUC1K*B`>oH8;3|*~!#4=om7b$8;&KR+*72^@PtPbWNq+}mEa(Lzzqs=a zVD3AMZ7$tiP06e5r`pP{Zm^mXCIp2bqUa7Bwnf8ogvWin=FSNpSl=Ubh5lCQjE6=9 z75?gtk5hiToa|vU?Y_@sV8c@32Wd%xoZfaaciXuAsG)oE&`avs$}?e^4_q_SPQop5 z75M)=@HX>ga>&07SmEKa8Mu6|%d|qnos=H3+n4&u#tt~2k}CE2^cBq5qHn!VaeLGY zQ{x!inFG}zSr}rKmt-HbEbaOkQa`RWm8Y_MHR}iKU_*03TdrN^w2!vp}IEDPFTVWf6e?;0_Wvt7t%Ua%Z=@HT1(jc7an6g$y%G>0k z^roJ_>6g{r4~KhR#r<+OkZ>vwYcUZfo*0n5*Pjy|tiC+pH2!{-=Q--v$OSc=J=^{h z#h3!ew$@iH!6CBtUg7GPIpt{--uvuSk69;RS}kzpI}A{#)c&_yx7q2WP6&%1O?)8i z+*IK%kqZZfF3v`Tp;u0`vnd#llhEz<0J#n0i-_0=b9N27+Wh76qVk-slce?~kaNQ{ zHr0katct(Rr$$A4U7)07f;#tpO#8gU7vMg~JFHN(-R7w9?6Xlh7Ky{X;TMr^v-IL^ z8))Lly0LSo?GKg)e)4T^+{VHmV#>v5=VN@;!86#&0C31xViM!NqwwE)J0D$6=Dq8QARNEoTyLo? zl$4uo2o&c9P|Td2zKDAgciIm=wJAr0_bs-_5g$-xH%kdvmJ<}C{zhV|8#H`0*Jb{+ zWXPTcp6S>GK@iT?eS%6iW|&f+i3=6fQ_NcJC$+sQQ@@TFmp50d=}n?6YC?V~e$SZy z`v)y5FVO}beYPUuV~ttWK)+QrhYma`5^BE0a4P!Z&Z1V8kVbS=6;{CTXu40bg44Vm zSZ3HRNG3g*p)b_X0$B=QzgCXP_JhJZ)3rm9lzAy>}> z?hTeI>s}!fs8QukWC@g>4T}rhz3C-UHDu5X2&>!lx!XHyfS%5nFpZw5S0!^5F{ggc-^@Dpm> zxqya>0W3c9-qsH7jp9J)uBQ?8fX2~}l{)y3tkuoIikt<$o%cZ+kRY%%#<)TcfBO;2 zMcBr8T)LAqBI*5+53w>dLVfaaPP9Ot!Myr!HJ`0CU~imG8bHA0 zk_Gex4XHJTP(2y89y+i^2f@wZJklBf_Rtr*x%{3^laC5^$SUtz%wZL(xi;|4`7CUq z9j;yQEmZGuI!=YNc<;yWpjEB(E#aqOCw?^B&*xz%{o+OiHoiF5JO7$A?YVW#gWjKw zO#JiL25DHni`6wHmrY{XV9oClEbn=6Y!v*j9^TWPI6nuvS_egB3{_GFL5EbNAJA(4 z$eWqJPSqWyX3J8_D7-zC?2X4RcR( z_6gE9c3+Y`oLHRgaeh|$XK4Ydq;)LQ3DQEzf$khQ-=aR>8hZ{V^PpO?k0;mw!-P3_ z4;3Y_s0K@?W0#F^5b_5}GjC&F!8AqA%)sRt(bfQ*5`K4y;QxY3X}%I#uYQ1~30e~1-RrfByogVuj&YbFt(eXcFD^_0j*nMCnUHH`GGEJXBz+?L|i zq2qg;*?3P*TlUDv9{3bsu>z3K3ka`)>ikrerVlWXi2SaM&&cFun9l)d40Zf$>Wibs zcS~8kE$fif!u}3dBRLFOEnyA2^pd>X*Mgj$Kuk_e$ZOZ|CT`a|%QEHppH*n-WxG3Q z;tu`;=JIYu+rMj`_KSTGddjROI7w;;zp=7M6?@5}gsmQS8Jm+nUo)ZuZ4#c|W`D7` z)_@Z>_UVP6eW=4CFwL`@Il7;$!#*|I zy`wiyaTaQ}aNbJ6D6?AjuPSrv%en7W&}$b=vC`Ks?M}l|PSU$|hA*rxYpi@9M5d{~ z@vGo{VfVs{hF@SE#{8SOGkusVUl2u>a7PF~Y2bJG5kKGhMa?{{O^oMSpp33ArS#CtFT!XOeU+!jvWda}*8#fUzQw=q61SI~;kd|7N37B|Q8F=u=D@_B}_mmXh z;2hT&fL{0eO}kK=et>qiFO9D5uF(!}uu612p{nk8xo+AZI^?7L5az?W@%S(uvuzpB zJNac0nRc4eM>h1B)8sC}f|BfZ2D*=R?4zYBwq-u8Jq<^wNB9vaU4Mt_E$)y7Qu(i~CV4Y|0G6u0U6FR|#NV*6X;hA8TkQjgmN2rR0@TEe|yAiW+m_8e!B+KS6O3 z>^}KJh^A|4QF~Bbe)fpaC(a-g#EeyiF5QNu5A0yhoq|*M1%@re>~K!ZA_&cj^OSuZ z_jz3*VP&l|DKcz*m!dKOIEATpUmtZ^9{>Bq#SGv-e(KA22uW?m2=M}x;qeEkOZs}n zpb(rnpik(eP5E?JrR67-@afO~Y=qJwJil+R;f=QFlEyv)qQsl_=Jbq<%meeSK`K=2 z7Wv!c6XjzrdIV{D%`aitys)QWn-Lb<63<(}9hly>>UE(l-iLN_y&T>V6xnxP6&gW*uT&r)?i(gxrJJBH zA?#tbChq)4G}jIsg(K?8eIuF#LdF{Cyl&T)yCjU|LWJ>wa>A^SYf&LlyjsK3^ZvXO z`MJK1DomB)%Hb?xF@w7pBOVrdJ5o}`%|%Mgf`_K49T&o#`4TGV_ICA>sN_{fgGpVw z5xr&6*_yTC`fx1+Io{-&{}7=zgB=isXuphrtC}ta4#i&uVd^Rl>yy7wueLgC#JHlb3E5Ca+lF|mG+x-FWKRMRi#QGNC_f4Wa z7iFl6S72ZdWMoY`u`M|H&6w{r&#~bsHF7sg*>O!=pdg+c5f;SmfjzSSDOJEa!s2_^ z)65Os&|TtHVUs8FuJihg4(%j2l3VLjt*IA6(*DC46Me`?u86y5)?EKlL|K|kCi4yb zbIHd0?RD4LK9Gh+;gtoYI=iG1{4ev$Kh`oU?_s3C1zaP**Rp(`k%}6no~+3nKwy)9 zK6&8J_Ku<-1D5vpVfgwe{8&^t9LkKzrL<2|V+o_N3M2t%k&}C01E&C>>l)H5StWY@ z4%d;t=tUx1Ino3$`wTkFgRv=#ppn_D+(L|dqTR~8F7RM6`JuT=Rpv{S|0s~WJM6RW z8Peq24-O&xk>{6$B0`$JCR}DNFesSWislj_g;~yNn0ECVZz;u+MM?eN?l1@rC{*>K0CAkxgu?B%2lv_M&+C4f5$ z_+(O3`nMVTQVmz1XvGB~$R`NH@}8`c`7zTL4a-);qde$c zY({px*~5o_1o9Wo_(JFlF3nd)>ZL;Q`@|I6!WMWvX$x(ffh|`fgFjJo5htb!IFus8 zfE@)$2ZO(n-6MXU{|#7Y6@M*Q=)iT5=}p7=B;go_o&8lqLhvX^SBvAG?7nF8Ljq1p z+9=Tir0qgRe@!eM8-4c21+|W8`jF>tmgpRDFSMsFB+U@$`M+=%o*p%Q9n`aYSn@A3 zsL;sN9dcmhA9Mv=(!LE{p@fcZH}Rj0*AhGfxiop@mm(Pz-5bBO03&-{5Pm z;XLh1q+A}gsMQTixm8TL#`N+_9r=^q-1&u&W#@g75G$GxG`M4Eg7LKxK;= z{Zb8cAC{-EfYIfPgfvfcQW5!@YudNwRMs;&qEk{|(xN&d)EnO=03r8$Sx(2%FS-#$4bg&DNL%2CCV90QaJjJ z!dWfa7$=>%eo9Jjh$$7a5h$(d^P?eN%+>0AFv(tx=ArIx^GiqH;fbqG-m3mWw8)1b ztmcHg-B8Grv=_G12ENOAj*Z;YxLP^6d>a@+NUgb(Ou2Bg=G4cP3L4GjPFTFUBTMxu zrZlXH$JR`NIa1hSz*}W{?8mFPNDMVOSf%+YE z@#fnd+~1|18Fl8Jk?b@H`S`~^`y^RNd+uIkX3S7PN`<`CSNZSq4?)d;@DmO`kPU0j zok)(qSB9!O|C648sv{UrIFV@$rOvRb;=iVv-sF0Ma~iGyQGBTrY=20>&X?5%1e`jOv1 z9Mcb*lZAuNzZm`Bf|otQnjC1>W)jSA4d2+U2?nBTpOGrwtCU~FPY7y7wyC|Yp!=Gt zjczs%7FpUYLLw4|=`2K4=Ad`plsTV^Z_<&1k$v+xEL~FEYcCqWqjh$u<^EXuOEgjh z&Hqa)6yO%3#DrJ=(kc6U=;yCv-8+Cr8hhDn==T7&%toYWXCiqz ztn)@nmGb^ok9k4Y_H)E!6evJY$eDK3qpC>z!jjxaxlNKgMx=rug=4JexuI6Yo$&-P zQBQ-1_ubCI?y|jR5`hjY!hYJ`2L+5_Z21mDOa12r*8iDyB>U;)bt7y!xjv7B9QJXp z`6oyj=jrJ7dY;o_nyN@j*CMX6WBO#YHc3#Up(3jcU{rkf&{P z&EDNn&9!3NrHdxeOC$t(yKxxV`O$oMQ4o~mIXtXQO^VDyg8Zs;WdmU9v@ z1jn@{%p~7=b#PfPDQMavo|X~j*<*A{`vuR54=nK02N>yjki%+S6;x{^CoSlgnx~z( zm76v-W+9WKniP)Q0o%EQBQ=JJe*MmuawwdxMo93w-GM*)OFWbh*Bhx-*owLd1O5X8C_ z53cM3uYi@$DTzKr+Vd!;d??aetIFhX!(t@50(|NLK4`jy113H`K__`p zUM>RYs8`qagT7qwkIb_JIrli zwKy_=-BY07HW`E?(^`Yc`pZ35bD;Nda1Y{a?4iS>w3~t{5@ppLK92^kNL%ddd zn?JsF1f)%hH)={S{_}hElhrg_bWY43Hy}^{U7*CKRH#{k29_NEfu-x!&ImQ*#P}e%WCf#NA(M9AdtZ(_ z7{5vrv|S!6(k3umUxJGr^76nNtWOy&_V+*XJ8MC8bcglC;!f{PTClP|cMj)V9l80W zt`HT{%r8y{jZ|?o1?nY*i*XCm>;yOYb{Q|va9jevfgi<9X34YBZo*GhLfOp>(5D{- zcOTBbEuk8abGzT3tuf6|s?1*1Kb0c|dk&>-sOyQvFal!r#6@=6uw0{8@2G4~!J{eL z1FACM`9$MlP$9Z&l6XUym%(B=mtxB)-jBlGLXL(04qja5eLCfSu+wEgxLaiU%>$IrFxY?_XTxy}3#UJ^V)5dZVzXNXj5c%(-=%1P63WtP`GXpx>b1 z{DR(=F)FwIi=L6nc@AZL||2$E-7q zTV{_SEBo;)g-BmZBFsq2?v>_X?ExBN7Nh3X8pC_>h^_Xsw8dmPne;^7SBcK(ORHia zQ$fs-DaBTJ(ZO{dxbM4Ob&Ua@5~W3#&IIAZ589{J@9-Vey-fNRb$ zu@}9=U?q(6Z4hdU^@9GRIyX2DnvlE)ZU>*QF=Ric)ud9OY1VD%!_5k{Sk1GD7mACi zxn5>EM~`HNGl0NLGa{$vjIxJPculmnfv4nr!Du~-jwJJHPjM8A-94DApc$cV+R2ys zV}jo#-=^~Y5vz938_H^F&*Y9;u1cgStHvz>AJK@8B47Z#bAQ*f7y(k%AV;N5Yw(v5 zJl$ZcLbYPQ-?U$jOGDegs$fR{Vz*N&3+40golQN*mMgk$H<)?=G}3DJn({~+y(<`N z%UJ+*2r;v{^jQ4aUmfPK!{#%W=48(2(?xgtqFLg)O4E%>4OQy$bKw*6&MEIyEpflZ zUi6&V9+Y%@b1H;qG<@AzTd!ffk?eQ@1D>ig|p4D8jv8*5I_&}adj9E?Za3zYy7xVH1!L(I|KY_gV`JoP5x_LY)ROk`Lb2{ zWzD$!_QOZJ@`w9sH)%vsDzt)Epfv4$hI{3odcD=$8gZSw)Y>@Rljmj~9< z+qVEDtPyo|Z6~QvF-co#Y-t>(EL2E2+2u%a?*S`Q0w6iDVSM)Y@>lIn1<+-b(q>K$ z!w5bi(I1K2mSK?{#@&ZPpZKeDhSBse_ovc4i<3WTeJySE)ZT2=?+)8IUV6JqxVq5P zcdcDGFisSTD?l-@jtRt0`tnH7Ie4hl=Gbw#?Kny)&!Ll55%v-i?ALhgo;QCPHf^Jd z^a2z(nK2b=0dd*=o$-F))tCAuW9m*(8Eq*~bPBEyd-17-ryyPkCi{UxQg~6Mu)9O6 zngHAIUW(v=M|9#k zEZ@b&j)WOMnu~XvuQ5KFVD9phFNHi_L!3X&EU^!oSnT9K;3x1OUpJ}-&-zTJ#UrHA z&94Pp8(UxNyi;N=TYab%82U z5t6z&VdInJeL*kyz2M>Raf^lOw6EG?A&T1#s47Rc`5d%haw0&CzrUXTi{Xu9a52Q{ zU=E~ndb}W5)O@JnpW#}rjGeb?4y0U9laex%I}S3Ze+6>`}21O3^;k)zSQ*hV-7=+XQ`eQIfR5D~l^;Oein7vN ztn5$|qU!%IrhCz<9v^C4HGX{kRXTj#u@Wai(_c61VH5mTGW2~CiB?;}n1`MzTIY7h zYg;6X%o!nOlh7-qF5!-;n<~3VMwt6Of6sfVF$Uqcon*0#@X}F&Y4IR%J(^C_UxT(G z^7w9E(Jn%91#_!g_D@TX1ZFVUrB={AJPoOYm1kN!iWxLq5h5d3ueKyb;mEd5)#UVP zqun5pP59psM?nNa{a~^HSdxKJ%BtZAAX-DtqE006p+cW&KyK*F|gSju9IHMMt` zF9hTt9_zTjP`pLVD^HLZMtuV~hhku2n#O|o3 zz0cL&oOBy~mR43cjB*anF01)|vo7gBAm|HVIQ12~EbyvI;A!8+EkJhQ)pM4JbI2RB6GqgywHc)$BoPy9&bM0pXU=`;8%a_wr*RF0Abq8j>MNCPF9x!&4=GcTxqNxt?Xp>LdT)8%pk)F%}u- z3S=TV>arTTN4z;qIx58XtR5y2=Nl(6+?ZxBX3HF`-{dX`(@R=VXw~Eu_hZ!%MJb{7 zO&2pkdMl)W&@5C4WNZJfT8Ox&k%KQ(Mya?alg;i0=IRe)1InsJ{xVkebl$jFFB*ui zO;Huw#t^OrjQpOtWg5|Et3Eihr0>nB*QneCv2+bIpzLU{1-qf&E|?%1b8dcFfsH-f z7&AxiVZap@9V_cz|0+@H`B4<3mIY;(nn+cDPFg;|^{q7j(>2&WH`6L3Ad@TV zPUR;BUPN2d?hg8A`K9r{z^mNZEV_sBrPQ}!9kb5kxYC>DyQ|?q{uTRJ5ZK)u@Ka>A zhcuchS7G5Ov^!lqq}Fon67bP4{BKo_-z%~cDx}Z(`0L{@{$*JgT9#dB?h5PJ7(z19 zN_>?#g!`|D2=L^2%i6MT2(%d<^~lJTepx{<5{@jobG~V5=TIn z3aQC(wb)`tOr62*Z#|DE{HF26o$rPzRN@$n%;>5EQNe!CR3$avg3A5q#dMu}l!n96 zMX%eZecHF9r?HIuJ|$cqqy8*??S36+if{xC8W}HoE1Ry4GoW?q^_B+D9{dQI5;=?hVt2zVh7ZtJ0-+PG;psx3Rz6J8tg1jzrhmkr^S+B2P+20x^& zSac@zuE^lg4ERZ=TW55rdqU~+st90-EZi+ZCm5kh+LB(nbhVk>MX)vEKMHRE3?QA* zY`GS=E_;Mb`WY-RFhX!@fz5EL>R9Du2j>op?}_v{*h!subq649u}@7|6BjOse&-8@ z`(CWM_QA)zVKh8O*ve)+49R2cU8TxA6=bd{K&1M@dk(mdtDjJwlRA!J%-f`&W7bEX>w2KV5AukIz# zM7Dbg%JUiUQ<$<*ngIfFVbJ3-L;+KOip#N|6Lfd6lOQUv1k<4Ud4`s)bGekgMyHY$ zw0!|7&~m=H;D#?Aw1kqA2N=%U{`Fq>E2A*DfO6FtZN1d(iUiMwn1d~V_&L4x|FoC z$+&X+=~DX<`P64I3stYGxDv5B;0VIs;==Bz;$IFBdr|MyXY!&J!p~GKUS?enO>6kq zhSKyZYT0We%loe1fBe0d#^1$gFs6}|GFA;v>w9)Ru3G#VM}Fh|%Es6Z&D#;T4>x3* z%o(}Is(}Z`MpT*6Ilcmh7L72ha6pT~f$}XXJ!D4gI>RQW7=VEWvjdAz zqp4)?z(E2i^~`r@o=Qnd?BplT%!4u}fZqmXl|XVQXD|pVviws%}pMzn6QQ zkA4$({g}NxhkLK?TL9gBiek$^p%ojn%*{KCeeW`Eew`P3fKy^KF3v4miHp&QnHmJV z6XsSa!R@Arpf^a|*yE}-W>-HVIqa(p_n#Br?mnQr)myXrTgoE^-`Icd}AxOcmldLOX(tiLcHjMwc3r>?V*6*ax!I^JW+G4Q~nWS*;=+37lc%Y`x-<*XJGvd$S0}x2fxonZz#7yqJPeiz}{=%sYH&%`NS$L|IDSicdPykFSp{Ml{%=3e+^8^!C6@erwVU!j={&AkCGA{2B88zKFE6PjiDe2SEB8$ z@AuGbF?0~v=Q`$m5mR=+Ttb-8=ArQX`;@^`hrF$Ve>M*W@q^KCrf{-3s4 zsXDK8&ioyY`H%@IfbchH#Q1eY-&rjRh{7ktz2aPMhD)szsrSN^*F8_TXHiN2_<~~0m59Rs#^LDQ=MU(N%h7#kUH%0Y37#9#rpv; zWL&9c_*VbaC z%vlSyBT`q4vy$N z&vhO=#1HD0IgmWOO$R_LJ=x0s2}3z>nIB+hDHuVFFLZR8AkPKjuKxU-m*>pE`Gg7U zcSfAlKp@?lm5H-n^vwENV`#?Vt<(flP+>O1_Ab-LhW&R%1$kZ*D>-q474CerCWlKk zK>2~+kSwWu(D0;*>nHctITgW{YdUMfOT+f7iMt$*9*JIb`gTnzt z%?_C2yI1*xjXkCbPd3z;(hE{w^w@qt*k@(;VLsn?yQ|2L%0oR6F%ds4hcw5;MBq#J zXQ^kr=q~)$!_j4uhA>?+q%hxZnB}e`oKw1;5fWAN?$u-}pGeot0|r9c!2wmB4!<%a z+n4w}{A@SiktZ*cF0(;(qFMQ88AH`qX+Mkwv@5AaQx9u+x$4xoN{t2?87|Qo({&eC zLRvR-CPMBR6!;);1rpLd(>FE7X~t#wE~!H9Hv3j@w#*H%Zhp)1l8MF~qG`pL%sk64 zTCX4JIi^s9DfGYmO?+P4;Twz!jY213z+WZI zjV(qAZtmvE#31gxVr{9VfUaWa*E*2 zKRrD++nJp4SAa4%+o|u`fFNKpRK8|w84TlsPl^TjZgfx|*7~V`U%NRHC+KYI{Yi^& zQ>le!>~A9QDWOyNFD!KY!`vjjvz8mVN_y3?j6blLZ~n=)dBY?nT#DdL|SxkKBTDIv%7 z>MLd=k7nsW7~@;bn~+^3h&_5qJnI~7sW4l(_3T?MKlDh<_SN=MnUyluC%de<$bf@= z7sNIXXJRb?3U=;k^xc^an5VLSAXjA4#^D zSfF0Qij46l`6RoG*xlKzCz&eG#+mpo7y9VnLtIuCZSN=bWIW zvELeL!D}p(nG&-1l-6)N(KCib?tas0X$oWk0F{&2gcn07@Yy|~%8|A7%C&+6bT6RNaS*#smgA`9^JMUcy=XM*FA+pFBCcWbsjkKXm@Gho4ia zKbSPws7_?JxV2~Px9`&;58v^ozXmv7sjN4B%$u4h$DkK3YHvId&v+inzNvsD7f8O222!3N)?h z$(R%Pia0Z9!F;$pAZd1Uv+&n=n8lV-IbB@Kh^Jp<^$RgN{4J*sL_0=f(p&B84rIO#NZU1~HF4IXTeo9=c3s5W zZ=oI6y>jtC|cpJ{Rjx}k3Lqtm6 z=?E~(q@w7Z+v}8i@xdd-JDq$5baEqnXV$ctVN76!bch_?4=kG zOD{ilL8~;_^2VF23E=`^%4NO~KHs-sKQJI*&~uWK?87W2$GvsS4DXt(SL_I$FY2O> zTTNb0g4Ah8w?Ri^h}(5t>Ec#S_ql&;Idht>^QRWXF%RJQdMD%&xEhP!5ud<>lG%T`V#F zd*n=7dMJUUr=#7>$10fEnHGW1#aMW&*IrQ@$8Ii~H}-Tgm`AG3@J-?CuEL+D2c8zY z5icL zd;HAc`SG$E9ze?mkUdTSDqsLqECc->PJiyaB?PnwPqHaTW8d@`_N6lARhmlm9YK zWl=6y$(c%7HY&6F?B_>n&xcYGqQ%8?qwtV;Y*_>V>Ca!qsYYkte-V{`i z_MDC~B5G)XsW0p6vl)p&^(}7oZru}Xch7BpLFjqY8H3*GeI|e*g*!IH_*N6NDn5L* zV|2Us7q)uOns$hhr8HyEZ%Yk-U=*njqz8J(6B}yvX_JZ7hnOW7H-Ar<@K4*A@Oak% z_K34v9H`rAT8BIu(1sP7db+ic%!7i@`8CQI9^-z6Id=cOKoH@I!-9?xAwZ}(*L z0&rKN(6Myg6WlE8+Gaokl6~Np*c6Owy&Fse3>MK`Rdl{4pGA(!+1TQ* zz>@k5kJhK@E%6+^Ci4#9O|q!?R)r^M5h8p*wwzkiBYwC~s{o&+>`eYf%aU<()L*3p z>KMc(o4*T8hy_TEe#xTRt5HDc`gb7IbdiYP;LX^sPj_~R4f7Hl2d=`elk6aYE9hR& z#pxd_d-bD`Q5M>Fm8Y3*LPF*KUAS1r132#O+#kDyVGGF=e|oD~qaIB>?otZbNl3^X zQ&^24`}(-&lumkWi6{Wwyh}}Zm!eE5?^X%*Rza@749?kClyt#HZIkVi)6D5s2kW?1fFr+M5QPut7fN)ZdW z>eCY0Ru5GmUnLbbGoNI()wGa35QtNr%h1LIQ&Y4EbbZTj1IU5q_ipLjS||V_CxAY# z--wmUG(W&_#%~}!RIx55ArttBTqJ^#h*3p_1~2ToZ#8O@(i!xEGiE)fHI;wR0mlHa z8m#r=FD!Fm;lWyg!PZ18?c-lF@aP9TPtjes&G&-1b`nZ{te`&4<%OY8gy$?tyR_RqbZI+lM6W4UtKoFm znaOFpfKiTfpSB9w?{d(S-+Bq4y(Cy5;0~{r8kI0G^^tap%cwMrT&TpYYO8k*Uqa!F z0T*$oMMCtfc=3&4SASj2!9v6Js0p}8YRcAx_AV4pcU||&#K9J2tjh?55E{)mYjE@7 zMDKtZ-bn543`=>|kS<0Jeao^w3>|iuWIdmyC)uQXD44miA3{ewf{j#D1 zNLX!*GZtPK{h5ExXajir)?!?AlU^MniA$u?KbR)Gj#VL7*{ls`<|&)wVj*~B7$!!d z%_Uz8jMC7XKfBQGqH|ucRJ|JDDc9gzg?_*il8+n2zpd?d9=rnB7(-Os6DN|PA#G7`c3tx2_Fw<^y@wxKXyrc2TC(CXnx!mCL745wFI(?bqHVcoWb z9Bw`3l(h^FL7}xowfh=dCWARsCJxYxi8KMXB*x`wa~($`sHK=g4JIvppLz&)8&d_0ax1 zHM(hm#~TvCoib0F+Bt2-Ym~X?;;K*$h1_~dpk9@Er`GB-?1mj+F|Okvw0gyE=wBN5 z*er+6j*e#;C@e$THc71{g-goMpG~rq`{NOm35Mk)fk|cdFk9WI00|L}j}2g=dGt=7bD0R1Y*G8ie44*zWz zWVW?Qh~HL8i1XkHu(xZq1rny+V}lf~BCBu863P(SvCT~^H6D+pNI(9!VhFZklNRsh zS%m0c>Pu9p&lARML1RwCu*2(y*wh28cP-7J`Gmb;%~73mQ5zzy`e*KLfr1u3EMWI^ zPsV2KguX;b-rzX)8!_<4wD}@7QlDV0ml=Fwrjz|M{-CzdG1^eo*lm4?$T0!_ylzwj zX9VG~C$S1*Nz-_of-PdGwnMQln;zxUU2%3WiUn?KpA$e%)5zAT1IuiD8D|zc(yOAvt$r=!grt9J~-cv z#cpPsaT{2Jc~QJER%-+c36V5lRb@4~qs{zha98H~m*K_x?$ z8Q|FDLT6}&_93Obu}S3XBITZxDC>oT0ZP6}NCA|W*9ye~f<)zR1%v_RqAQP1sA{;i5JJMxi;?t&{}idWe^v=pVc(6c?592 z#MC~)0Mq-G+H$E62=`bkxi?+^KneygGJpanv&L^F5^7LL9C+NZ%?$;irUV|yI%}$O z9R^uF?XLD7;S)hCs;SNvxgnh!Vyer{E(0}d!zOv|gG$9`|_?)GTO#4^JRMYH*(Ht zdNWCCagJ%7r*Z`FkIit}C(5a0--Ybl&i`nUB#i@p;ok~5mOrHgmpt5k74jM#We?RY9k6W@{n+CHAmDI6%DO=f{=1-l(pcMaDUyI>Pif)7v{Ll_D;#OZ4P1N% z`&wmOfxA~L9-ZIYsxQx;1E86!SF$fpJn%OEnvc?xLN*SVbbtq3{7dXDk(u={xr2dJ zQ}ig+uNKU$nv6dC$9{wdpg`{)9<2la%{*sd=JkRYmfz_~b|I5rvtLw?xtbbi%K8ezY+$I zth%czEyR5~Qp~8muoV!WdPQy+wK4(BRB7OttDTG7_`4;#9nYv%+_ye%n6KVnE^{yy zLAb_xoj7#vtJ>+nxgQF*Lu8;Z{pT7zh#Wv!?Kf)sVHmzpru1$lpO@Sq94;L3)`EW- zMARDo`Wdv2$jQ~#N?z$6a=zDa+A~2dbf@HuUK8t76Hb&Y=d2vs1`gZ%VGGMaKvi;K zsYKoT`Qmo5?c##86@)Xa0^>x9bky~Gr!|t)40@Yr{oFX`#jZ{k#nMjZ$K!l>E(VE+ zJ@(sHp(dWwghv%TIC9_UdTA3mQEX62ad#&`2%Q%PBvM`Y8~}!XXK?1t8nJcLb8%A> zpu^@93u!&>!2(Ku6c!cOkhW?+XZ;J-(>9-u{uWO1ow-pcp8U>=@Ah!0z+|8ZAKr4| z6aBExDoC)Jt^0Tx#HcQwE(X&vN~&kq0S;@LL+Z*WWxEV5j#sdDd2Pjqlfsg}aq#{Z z8&l_L>iJ6t7)EejS9=ydS9^uVR(eV&%qZh1?M^pKTNWdek7I)Ug3(w-YH)}W_drS} zx&rT%k9;kd;0$uR=XKIns-~;^l=74MnL8%@swyRiZj^$>=RdaU>$3s!(=6g&9>TwN z(c{Meej_d;(|klNvi{vF_PqG4-SEN}>yQ)Avq#>VZh^ED~r&^V?j9$)S>tZC`gZrv~8xr}UUlb}@E&Q`x;q1EsXqPr1(zxRnmdcEGJwBv`vB7C zKJWfp^UT~ZmrUH<#pc+J-K{IuWKT0`?zQQWzebyHCN|~R*w!*l!rvO+CWSxTe}qe( z1p{k=kmz;j!-u<_DK2 zb<_S=cuK#7H~ax|xn`FDT>~LIt4oz<5LQv<`>gb^-Y&HGH_G#ME}CL}OCAcu`aJhkiW+0bQ#BUIn{cTm-p3zg88zinDm>L)yN~Lv_$Q1Hx}r?a-e}Rr`0VoekPWVJkybK`mq?4 zS4;N(+tS=WE$4o5_LVqg++VFNOS=D!qv<4;z>>cNh@tXT41lQTRA#jbTcN0={t^&^ zEV%?MrU=m+g{=e9spC4{#XJ>i;tOA%Jqj@>tkryUE*R=o+g!gtPc#vG{u*c?rqwtl zG3aXW+387hW8j>#8AGsR!q1W4+2S{esDusl*AYOH8P0kpxtKr1|Z0 z%^trPZG5S96ARM6LpbH@?(<%dFRZP6vyEY(Z#Cdmns{cO?@eG9&_9!(V_J#<{42Ft zLwJqmQ5y5WG~%Ojq~#U-%9um*X9(h34sz;n#Loa%T`HKj5+RjI%@NeyFGC-7Q+$17 zu;W4T2I?0M=X*!_=@;F6+{;<6Q=kJ%~klyn{``~1+#r`T)@NqqAMuUS^(wGYfu=US6+Icym9E@QNER@ ze^sm+jlbvD?(L~tR`|8c)1A0G^r62|7SULltCcxrn7`sa8zUm~vE0^|=GQoBSkg%h zCHVze9F7*&xrV@Bj~Nr2WYd92PIqB5CcAnPn+7OBG@d`MrY_2&squyId)J#FJ4Fis z`?$p)cmsP&vQKhr0}Mb!C9dTKFB4^C`9Ayq44KwGd7C9@$i=@*aX9)<<8h+s3^gV> zD`kBsGDlGyrmwvLTnY8P(jJsyp=f(rzCY!IVr}auw|02QG3|W0^m)HqHIbYi+9k4` zwP2F>)z}NEd-to9XCYy|ut8LK;U_^qsFF>mY>vR=_i)InlIs$xIdBNj$dy`0(aa1z zM~5_JJSZ0BY>H0RZhaQSa$z!XEGhFRF=astUU92}>_e{>ZHp*+o%1u!cEL{0p7bx& z;lm#|=;I^VFWI|&e#gbMoCy$QQM`&jU>Z3a)(p!g2>Y1@uggu3rUc>`ot;3pqM7V@ z3a5EXWjAx#O@odZ6MEj}LM$|Cq~dr#-6aW_WOSgN3YiXWtRs3+UDfs)1Rywmk8l`C zyL3cmDz?rDqgZajmnS<%9`v~9NS(Af1W?i1F;N?pSkLTXnpC+_~}3Alms!^PwDKW~dyxLBsMm zyFvh^N6Rg14~T)sOhuxTL%P2!r)-=WPuZ#P0npIFF+G%|sjzJaXSrzrB5Yul^UZ$$ zaF*1snk4w4M^iFote2t(>yM5j0;Eg2ho*dDk4aqv-OANNGYj|Q$LhJY#dOFGt>a>> zc1mQehDHO#EVu0HnnuWi6*V4fdk+8@mz0gEml6B&An(sL1g*P+>|iNXr($K9&AaoE zx2-X#pn3{}nN6s$c@nP1TjmTzcg8ze_2v9v{O-qOQKFS9K4(Dp-Nvb$P=3>xAHit3 z{kYh7Sc?251%a}$^2-&79cWJ%-@_wK3o{fN*uIEp#9-q3gv2GnEz|$k*;HTk`y~2( z4879fvncCg*TXELSoZj-S~4iXA&4;$ja$=<|0mepUaAl=X*Fo~K2Yv@${|AFV)q!h z@n%#WdCDC~ueWcOE|y&`+~XHAR;uB1T~qK%1s=*A%J$-$6RTHD1IH-D3gtYiDx=mC zSH5OO3WYa=hSeX>YI{(o5*?f?f-Wav7P19H?5p&g=;lPo(9qb>a$us&AvZq)PJAMVuvUpbH|r!m$2J*rl7bqlUmifo=p zM==t$S0?;DY?NQdz7F?&P5lbSSBVhT)m@}tVO+5SdJ9hr^Y`N)+tDtM59wbbHXP7z z_-x{LyfeGG4C)9=R1n8rg9BpPa%SF|I!-wa6)J`8sI?&MCWVgZ<_F5i$mZAsFA zX{HMH?&IZa8|vN(hsptlHt_jTZM7&cIj=skYh$8UQ20dk;Mmt{tBc3nMC&FHE(09} z^^(NpZZRNCjA+!%$IxdttOkd%l&wVJ*78zA%u1)G^FI0C1=^C36cYNr48o() zE7`c~z=90>^VuZ3IG&|!LpiDFe4Un6eRWCObm-UV&eeT3nk3IQFQm-6p$*Fu?o$Hlz;N00XqoavQUU;Up1Oc0k7O?UyFT2bX zi8d=AyPevr&c6|4vT(|tKd?LIqn@9W6tB#6!e{a!oZb7-x9m5z;KH-KSCVOx{e=x5 z^k{8ay?-Q)rNck6c7o}yJor0l!pQFG& zLclf`88XBAf`%1{Y`b-p0DSb#DD3(ou;U$USS*=V3lHf$OCt`)e${(l89ygB^s*fe zR2Kv6*!H&m?U;6}_Ng;Ko9?aqLa9G1AUyqR5_Qm-pcn{Mt0<~2jh4^Mj>htjR)Ek> zc8?*KyTOUbS1?-6a7MF+RrfS;*&u~-dqBcp+I&r^#K*<9=O0`N*4FrePU_ZA`nqoi zlH}_EM?Rp;zfs&NO8~#Sh-!Y$n$~I7aG^^5ku*=r$O%b-ioI z2o}PD?5)F%% z6gqtgvPz0opjeec^*=8wQIg@qlhjjWY74NZ>+O4d(DjkmYS)mc4aoc0x3A5YCa<+T z%&AiMkh(UV(EEMhOG)+iN@yzvSUMe6E23N#v5i9M;wSk*|cdWxH<3C1q#uxhocjhkc3!za`{hrmP8I@(A|S9=vaclXZbdE zQO$ZJTrU2da;f@J>a*ND9A(}VxL&9$syV(bdj;l(_apwF+>aGOO3Tk0;hu&W1x)9%A1ybC zjjw&u_Z)@vaEx1mzxReUybdX(vj^LVzUPYLf$SA=w~huq#Tq}sf-Tg)hM_~$OQ@|b zuxU$^iUJiRy+o8)S{%6are{odjn%Oh;S*yKVO${|itrwUvMB;`%uE2`twkSY&g4d|U5A-zUjZL6P*itp!wcPy>B zhO|0ssD(f=7lPI8{p?@5XF~5OhaQAeIxsl`&MNiefl|DwJkC`5vaaU|(;)S%Nkn`- zc?iG-Y&?pjPGIFc#nu8VD!o@0NDEER4a>$-R#eVs%!qA$lh(94T#7q{3X*{4`ZO_! zxlDB#j09<6Xs<3W?|ZyCwqs2_KlHM+#PAJ!+V%wo5)s_ojF3eLRG0tkCVvL#mrOw*ENmH z9+zDuP}2S!MKV&d)uiq!10A+SpMUQNN>EGef*dr1JRyUMJ*&Lmyu)Cr%9#7w!t*fAli^^lT*}< zS8sfkMoFRGsLn26t6wp{(F*By_)=8zI&3*%fb>#LU^B=z+`6GozXXZF+W&`_W(T+h z?|IMfLSH3b-M)-;1INLmtACN7P>&|xR7jXZ6WVQ+E1K)Xq1yJvCBC14`1%U_DXIsL zYofW7U!Fc{MXQdv1A#SUl$K|6%~fE=SRM>?xrs;4L@Mov<>y{^uip+pMMg7e(ITcQ z>SI+@9$U1ET|%xz2*g@rCJxs&mF>hHfPi@zzlYQw-LRbQoS!??VEzEV?HwGB-#_o9 z-b+ndQM_N9Gl6_-I^o=EEp#A3FAj!T5JSW}xKw~g-gG*7kAZaZ1K$O`Qkc(I8*k~X zZ;CDtxlHJqoD9q8sn0GExgNhCn4)RXv?F^p>??P{qC$8qMJ2MGb{o7ro%%lG>suNXBcQp z*$0GC<6)%@EL51)QiK$$i9k!60g{B-(Lgx7ji}3`kDSsPQ>2_)lKI{h1*Udu`I!K- z64v08vJ>hD3IkHYrnGL9j=o$P+X*dCiI;v2s3TcbNC~O1#U4l1l|< z4F(2(M`8v~Kk!@o-}k-@lV36zO8C*2+`et1v3G#`7>dw_YSBQ$he}0>RoThmy3N%h z`Y&O~h(EQhO?99snW)%Sne~B%eT@;Zg+}-{wmsjG2v{O=4V9=4w=2oh+Q_q_8|#a@ z^cyk9inm!MknQ2*Nvr3M6iTnuByIaJNqUV@wT{Yz!#TMZ^H$tJA$*x|$hg#Zk!!PW z)}qYeFBZfKD-#Mw?yS`ZVH^I=7& zP8Xb`jodbAXCz?ldsCECfQA=FjF>S2uTvH}GKc>$Dfz}4^tl$TU$2TZcZ@{-d00c} zfb9w5*zL+gg`-5VB_v4%>PLf^*`FA%02AJ_oT9pt%$E#%{FLxu@+Sa&3>)%D4I>~M zg7)^-|6Ae`dd)lW(ivXKS0~;Ba?I_M$WIN6SP}SaGMl2-<2j!&z)Gkvv8R7zcbxIe z#;H7USxubzY$7lW0OUqjRg<4~kv&bRWXCyfwl@}2glxm$Q!1{`}axg z1K!$yfu-ZH+xk>3RR4g7M^$?A&p_3Ip`fY*CCI3wIR zc5QtGcuD|I4i4^gP7ZG1$hq~mbguusdnBFv|9QRj!Q97)1)vAQTlMEwdnuNCZ@gqk zZH5d;%QO`5D)H?(dgR9FA?6d;nD?hlE8LT`=x^I!zioYa;?v+#5z3R-(IatDjp=XW0Y(mh$y@7k1!+-lX z0|i<7LJR6M4L(Z6A1W>)pC$F;jz^se6qB{Me*HS)%9U@!G4=X9t%TG2-dwzLNc{0A zC|8@DcKEd#G~f24in6lb(+j^GU+VF56!&?a)|ga}4|VA~r0xZM#4TO=MO*7)9-{8c zV}}mbo6*I=cFXfF3TvG+qXVC8@?J%TRm(hG<= zx32XA0f#*3`Eco&mq9|p$z?IoNj+^edwf6TYV+gu#1`M(yrLz?)D`N+hm5bAnVD7J zm48yskpjV|2RRdisyX zbG(K}g;YH3KMBfa=(&x9L_&K_ec|Q4KYN}poVbw3*V=Tvk-dUgBj4T4Jd?;O868x1{7`XfP0yeE z#LM8niA^ubPedaj7kpHVBj325=Id-~f@7C=d1|h6d*7O71*zg;E&ZL6zs#?6hCVmk z=X5^D{(gh|?wmt|rB-_)bt{;Qh@ltWDjO0P_8!#XV&-8z!b_&6b+g*+FY$*1Tc;PD zf;ZLd&Q`h0ua)O^akfZMnDYF{(`fOt_IKe5=XS4>4PteFX6}Wgowb@lvr48wd49;c zxPC)@nfsiM)A#-yuzDW-*ebGel-?a_+!yhW_ zZ$Yiz7+K@N%lT)9b|^L4In^*5QAOr^+mW7*%d-}Nlixj3uH}Wh6ltE?FG4XswTT7= zh#z<=CMTa294#u+bCbjU(muWZ*|_rtcVy*EjlYH%Pqw=0RR%~SF7E%{Ab-e!NBsqx z`F)j$q@Et0PyOy98@tcJalv;I_n85oK6y*Qy*c&e5&AY?DA$jRV>w$eR5CtEFz7w%lU z0kzeUM@A3t#!f`)8;srxUrv8!+pCEeKB*wOJDpSJ?Cz0n(|vb*C{;X{C@(g{ma&TI z>k~(OR)PEc7`q(>IsSR48)3ShB`gm%@DjAwDLwS+#oC9qRO7GjxCdy14WHdz5q)yU z4lC6tyIszD^&p1p$z@K5vl6u*Adit(Rt!il4_(R}9l18&lj|LK@9=0=uUxakX4Fan zh#9F`oM+_tUi{H-o{^EaNF}uUuOxlLD9K0o_xl|#9{iH{v9$j-@6xE0!)N^nvY);a zl>bih8HG^q^1kObDBmpXdQm**(IaV?b@i)%{$9K_ttDg0_YsZ6;VG z@%;0^wM9bSyeh`^p8q*2c52>f)k!ts_S*XgKl16983j?n-=6=yGw;|rfgW@W)>4Y- zK9D4WGE_Qt;pN-Yu6M;a((rG)9a8`NkO=5g<%m4zuRB>VXut$Nd>;7WBF`{3`k-&( zr%6g*plry#&|;>c@ZYxZhtOjm%xb66*JKaLSVa}e&Sm&@g*Zmv9HMi5 z%*Yrz>jDZvJ%4i;i@3*wA+iR=^gu`&Urtm_R8&uT)WN~x*hgwOfey4z%sZ(Qxw@CF z4IyHRlSi^o)>%O`cy2{qQu7sfDS;j|5tk}ZPP+Bdh|__QZ)ZwmRGYs#!?#*!dgOf5 zp4eSYbF@Es%{Lt}Vf!);t?!pF$&{bbvR_}~)NTK8{t5-M?*zp7_J=Eb54CxpIitJr za!J8gA+C0uZ~7_P2(rQV%vl57{nB&-e-B+;cD-*#IQZSXyxfbDz&owG>&2&CJs|sJ z%U)*lj}{yJy<(!2$EWJM#--QhzGtld>uO*Pm$BrzcNnLW^TFJ*-0>K>n^>c z97(rZ-xZyd*I7Mg_SYo|wk)9JdY4N%RJ3c-cF~_6uI6WUdpRs5>D2wqF5_oz*B|IP z-DQo@lN)@nSixt54tMx3|m6esF&V@mR3`{B$LLAJ)BRo)J4&-y(_e}Sb_TTlq zc;Mx?z^)(nzZcom9~U<8QhsTx!uZT$v83b%B~P6_#1YhYnQQdY3({5oRg3i!e67&@ zaOEthVn*o_!Jtd=+NF1+-Wkp}qOFo|#Ldaug@Yf5%T~r5lC|{yTc+r0Sb)j?R;Q4S zV0nz3&Mzwqy5j6S*0Y#=;-T)uoVH+WV6w{VBOpiRl;Dv+QP6wOKJ2~lZu9`6Q8nh& zJ4EKoZhS&Q!jiSMHSd)O7rA4CNo}+Jl{y3C3+NYe->zSml?AyXE>}lkl8> zGRI>`MRk+&8@^qH?0|6C;z|EwY@W_u0IkwPczd{EeN|O|a&mF++Reke&q~hU$p`D^ zllPKO^5G&R5G6y$X0{J#&i?%8|W$IHw2 zK4%sm|6wt4326&CPd^Wjw*3Nv2ZThSrsgUrry#5iaQxShr5q4q#$q!L0=rM%=gtro zxxefF?)yBqJsr_b@B^a2TTZ@6M_)$|FBfGWCub)gCr_l)Z8xNs=T@7NAkp;n`#e8n zj>sOh*=cF(AFXy?I$>>1%`dtkeSs5k^a;w4J!WNUZnk{_dk#v-DV))~Vsg_Q=IH8u p@4=&p$Qb<7=dV5$S5#KjP+GdiwwNjK;N0S&TMxON!~cH%`9EwKTA%;` literal 0 HcmV?d00001 diff --git a/gui/res/muon.ico b/gui/res/muon.ico new file mode 100644 index 0000000000000000000000000000000000000000..83b24830aebf680f6e3c07b7675f30e1d510d4c4 GIT binary patch literal 96062 zcmeHQ2YeLO*L}O21VU3p5D)4AL$_N&pJ zjJ<@r;krLku3w1#H#mMD`v-yH62NQha6EU%>GS)0y^!hgfB3dYXE4u&fu+Wn|4%@Z z7GT>SE|xNKKAv|B+e&Q2U~}}T|LFRS$Ff8Mf8H z$$uHaN@iS(e(l883;k@0Z{gxm_$Dr7x^S+%d!O9`zIZSXXht(^Lx2tPv#|MK7GCo= zaF+nwwE)d4G<^NO9Nc9ydPiA&_{QX$F;D$~lVe$kl}O_HKfF&IaMx_o_Cq?6J*8Wak6UBSXsMp zw5(nZWpLoCg7l-K_oBr(-u0Jv1 z4mmXKW!X8WyMfPn%NEO+HQRx|3}KM8Zs^F3$(6b+`85Y~nS{A9uzP_|UJW`%KKW0$ z7#j?^EpE+L(5RWRV{T75I;Eu$6B)r&xYwQre*c*CunXqa@y0M3EZ8BuK zn`pZ^SLEsJ-p}znjwSi!NwYmvFr$Z9S;>_gV!g^)Rn7c^ZWsFVq(Ly zO1DD6mfJahkG};x_iLHGd}+A!?j*+PJMh**({~-q!CV-a8;frgIJ+C)>$XraHe%f_ zgD)MP`mCHD8i#9IUk;2V z6~Q(pRE)*1-V7SnU;c@&mWnUPMSqV_lF(7fn~l$|OlD#wQv3hnipsCEzl2V_G91h; zg)CR`>i#owXq<+|Z8-8LX<1XyvcsX^Y$D`p>UgK(E(yRG=XiThCC#cUL4t*B?tX4# z&5GH5Gv1XMzbp?GbARHSeG58~C#z{lc6$EU&HFEcemOW4jE!5p#lYC_Ml~V<(0e>%S!a?m&uP^&rhroccm>Z*jO$4X)biiMp}$<+>Z=`Tz0<_Puoi+-^}uoe?diw>0Df9 zy>tFz&7^bx##fS+i{b@-lwg=U4W9Z{zcu?VD4yDP^$M0_>e3ZLped>xa;%4hNN-nP!EqTY4NrSVz@nxiG zH6^FUoc}yj_YEDI+E&IRcED|%p)(x9-z%Te*aWfzR?^#tWxtEUcT@)Nx5e%K$pikF z^k`6=(RS9bibwJcPfO2C{u%$;g^4p0d;i4WBny9fX-H9PV&F!9DPII3t?O9 zgfr>@$q8?ThcnV5V68(#&@~5Hjku$YP2HMXcEBDI$~;^s=ln6LIb!Bqb%x)8w<_n7 z>^5QRfxMt+j`}9!VGmAwA>BBb*g;9mhnMT=T8hmh_WP^knLGSG_zML~p}gmx6YmrH zlAUM(=IsFF>yqaJ-r~0&@SwkraT=r6CL%UE5NH354v+rq{SLk;(5?LQD!Ae;`pu&9 z;Uig(H_DE?`zYD@ZPxdNc>HsMJKli9b@WkZXS{*_GA8Ifr*CG&y4|2>?E~o9??aT- zx?0Kp@595}+lUp49e9;1*78Gki|$xVp1EB~Vz2P-9}0~KcFw=R*m&4p?!4Y(_-WPs z`K4l6uc1eu&SKl&pNJ!6JeJd3fnLNzugjKkaFcc(WlT_Gr@k{cN$YQd{ME6El9s^3 ziD9ARVfAOAZI55#-=Z_g{=8?A_Q1Tb-w4ux;`EK)?&_~By8xr2A zFGRmlRGz#QG_-$c&uCpQ2K~BBuFhRUZmXc=|84_*(8pozqGZAQKH1gVBcxrr{*Hc0 zNz^N_0a|>troNnSI&_!ol)UB}D)0E>m52n}3_v33TIC z2b*pRO*7}$+~@97TJE~h13D7?8HWdXr1>p*mpKaZ%`;^3cj!6Q#!EL%aE&V;4<<6)U zGOD(eWehq;OfYUP+R3lMZvebhfj*A)98Po33F^4i_qCFh-Oet3TeEPa6Kxa3 zeobATbUe#rky2tEwfUOkA$!s<7s@wD9qmr_H0Z}^>8K`1%Q_0QA~@dqJfkFck5VD= zQ4?$2=k9x@+zX#7b=qM4J2=2257ms3FTKcZ$LYGQuV;hYcVlsbzV&O3KJ_l`+$UlU zGU_N#vi4qsJv*h@O;K_(O#M9Ad$|3ban5s>{pg4{(32KDmTtq_XALif+!zD;x)GRYuSZoU+4%L@rEPyr zsEd4Uecl%4`S|b+NmpbA)<&$`OWw)cP3^a^5&4-`OoZ~AKK1r$pn)~wt*2Tex0Jj= zHhqnQ6j{i=XWUTvD?CDZ+e)`W{mpoB^+Z8=qmh!|`Zzy_&)xsMN19a6CtrJia>U5n zzOm3Jypnf9S?B%`YY!?J;`!C_KAn7%Wa^tf$M?36L!^$A;LCB8-8Lk}tv`GmgLHOj z8+d0a;OuW5)@CBt$0_&3ZA>UrUlVhq#H+u~;BA0Plo}V`>6$z6d_Cx+nmD#l@kU*d zJg;z#7>RpDiJNUXxxYsmS1l~vy+3PlGF_dLXMNozx!*}_u9lv`8tL0` zwO{J0mO?wiDVq#Kn?seWK-Z?hhULO9L-`wZ4Ar`jbcL_spOMZqE(v&RRJpkH@GjS4 zWeRlGX5J2x>ywiDJ`rn=#K-{8HtqGqT2Jo^>DM}Iuy%4>MfgoOYVn47-;Nr0xy}~e zpqJdN!x`H)AYRJ+KGL&a_a$;W)mt(Z<4v5I+c@r|H2S zXdHc8uiUF-PhV%e?d#`}dn;W5eyW$>#;apeC+2a9?W^%^5NnU+HtZ+Fm2Ue6IHoNn zJ!2S&Yxd1}M~gMiG3Ni3vw=0laWemDi4JR%R;@=psS+6)AM&q8mAx`lC7r>UiMPq% zPj9NR@>FdlN&Wmdcmw%UvHh=%9M)3snY&kMDOEX2e(mjyH}ccRZjP0YV1Lu$WhC^> za>Z*)o{=_tGqKh@FYIYswAb-opLu_Pe=F;-27`<+e@!>fXxk4PZ@$dN8~Ak--Sb&< zDhWBVk@%(Wg)wR#>Yy6id?-9K*g3SrJq2HZn{D~`!5(ST zKnZ1e9o`1O_FLqJGJ(1RvG#a=>F3#`y@vPsz&rh{+jQ-7cVc2=N1p<)_Ws0;zoDm@ zqbGFyaVKfo3LVyHo3Zyby~oM$A>F7N%0zY25pRRkZn;f8Ceic*rH5CBcumx6mtoGG zX&c{>{?g}xx31n9TI`U|Mm4x3)sH}|J$VtZwo!XNu}0t3w71W`9%`Sn)$sY~<{NU` z5%9Q7qiwi%ecf}ZBOjjnT*R=(_oY9+ms;V(u%4@%xRhZx-u@#Kb8`pWB; z4IWcYAAL*2%YEXVtHn=e?-cPoa{L$v?M(cv@Z}eLd^boJX9o zy3iBe56`+S*G|*SW9oalc}LrR!n@;xg*f1K*i59QgJb?k%F_o0ieir&W{;XcHx)UW$^*Z$!!5PV{s6WFg|we(dUn-ylk^ zj;Cu>mqTsQyVb&IiK79zt( zQ4={2o}-OT+c)FAkiK`b&*AKMz#m^vJ!AOei7BV;3-yykwYfBGKAP*(E2Qpq9vShX z6591xgT~sw@1Ki8j2ZGPJ;-;1KZ!PqUfxxPkBV_c-MsS+`K+rqK|1>4j5xG*zP|FD z?;H3IzIOC2Ojdu(!%=TL+HxntmKa;Gh^XArz_U+gzvq+r!19t0eMbDp=I&nE@vRrJ z#vb^KJwn^^5yU@HUuI6I^&KMh`^1F19cwp0zN#8AtZhhsN{4CIvCgb_;~4RqX1p%_ zR8BZ!JAGQkiQetl?>9#I8BX@ab)*Oy+bgc`bdepTU>k z#XC*tV`W@rdtZNf0a$M1`&ORteJJ<)UY0vNPf0b^M9QfKa=EGv`-?Zze}-wt*jWjl=0WtZknEz2iJN&0o0ftZVfWV%prW#=o^w{UvvI2cM7)d-l`k9Wkql1-HEKpg-gYUTE?K`yvaXQ}Md=z$HZ>vIx^T))5z;FH- z%GeHPoiQu1=Jf1|umv?zFUg`0B5N}t4|B?gft*z@qgVrdY^|edbFmIdD03Bwb3TKt zPG5l=*66>wMLp~s?*W@uzNzJmc-bxwxyN$Y`<&RzD|N1^;3&&G&3RU~GdAwt$`?gk zw{X-Eu*S*IwR`XZr;oM`!`er{nl_#zarW0|4Qp$^P|!8scEuWT_^z5PG4ES!ZKxxY zXT&v<>(dhAMb1@?avm9rm?5_q4m-}w<6n`-(yYcMhK+Rs=tfrJD3oWDx85B6AmWZA zYd1MMeVU7OyyRXk{#1^^HHpU*QYRHL4 z{Zb$D;tCe`%Igi4On6-x@s>_GPbQv%?SJd5q~^6zQY^ZHv_^~?^-sp>G7fE+=QpJD z9hPb8ziflUO40R=_|9PO74F~tYa6AFk%c~5DZN;OUZC|!alNo``2X*JPiz2h%)GA-mzsQwjb=h-AYRIYsCy-fak6PqHaLW z@s&z0yQHk#6xBo;t5*;Q^`W%%bb}4|TZ1OP@0)7)O+WR{Gjz@Gyc=bpXS)pcB+5w7 zKH&8T{J?)Ars|}DTVmJ0okFhFDd6~YNLc1QpQ;_3Df7hoymtD-W7uF(pe22D4Kz)g zAGK-zz)X1uxA{+kKfa2(UnXJf-DunAY6)zvU?3sL{lU&5uN{V15?|FA$@LX<+}SQQ z9Uu=H`Nq&a7>}NBQaK~GBhTn-VQ0QtV!yjea`(DYa&<3-S|nFU%sZDGvAa>P6ct~K zOGVwEPZaDssus2y*eYSW7O{Dk7nI8{zD_Fo?vR_+LvpuzPMZ1NkOyJEenh<|kE;*l zaZgw5yUPFJ_y4Ib^00bWs(2c~?+{ttz#OmSgbsSF!CtXx%XSQYcz7GS`d7+oKcvNP za>V`Y<~s!2Gghs)+Te;c##G*LNhSFsgq%OO=h5y)`&%^PJj~kS;rhEmKHtPC_X|@o zOKdY%*uXC0j;Y%)XQpaN4{8B>;5+lmdgLyz`_jMXZ{{*@`^GB=E%~Z$@0p&zog8-! z?7C_5mw}fP*uut|`gk$zYNza28@V#r$ zFUlBg`|=4Txq{R}3K>f_`(8$`Q}y!5z7TQ^!x`Uj&z97@)J*k zSoq`Tx?*h-Waz4@sZgd*@3SASiQKI5E_rtmrd8o!js6kpO7?f7o^8~)iGZwXy*KN5 zy#{?=)z4$BhZ9vZm&6bHSc^622i?d;0fcZ_h0&`!$ro>-VR@8|1aQ)3zT(CqmZ` zfU^WU)_CtfCN)m;J*D?uoUYsOl``^Iy#Kqzh`D7fWV;6bdU^E6Gq+`++T}{yh9Nhm z;f?vy<=c$5zSpqm?zE9~Jqhx+(#Ey zYKSY=s6RAO9b`RXh3wA><(RbrRl|G{%bQ_-eQaz&X{kP!s5<#2)}fBMiA{4)9XQwL zS4hF?G4d^RBYWHv--U8%=VquO0xZP#yHZ}hC$uDr)mMr=o#wbhxQnr?YJhz!B?e(C^IjEBt+-x9}~bqb1CkA@x} zh!>9cjRk52^~Zmvew3aq1Fv-(U+dpUKUv#8<{i*BeADLKXJpUXMU4GqoB(sHeeDW4 z=TM_QE7#b%?8a!rHf_kBar$@Jh#C~?K71FbqshLiCkx8ruKIJW@96fs6S3PHd=v5N ztf@E>G|tQer~Edwt&(rYj?>XKwqfDm(0C|n!d#2<)2vH2Clho~%4N*G^FoggsN2Ui zF+f+Ae5fC@Pn#?GN-cAxZM3zOEm%6NdX?7kCoS#x0KV^+kgJs*zGvfy%)z-;J!;6B z6V$)Rm6$9ADijO zd{Zt%H}WC|wMUCoI!U|Z?T9apdc2@Cc;Z?33X;>{4SrDs0ELD%;?mAPdAxMVjCAoM zr*|XH7{lRxK6NcdbG+y;CqH$%b`AXTkEqVBSfkyojp~yjTO0K{%G>JUiws+;*}wGe zy-o5Obj`F04phI&?Y<`@26cT&LwMiZ@GW$HFtk{dmE9myp>Ov7&@K`z*U&z;{I(7c z^v5VG59^jFL%*`>w$y(qKeOilJx{mQVh!@wOQB*7vRw@w)>bc?;5hg8eur{QpSX{) z+ob(g8o)dw_=ViQY3lcND=J}bi#cz)eQ&i_PbbX4Qu*Y=|@1H zt^IfTo%@?o^1SL5&}YWxwNzigS5?rUB_;5jQ0z6#|9P+m>Te;I#oia{i`QT44eCFk zAC7kKc6TW$idcnwSNf1ofm-3f9p5`(d@zQMD#I28*(Tp~+`m>m!8)*M=o+vSat#K= zz5P#zwT%&s!zF#csRG^&V`3jC@|sq4g5!fVh2BvU1Ln<+H^#NqjCvqIrVSXsAabPj zT-IB7;#Tlf)ZGoYmZkZQysmhW3V{CcfPS;a;ah5)sEbhp@Fm+EJM=LQG=_aK?`_{x zkJj1Y_)e6&mw%$cIjs{cQ~$x8fT#{nh(|`{ReHWNB0-H2EjgcOZ|Wo%1z3|AtbCC2CT@pbvGi zmI3WgjCETAU9cZyy+^9yePL@?&lQqfAC)k4+XvKZTCDLKc?I?y#zndHW$eq8n}XQ? zsFT)-4XC&DJM2odRYp_4PLU5u51Ehexh*&R_U_MR9Z$2i?2##tX|V=6H9n(Q`*k+l z57xO($8XLN?SVSpY2^WoX;6<{WXvUNjPg3GjB56Sb&y-DZye{%Pv1_<1F*HZ)u%M? z7xo@_C#@rYrOvEdqk(eIVc2OHUp)B@CH-3~sa6{LH)1>e{R_-ToS^_gT= zwLElp1h7V%RmioJ@m=N_0@(n(NZpfHZo5)RxBpYZZ_9jd@`DP6OQey1>~q*nElRho z&3slQ_rt-5yQrC3tg-Lp`^2UFnbeosLyphg)4d)wW9FLH@Cet%;XR1=j~@dqw8qG% z;EmsX4am;qk@n}g9se<@i44;CsUm^3#0+AMeiZNRsE1(JJ8j>X`K<-)fjh1jKp$lk za7SAsYkttz@cna2K2q}>=Z$kmS-fiTvRb<1HlCUFH^xf1`E}`odm8$YsS8q;r!G|V zhA7GXHR3ig9s%QH8AHR)4}aB;o~hVb^%?j$>xXI9@M6q-de)Kteey$@M%Q-C{U$8j z+vjNvWDMHPoW>~Rc3_qD{a6nxx_p#eS3=1>s*Nkwh_}|NC-T@*$KT$+vw2J#d^6Z9 zhN^wqep4^4g_>WcPbi@yumYJP6#bX}2CEOAw7)6zP3kde#+Wi4zJIfJVmM=Pc*^5i zc@6e8ES{1v9=c^-?+jt>v053dp=|kf&x{$yin^b-ZXWpKf7Q+#amJ0dwm0F^3uip- z=aRm#KHSoe{PLGhhO}R!J0`t)5&9-`zs&yG_sp-D2pi-^_~<-XPb-*wW{wGctrbv9 ze{dUR=vQ3ZQpY=aKC#=dd@B9a_0_5E;I!6StRW`~KnV?N@G&&h**w<$Ff85kMA<&3 z4%T7R;UxlXl!ISY!yV_1^T=FY=o?yIrUI z8-2W7m;QFolaBFGLHs$UjQ3wun>{!y2Ve#_bJs2hiH+NigdRksLrI6Hl?9>1;P zjT}C+U!m?rY`9_O1;3s6i0dT3s+M=Ikhut5uf20SDcX4{(NVI#N zEg)a3<&N{lIUJ()O4DlLub;@Zh@5H)(nnMnah$Zbo3gz5-nu>Q^{QzBLq}pv8tYA4 z@n!w}4)|zHSNAobGdgzE^;_H)K5e5PNk`XU%MCdWeDd~#`Eiev_WLBPSeY)YQJ1dD zH3-tVwo0gDNjlLSIcwIr(*3?4d7I(b+77_Zpb$Ui7VBZy1DjuL#H{G>Wwuc#Xjs)F zd13cAJ| zsx<4Fja{<^IaDae3;8&ljj3o3i~N<8l|;>Dpk_VE#A6b@R;r&|jMiu>)rOqxJnV z<2U)-dupoVyb*7-wUsY)RY0t-*8I3U&qC+ML%vZJ=cg0yA?J@=7Of+g>koT zdJTP~hMX8-e3{QT_l)1TqH=V|HCrd@*LL}L;JSSn<p`retD6s} zHriX&(-B-(CCGSlzL_7+Tq=`}>GrKu563u6-Mjn+8x><0eTtpIV=JXF%dqmxV?={G~N8<0a!BvIcOIx$G-}c`p<8PFq z>wZf^*AS1k3w6}O#o9Y|y2j&eb9=e=A)rt26}GGIU_;EraZ?X@q_5iSiZ#}=5615T z-UT?JE$!W=dVeD4*`RAFJd|-^jMumpYXF*Yc%+YaB3?Ei{y1eEe291Kqc%DAnQN=+ zu8Rb|?Dt?CF4`*Cy7;Yia+W-W>%RsP4^oCa-De3y@pk z53=`{$E*+iiW=&OHRd43e4xKpcfX9b(I$5b@W$K%-TZE!+cOPKBVK^Dcf;YIJQsBE zavj#Du3U|0hgQ>z>*9G4%atzzvHIbR9c|%-N|p-hkEgAHaY4GVbZhI`625P{%?t7u zeb_1%@kI^t8M#l)X{Dc>d6taLC=6N1$;ZUp(Hm4fN8V3gma3y1`FA+u6Y9D2KipZ# zBaHvGkH=3-60}$Yjk-5ntl=8UZ2QvUZC^;W*ZeipP^SR#dZE5sB+sL-)F~d(q;ZC= z4Sqsm!9JF5$Nt<=*yADFP_B=D39*rP#29sjlov8X;ew*Bf}DDp-w(z3amKe8wT@h5 z2T#+yj`}EVBK1)d{cQ13V=kcAtDAG5iB~hnwU;fH7$tK&o%ZA@U5OiC0ptFR z{rOt`V%UheX3>-sI~n~KjM4l?t(FdIH0rB9BEDt?{CRK=aW0H2!9Yj&?(yJu=dO1NkOqjnT2axTlK9- zkB961fN_QO;|HnV9OsU68LF*~@#bBCv0GGg`2cZeqfwL3js>@4#;Ny#@1M42?|sO% zhOOS-f5wVeSB)KG+PTi9strEsfK~hb(tFJB)OUAY83f#)XJ&~~ibkD2osk@z7Oo)c^=`TW<_NLNgZRewm85|^d1O_=XPJO9)-;rEDXAdI&R zR%_4=Z|2`vL#__|oY8NhwwqO!<@W(UsndE6yo>aVMYz{cRxcNQ zEBx{Qy5g;s>aMl5@tdYT`50(XusU2OjzZm!$NC@b)c2wqBUZ?gOGf`F^QoNf(^*Y( z)MdjRAM5$Kzb!3gDn-c@d{?yB*zsi^|2M9fj6kgo9Ss_@X@4OTJK^q!uGvl7$2YqB zu3b3Fu|M=dMebx%ndGh5FZ}q<@s_qB{9UGlP%j{-UH2!$Muz#FW$ix0xSmaR!>UP<=HAHwa%= zGp_;G?$BXv{OV2GevuY1XNhB$Rrs<#m+`xlk)~o4oaUccx>4PI#^%a#W(-tQ^(JuU zP7|H(8BRODg_s%_``1n;ABBx>u#23@nz`Y|vsuT){+l^%jK_4sm$jYick1u}+5U}_ z8NeCw1|2pU_uj9&|AA@k)AVn}r?6pSZA|<7MEn?YLVJo~Q?bfCcKMEVXs$0RBh?{C ztPvM)s4)ir;JDI%6{tnzlY^{$SL$N-xH&*8ywV*va9j1^xH<+Nphm|Fgk$u-_tHAmVh)La*rO zVeMpNT<}cFR;-gnyTr0j{P{-jKZIPqtG%d6S=#VZ`s)L^`{VCXFB-YHtfMd>NbZ7( zH_BD?V?GOC{&j_~GHM33gneIKo0-qC z@0rV!XH*2^jPU(N!=A>xK3(n}$9U4pby}6>|W3JmB=h%83 zZMDs?&OlqpSIk4E{ThxjgBN`P`tC(ttJv?al)NLaHR@%sRz{`#cS%pR*75#apYk^E zW60IX3p$tJcwVIWs4*{~lexgZ>%uR!pmSiYh2(@cwKxMNPK@2W|DufG%X;lm$Ze4Q zp4VY*-0H2UH3?P?+;g0pRLgw5fPQM`B=cLd(s=uC`u>~W41YKBZ#jnc`ao9P@Hg!m zm#QnV*2*W2b8KGI2XQ2|N>nmx`s#dK)RAbHW6d9<4g+jJj0s>ot{3%gJE&2PJd$)$ zDd<>OE6?;pn9nu$tkD`%3$?Hyw`TbJweSqyi!lVAwwGdECWUpL{bS7auXXbeTztnm zq*lCS^f&7NPXsgq@ND;KA1OWKG$haen7i&*~>jrLRED2 z$5U5*8Z}1SsJ^aPBX6r&;`*R5UT6A*Z}8v%CI16oWDRfTE_qtymlq)uI>~V_sD1|C zMq!OB6JORn`+BcxtIzqgVMjZLA)G^7g1R$SmJVtIoM~%c$*>K{l{1Ph`}KpdULSDw zxejZrZF(xMq%rT5lQJD^{PqxUeHZeVbTJ5L=Ga2_h&lS0K2-~~b7#(Df3-d6IZvpM zgmK~a=a7do2beXObag!#k5vCg)Rck`h;ho^mKQntKk3i7N>y`>A29eR^q%x$DU|Dc zZ41dK6MO_*Tgs_FtUVJ`J#+Y|F~+nPT~}1T`+1v|e?lj?%LywPZJ(WZi1v@(I@&gN z%{KXO{0(w_QTT>u`fG8Tn9%N7R|4-s`xx~p*8ZYALwg1NnA}r`jD?TdSknS?W0y@R zSKNkpK3#2W`yBI_dh0{L0BsOX^B1iB12sz+muJ5}Wy4A(QrCLn`&^E70T@qY&Euo4 ztWbN(d>8r)uDZOs=y)aLMp!$`$%nwc-ly96>0}5zQ9BPV*ToLJN*c9(SzD(R7+40G z3Oz`_pCH(^klRY)Ie+W$wsz5IBQDjbA8mUF#?%u_{O&1hsfy83qd00>RQAVsajmJr zZIv;P^vSWl7~>4+k8BQFS+O``5K%KmwJv1XI`hW)^?l;<`{&Zmy&VhYG3E8wA(sck zl+)k2)|GA@3)aLkYO`40+lZY+9v^LvhK>rna}7Z1Hr9FPcg1z`bkC$*rfWCbXvd@d z(0ac}{r0xHNZubaLrc?uvwMPJC8K}ecl0ph+CI}^ZP>a!vT5l5Nuf%q@uyrDj(OGh zLZ=z{yx%s!d7=Dd*r~yH$$L#KX!rO#b3_=o&zj8B-$MPo8kk$G^T2T?9<|q52&OVZMUG|MURyi6I+D!{jmmX@RE4{GKsd-GBt$n=(K6~zau&sRL zoS#lV2G?$I%E#v4=_^Q2%o1%QhQ49NZw7z+kPrLTpz&IohWW2yV&QD;p(nho!y4Px z&*)*`jW#gWP^63!G8QznDALywqfe-h(}lJ6YM}hkCGGpLra9}^1kkH6=iB>4fuJ!d zCg!dCu4*=F)<>>Z3hM;k()bb3w6wlY=$?beZ{Cjq$b6b+J_B-_54=?COBlKKS2;1U zakj#j6|dyowXTM27-noO=l5eZUt5b{G~`RlT^Yd|V|6L(TX7W1Z^jiEe3bfAnE1Az z&w7f!+Ii%&=}UAp?HJ~~u!(`QxkudYZBDdpHr9kc9hW)ljazY(-rua{&A7u*=F)l& zV`iC`XMZm1GV1Ek+UL^s*oY_cImYE$`(gk6fO<9Kd=zq{?|%j5#U2B7IHTS6#UZN_ z&nitb@jQaLRt~Y0#NgT=Mx>b&`y6G}G3%+;_B403C)nqc$CRfkM%|XC=2`-3mPaDy zowV^KH7M+FfNQE|wB{J=I5chdrVL)YHx1T6&lV0^pM+%1v&TE_&w}4IANrw<6Cb*M zuOubBm2L6XroIQd-`I|N1x#kUHH9l8Mg)tU7T4ryfAB%NCt$knjCF~i`WH3e)JTwNiYZ=qjL#+y_ zFV?;_MP2ykTu1t-`!YxFWIca8F**Xi(@w>WeM-J;}LX?{)G34E!{R5 zaZmroR|}XM>pW%UZ`w|{#wgcYE*D$X@P`vi);Uc3`?TDRwVAn=qS<%a3yWQwv3g9* zW4f!HGU`XuW}No9?si?~F3?tP$CBG|F60_iY0yx5E#9b|JIF{A`>p#eTj0#Z-Gr?N zXycu$!y4P>VLixGaYfF|jX6izX-~Y6H$Ho(k~>hVrHh&&W7JXYoOg$P?#=sCvBvjc zojJyFxXrEG-{=#fkAZdcD=6BVPimj-gh4+a^@PSpNkg$-)g6yMEq#`5(c^4=(r&Cx zR=}L&?6gOYUm@Tv$q8>iE}e~-vs~F4ZzlHXH>WSXdZ~-0h3ba<^)&%=&sd;(s#Smw zfpy!2gan_>3K?MI}0aYuo?1kXcyMq|4bYF7E!3P@<7|y z<@*(hTAX1H|An2QN_N7Ry)Tg6t_R-!a>Cp4#S<}>QRf8SIOl)E7DxXRYhhK*-N49! z@vlj6+K{QZPOK4&o??Tho%kZGV`1jtotfVdu&185IH1lRYoO65T;+-aM(!YM<_D`Q z$Jk=0HRaeB=3saqzerlX*Hs3tNo%W3nYYuBi5{K3_pfZlJMCE82AvrFZH7&&EAU-@ zSv&#sE&80nn?dW~+oC^~>-IFMuH=5iUoa2;9@Grs`kTf%Cf>S%zE$!Gd1A;|gB`Z? zJ|5?kp~qizW48|yYOHq+2gVL$UcSwPx;{J9KS zm)5S4f-}T*Bz-z{$H8okGZS}-f1XsJzi*j+*X>E)PRHd9m?P_aW#`|dWAwjsUBs)4 z_s;tYIgXzx{f&Iz2EcpHNL0%O{E5EFZp-%iC{9xzAN z`8pSVvsNV69pc{JU+Nm25gVXTvy?h!8oaS)+syLDI%W#%&MZ!e?YG}YcT7JUYu9tF z?(5Y(##(92K_J%XM`KKl5kCWZ%ySvjGZ+`JS}DWmkKz)BJ|p&iFg7b;mf}neX^(I1pc4dowLqRi8sWgP(OVW z?{~_4U)_H8@}-D>Ym|ex6dOu7xcnFE4*a}invQ-2v_Y=vJ7L>F7@p2u`7Bu9<2FNI zSfA9y&E8A=jar*1JLi0zgSRm7mOQ_7ImYCk; z#v{Fr@o|;mIDX_0yJmd~|JJ$VPYp-b3jJJ<9GL!!B>aL}_ZXL88+3qSz*-*N_+Myk zlXv~Wc*|Qc9*M!mjenoMVukFR@eVKtlaTE@Ki`iJPkmMv{JbD2zEZ~VFvhh7a_lY$ z*({vz23X4r8pj$AL1`SU~DFM!F4%uS;plB*p285 zlFlA{_9W~#NeLZg)uM4SdF9%$@s;xaOMtO@6Sp18(!9;A;(wX>-1trVXdmGkS);Hy z#{IhEaGy*C?O6Wf6iJ-(mHa;WG5Ig9bf(h2Q*p%+$8xXi2G&jb#> z-7mA@n_G;n0nW|gm0|MAaPbLUj5d-o81Jt!-hYNNKThXRx8SG8tobOvZ0N!gXZ|fY!Z; zd06Q%M`6j=)_V{igV*nuK?WXo%Wz<3_;FDY8ci5qmDRe!~RI%DNSGT zUWwScqE=6_ksEX9m>mOIam*UQkX4wnIVg@r>G( zTog3#L16BE%yj~`o%kKpFP2V>p2GbP;@Uabe~RZm3E95P$W6(f?^o?QZ^kxHrh302>`ZZ~9|+tk#*ClAH7^mXvs zyYRc_)a{4zV!cB(u{R6Ngw~&&^DgXhdU3=IH7oJ3n!N3xibK8FiP+D?dJi+U=hz=| zzKsj}+sK*!ocYheKn@0SFpz_R91NUS7{GJ}{7Vct@*kYlw*M5%ml*%d=bpyetz3JT z|ID^Tv?+g+*~Zh(oS1UnQKOB45crqUHs5Gdoh)tsOU;Y@=l$(JP5CV6C8o6bpX@)c zv)NXMCmL<$?NV-NwEbtE=D(rQ=IcHR2e#GGw3T98;Awb~MB8idMf7cfuf~^4 zw7o80E>QwsSKsErd4WT~K}g$%r5poijs4fPbxM@^ws%twZJq7s)k(AupHjNEQi=BA zQ!3Q9ixLCT!ahX0Emxv_iZDqLZu4pG=S#FtIVL@)&0!4E&XI0RBRy}qH2BlCWek() z|32^?b>=r={ipi|9optwujB7ddU}v(KTq`ZB^263dSwT`6aBMKx{h|T%}yjpi|vD| zYcptj=fIb%!)xaUwsm4#V(>Pcq~}qAFAQdj^8#Pa&+`Ib#NQV9A`o_PZD5<9uLgEH zh5rV0x|9FffLX%5ct2|gOr59VY2=cT@JsnoVJ52=&dX1<+Yuruy=W~hzZrQFZFp>aF2Ev1K@cssMr-$SE! mXWIN1moiQ>&oel4ia2?ujg!*Je_Co=$}xBT{#hC_+V=l1WBMKd literal 0 HcmV?d00001 diff --git a/source/gui/resources.qrc b/gui/resources.qrc similarity index 91% rename from source/gui/resources.qrc rename to gui/resources.qrc index ba61dc65..0f7c9217 100644 --- a/source/gui/resources.qrc +++ b/gui/resources.qrc @@ -1,5 +1,6 @@ + res/muon.icns res/muon.ico qml/places/items/MapComponent.qml qml/CustomMap.qml diff --git a/gui/src/calibform.cpp b/gui/src/calibform.cpp new file mode 100644 index 00000000..384aa4bd --- /dev/null +++ b/gui/src/calibform.cpp @@ -0,0 +1,214 @@ +#include "calibform.h" +#include "calibscandialog.h" +#include "ui_calibform.h" +#include +#include +#include +#include + +using namespace std; + +const static CalibStruct invalidCalibItem; + +CalibForm::CalibForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::CalibForm) +{ + ui->setupUi(this); + ui->calibItemTableWidget->resizeColumnsToContents(); + + calScan = new CalibScanDialog(this); + calScan->setWindowTitle("Calibration Scan"); + calScan->hide(); + + connect(ui->calibrationScanPushButton, &QPushButton::clicked, this, [this]() { this->calScan->show(); }); +} + +CalibForm::~CalibForm() +{ + delete ui; +} + +void CalibForm::onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector& calibList) +{ + calScan->onCalibReceived(valid, eepromValid, id, calibList); + + QString str = "invalid"; + if (eepromValid) + str = "valid"; + ui->eepromValidLabel->setText(str); + str = "invalid"; + if (valid) + str = "valid"; + ui->calibValidLabel->setText(str); + ui->idLineEdit->setText(QString::number(id, 16)); + + fCalibList.clear(); + for (int i = 0; i < calibList.size(); i++) { + fCalibList.push_back(calibList[i]); + } + + int ver = getCalibParameter("VERSION").toInt(); + ui->eepromHwVersionSpinBox->setValue(ver); + double rsense = 0.1 * getCalibParameter("RSENSE").toInt(); + ui->rsenseDoubleSpinBox->setValue(rsense); + double vdiv = 0.01 * getCalibParameter("VDIV").toInt(); + ui->vdivDoubleSpinBox->setValue(vdiv); + int eepCycles = getCalibParameter("WRITE_CYCLES").toInt(); + ui->eepromWriteCyclesLabel->setText(QString::number(eepCycles)); + int featureFlags = getCalibParameter("FEATURE_FLAGS").toInt(); + ui->featureGnssCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_GNSS); + ui->featureEnergyCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_ENERGY); + ui->featureDetBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_DETBIAS); + ui->featurePreampBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_PREAMP_BIAS); + + if (voltageCalibValid()) { + fSlope1 = getCalibParameter("COEFF1").toDouble(); + fOffs1 = getCalibParameter("COEFF0").toDouble(); + } + if (currentCalibValid()) { + fSlope2 = getCalibParameter("COEFF3").toDouble(); + fOffs2 = getCalibParameter("COEFF2").toDouble(); + } + updateCalibTable(); + QVector emptyList; + emit updatedCalib(emptyList); +} + +void CalibForm::updateCalibTable() +{ + ui->calibItemTableWidget->setRowCount(fCalibList.size()); + for (int i = 0; i < fCalibList.size(); i++) { + QTableWidgetItem* newItem1 = new QTableWidgetItem(QString::fromStdString(fCalibList[i].name)); + newItem1->setSizeHint(QSize(90, 20)); + ui->calibItemTableWidget->setItem(i, 0, newItem1); + QString type = QString::fromStdString(fCalibList[i].type); + QString numberstr = ""; + if (type == "FLOAT") { + double val = QString::fromStdString(fCalibList[i].value).toDouble(nullptr); + numberstr = QString::number(val); + } else { + numberstr = QString::fromStdString(fCalibList[i].value); + } + + QTableWidgetItem* newItem2 = new QTableWidgetItem(type); + newItem2->setSizeHint(QSize(60, 20)); + ui->calibItemTableWidget->setItem(i, 1, newItem2); + QTableWidgetItem* newItem3 = new QTableWidgetItem(numberstr); + newItem3->setSizeHint(QSize(60, 20)); + ui->calibItemTableWidget->setItem(i, 2, newItem3); + QTableWidgetItem* newItem4 = new QTableWidgetItem("0x" + QString("%1").arg(fCalibList[i].address, 2, 16, QChar('0'))); + newItem4->setSizeHint(QSize(40, 20)); + ui->calibItemTableWidget->setItem(i, 3, newItem4); + } + ui->calibItemTableWidget->resizeColumnsToContents(); + ui->calibItemTableWidget->resizeRowsToContents(); +} + +void CalibForm::onAdcSampleReceived(uint8_t channel, float value) +{ + calScan->onAdcSampleReceived(channel, value); +} + +void CalibForm::on_readCalibPushButton_clicked() +{ + // calib reread triggered + emit calibRequest(); +} + +void CalibForm::on_writeEepromPushButton_clicked() +{ + // write eeprom clicked + emit updatedCalib(fCalibList); + emit writeCalibToEeprom(); +} + +void CalibForm::doFit() +{ +} + +void CalibForm::setCalibParameter(const QString& name, const QString& value) +{ + if (!fCalibList.empty()) { + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); + if (result != fCalibList.end()) { + result->value = value.toStdString(); + } + } +} + +QString CalibForm::getCalibParameter(const QString& name) +{ + if (!fCalibList.empty()) { + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); + if (result != fCalibList.end()) { + return QString::fromStdString(result->value); + } + } + return ""; +} + +const CalibStruct& CalibForm::getCalibItem(const QString& name) +{ + + if (!fCalibList.empty()) { + QVector::iterator result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); + if (result != fCalibList.end()) { + return *result; + } + } + return invalidCalibItem; +} + +bool CalibForm::voltageCalibValid() +{ + int calibFlags = getCalibParameter("CALIB_FLAGS").toUInt(); + if (calibFlags & CalibStruct::CALIBFLAGS_VOLTAGE_COEFFS) + return true; + return false; +} + +bool CalibForm::currentCalibValid() +{ + int calibFlags = getCalibParameter("CALIB_FLAGS").toUInt(); + if (calibFlags & CalibStruct::CALIBFLAGS_CURRENT_COEFFS) + return true; + return false; +} + +void CalibForm::onUiEnabledStateChange(bool connected) +{ + //measureBiasCalibGroupBox + if (!connected) { + ui->calibItemTableWidget->setRowCount(0); + fCalibList.clear(); + ui->eepromValidLabel->setText("N/A"); + ui->calibValidLabel->setText("N/A"); + ui->idLineEdit->setText("N/A"); + } + ui->calibItemsGroupBox->setEnabled(connected); + ui->eepromGroupBox->setEnabled(connected); + ui->calibrationScanPushButton->setEnabled(connected); +} + +void CalibForm::on_calibItemTableWidget_cellChanged(int row, int column) +{ + if (column == 2) { + QString name = ui->calibItemTableWidget->item(row, 0)->text(); + QString valstr = ui->calibItemTableWidget->item(row, 2)->text(); + if (valstr == "") { + updateCalibTable(); + return; + } + bool ok = false; + valstr.toDouble(&ok); + if (!ok) { + updateCalibTable(); + return; + } + setCalibParameter(name, valstr); + QVector items; + items.push_back(getCalibItem(name)); + emit updatedCalib(items); + } +} diff --git a/source/gui/src/calibform.ui b/gui/src/calibform.ui similarity index 100% rename from source/gui/src/calibform.ui rename to gui/src/calibform.ui diff --git a/gui/src/calibscandialog.cpp b/gui/src/calibscandialog.cpp new file mode 100644 index 00000000..6df0f031 --- /dev/null +++ b/gui/src/calibscandialog.cpp @@ -0,0 +1,217 @@ +#include "calibscandialog.h" +#include "ui_calibscandialog.h" +#include +#include +#include +#include + +#define calVoltMin 0.3 +#define calVoltMax 2.5 + +#define BIAS_SCAN_INCREMENT 0.025 // scan step in Volts + +inline static double sqr(double x) +{ + return x * x; +} + +/* + linear regression algorithm + taken from: + http://stackoverflow.com/questions/5083465/fast-efficient-least-squares-fit-algorithm-in-c + parameters: + n = number of data points + xarray,yarray = arrays of data + *offs = output intercept + *slope = output slope + */ +bool calcLinearCoefficients(const QVector& points, double* offs, double* slope) +{ + int n = points.size(); + if (n < 3) + return false; + + double sumx = 0.0; /* sum of x */ + double sumx2 = 0.0; /* sum of x**2 */ + double sumxy = 0.0; /* sum of x * y */ + double sumy = 0.0; /* sum of y */ + double sumy2 = 0.0; /* sum of y**2 */ + + double offsx = 0; + double offsy = 0; + + for (int i = 0; i < n; i++) { + sumx += points[i].x() - offsx; + sumx2 += sqr(points[i].x() - offsx); + sumxy += (points[i].x() - offsx) * (points[i].y() - offsy); + sumy += (points[i].y() - offsy); + sumy2 += sqr(points[i].y() - offsy); + } + + double denom = (n * sumx2 - sqr(sumx)); + if (std::abs(denom) <= std::numeric_limits::epsilon()) { + // singular matrix. can't solve the problem. + *slope = 0; + *offs = 0; + return false; + } + + double m = (n * sumxy - sumx * sumy) / denom; + double b = (sumy * sumx2 - sumx * sumxy) / denom; + + *slope = m; + *offs = b + offsy; + return true; +} + +CalibScanDialog::CalibScanDialog(QWidget* parent) + : QDialog(parent) + , ui(new Ui::CalibScanDialog) +{ + ui->setupUi(this); + connect(ui->startCurrentCalibPushButton, &QPushButton::clicked, this, &CalibScanDialog::startManualCurrentCalib); + connect(ui->transferCurrentBiasPushButton, &QPushButton::clicked, this, &CalibScanDialog::transferCurrentCalibCoeffs); + ui->transferCurrentBiasPushButton->setEnabled(false); + ui->currentCalibProgressBar->setEnabled(false); + ui->currentCalibProgressBar->setMaximum(5); +} + +CalibScanDialog::~CalibScanDialog() +{ + delete ui; +} + +void CalibScanDialog::onCalibReceived(bool /*valid*/, bool eepromValid, quint64 /*id*/, const QVector& calibList) +{ + if (!eepromValid) + return; + + fCalibList.clear(); + for (int i = 0; i < calibList.size(); i++) { + fCalibList.push_back(calibList[i]); + } + fSlope1 = getCalibParameter("COEFF1").toDouble(); + fOffs1 = getCalibParameter("COEFF0").toDouble(); + fSlope2 = getCalibParameter("COEFF3").toDouble(); + fOffs2 = getCalibParameter("COEFF2").toDouble(); +} + +void CalibScanDialog::onAdcSampleReceived(uint8_t channel, double value) +{ + double ubias = 0.; + if (channel >= 2) { + QString result = getCalibParameter("VDIV"); + if (result != "") { + double vdiv = result.toDouble(nullptr); + ubias = vdiv * value * 0.01; + } + } + if (channel == 3) { + double vdiv = getCalibParameter("VDIV").toDouble() * 0.01; + double rsense = getCalibParameter("RSENSE").toDouble() * 0.1 * 0.001; // RSense in MOhm + double ibias = vdiv * (fLastRSenseHiVoltage - value) / rsense; + if (fCurrentCalibRunning) + manualCurrentCalibProgress(ubias, ibias); + fLastRSenseLoVoltage = value; + } else if (channel == 2) { + fLastRSenseHiVoltage = value; + } +} + +void CalibScanDialog::startManualCurrentCalib() +{ + if (fCurrentCalibRunning) { + fCurrentCalibRunning = 0; + return; + } + fCurrentCalibRunning = 1; + ui->currentCalibProgressBar->setEnabled(true); + ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); + QMessageBox msgBox; + msgBox.setText("Disconnect the bias voltage"); + msgBox.setInformativeText("Disconnect the cable at the bias connector of the MuonPi PCB!"); + msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Ok); + int ret = msgBox.exec(); + if (ret == QMessageBox::Cancel) { + fCurrentCalibRunning = 0; + ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); + ui->currentCalibProgressBar->setEnabled(false); + return; + } + fCurrentCalibRunning = 2; + emit dynamic_cast(parent())->setBiasSwitch(false); + QThread::msleep(500); +} + +void CalibScanDialog::manualCurrentCalibProgress(double vbias, double ibias) +{ + static double currentMeasurements[3] = { 0., 0., 0. }; + + ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); + if (fCurrentCalibRunning == 2) { + currentMeasurements[0] = ibias; + emit dynamic_cast(parent())->setBiasSwitch(true); + QThread::msleep(500); + fCurrentCalibRunning++; + } else if (fCurrentCalibRunning == 3) { + currentMeasurements[1] = ibias; + fCurrentCalibRunning++; + QMessageBox msgBox; + msgBox.setText("Reconnect the bias voltage"); + msgBox.setInformativeText("Connect the cable again to the bias connector of the MuonPi PCB!"); + msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); + msgBox.setDefaultButton(QMessageBox::Ok); + int ret = msgBox.exec(); + if (ret == QMessageBox::Cancel) { + fCurrentCalibRunning = 0; + ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); + ui->currentCalibProgressBar->setEnabled(false); + return; + } + QThread::msleep(500); + fCurrentCalibRunning++; + } else if (fCurrentCalibRunning == 5) { + currentMeasurements[2] = ibias; + fCurrentCalibRunning = 0; + fOffs2 = currentMeasurements[0]; + fSlope2 = (currentMeasurements[1] - currentMeasurements[2]) / vbias; + ui->currentCalibOffsetLineEdit->setText(QString::number(fOffs2, 'g', 4)); + ui->currentCalibSlopeLineEdit->setText(QString::number(fSlope2, 'g', 4)); + ui->transferCurrentBiasPushButton->setEnabled(true); + ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); + ui->currentCalibProgressBar->setEnabled(false); + } +} + +void CalibScanDialog::transferCurrentCalibCoeffs() +{ + emit dynamic_cast(parent())->setCalibParameter("COEFF2", QString::number(fOffs2)); + emit dynamic_cast(parent())->setCalibParameter("COEFF3", QString::number(fSlope2)); + uint8_t flags = getCalibParameter("CALIB_FLAGS").toUInt(); + flags |= CalibStruct::CalibStruct::CALIBFLAGS_CURRENT_COEFFS; + emit dynamic_cast(parent())->setCalibParameter("CALIB_FLAGS", QString::number(flags)); + emit dynamic_cast(parent())->updateCalibTable(); + ui->transferCurrentBiasPushButton->setEnabled(false); +} + +void CalibScanDialog::setCalibParameter(const QString& name, const QString& value) +{ + if (!fCalibList.empty()) { + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); + if (result != fCalibList.end()) { + result->value = value.toStdString(); + } + } +} + +QString CalibScanDialog::getCalibParameter(const QString& name) +{ + if (!fCalibList.empty()) { + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); + if (result != fCalibList.end()) { + return QString::fromStdString(result->value); + } + } + return ""; +} diff --git a/source/gui/src/calibscandialog.ui b/gui/src/calibscandialog.ui similarity index 100% rename from source/gui/src/calibscandialog.ui rename to gui/src/calibscandialog.ui diff --git a/gui/src/custom_histogram_widget.cpp b/gui/src/custom_histogram_widget.cpp new file mode 100644 index 00000000..7c5a4e90 --- /dev/null +++ b/gui/src/custom_histogram_widget.cpp @@ -0,0 +1,249 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "custom_histogram_widget.h" + +typedef std::numeric_limits dbl; + +CustomHistogram::~CustomHistogram() +{ + if (grid != nullptr) { + delete grid; + grid = nullptr; + } + if (fBarChart != nullptr) { + delete fBarChart; + fBarChart = nullptr; + } +} + +void CustomHistogram::initialize() +{ + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + setStyleSheet("background-color: white; border: 0px;"); + setAutoReplot(true); + enableAxis(QwtPlot::yLeft, true); + enableAxis(QwtPlot::yRight, false); + setAxisAutoScale(QwtPlot::xBottom, true); + setAxisAutoScale(QwtPlot::yLeft, true); + grid = new QwtPlotGrid(); + const QPen grayPen(Qt::gray); + grid->setPen(grayPen); + grid->attach(this); + fBarChart = new QwtPlotHistogram(title); + + fBarChart->setBrush(QBrush(Qt::darkBlue, Qt::SolidPattern)); + fBarChart->attach(this); + + this->setContextMenuPolicy(Qt::CustomContextMenu); + connect(this, SIGNAL(customContextMenuRequested(const QPoint&)), this, SLOT(popUpMenu(const QPoint&))); + + replot(); + show(); +} + +void CustomHistogram::setData(const Histogram& hist) +{ + fName = hist.getName(); + fUnit = hist.getUnit(); + fNrBins = hist.getNrBins(); + fMin = hist.getMin(); + fMax = hist.getMax(); + fUnderflow = hist.getUnderflow(); + fOverflow = hist.getOverflow(); + fHistogramMap.clear(); + for (int i = 0; i < fNrBins; i++) + fHistogramMap[i] = hist.getBinContent(i); + update(); +} + +void CustomHistogram::popUpMenu(const QPoint& pos) +{ + QMenu contextMenu(tr("Context menu"), this); + + QAction action1("&Log Y", this); + action1.setCheckable(true); + action1.setChecked(getLogY()); + connect(&action1, &QAction::toggled, this, [this](bool checked) { this->setLogY(checked); this->update(); }); + contextMenu.addAction(&action1); + contextMenu.addSeparator(); + QAction action2("&Clear", this); + connect(&action2, &QAction::triggered, this, [this](bool /*checked*/) { this->clear(); this->update(); }); + contextMenu.addAction(&action2); + + QAction action3("&Export", this); + connect(&action3, &QAction::triggered, this, &CustomHistogram::exportToFile); + contextMenu.addAction(&action3); + + contextMenu.exec(mapToGlobal(pos)); +} + +void CustomHistogram::exportToFile() +{ + QPixmap qPix = grab(); + if (qPix.isNull()) { + qDebug("Failed to capture the plot for saving"); + return; + } + QString types("JPEG file (*.jpeg);;" // Set up the possible graphics formats + "Portable Network Graphics file (*.png);;" + "Bitmap file (*.bmp);;" + "Portable Document Format (*.pdf);;" + "Scalable Vector Graphics Format (*.svg);;" + "ASCII raw data (*.txt)"); + QString filter; // Type of filter + QString jpegExt = ".jpeg", pngExt = ".png", tifExt = ".tif", bmpExt = ".bmp", tif2Ext = "tiff"; // Suffix for the files + QString pdfExt = ".pdf", svgExt = ".svg"; + QString txtExt = ".txt"; + QString suggestedName = ""; + QString fn = QFileDialog::getSaveFileName(this, tr("Export Histogram"), + suggestedName, types, &filter); + + if (!fn.isEmpty()) { // If filename is not null + if (fn.contains(jpegExt)) { // Remove file extension if already there + fn.remove(jpegExt); + } else if (fn.contains(pngExt)) { + fn.remove(pngExt); + } else if (fn.contains(bmpExt)) { + fn.remove(bmpExt); + } else if (fn.contains(pdfExt)) { + fn.remove(pdfExt); + } else if (fn.contains(svgExt)) { + fn.remove(svgExt); + } else if (fn.contains(txtExt)) { + fn.remove(txtExt); + } + + if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save + fn += jpegExt; + qPix.save(fn, "JPEG"); + } else if (filter.contains(pngExt)) { // OR, Test to see if png and save + fn += pngExt; + qPix.save(fn, "PNG"); + } else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save + fn += bmpExt; + qPix.save(fn, "BMP"); + } else if (filter.contains(pdfExt)) { + fn += pdfExt; + QwtPlotRenderer renderer(this); + renderer.renderDocument(this, fn, "pdf", QSizeF(297 / 2, 210 / 2), 72); + } else if (filter.contains(svgExt)) { + fn += svgExt; + QwtPlotRenderer renderer(this); + renderer.renderDocument(this, fn, "svg", QSizeF(297 / 2, 210 / 2), 72); + } + if (filter.contains(txtExt)) { + fn += txtExt; + // export histo in asci raw data format + QFile file(fn); + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) + return; + QTextStream out(&file); + + for (int i = 0; i < fNrBins; i++) { + out << QString::number(bin2Value(i), 'g', dbl::max_digits10) << " " << fHistogramMap[i] << "\n"; + } + } + } +} + +void CustomHistogram::update() +{ + if (!isEnabled()) + return; + if (fHistogramMap.empty() || fNrBins <= 1) { + fBarChart->detach(); + QwtPlot::replot(); + return; + } + fBarChart->attach(this); + QVector intervals; + double rangeX = fMax - fMin; + double xBinSize = rangeX / (fNrBins - 1); + double max = 0; + for (int i = 0; i < fNrBins; i++) { + if (fHistogramMap[i] > max) + max = fHistogramMap[i]; + double xval = bin2Value(i); + QwtIntervalSample interval(fHistogramMap[i] + 1e-12, xval - xBinSize / 2., xval + xBinSize / 2.); + intervals.push_back(interval); + } + if (intervals.size() && fBarChart != nullptr) + fBarChart->setSamples(intervals); + if (fLogY) { + setAxisScale(QwtPlot::yLeft, 0.1, 1.5 * max); + } + replot(); +} + +void CustomHistogram::clear() +{ + Histogram::clear(); + emit histogramCleared(QString::fromStdString(fName)); + fName = "defaultHisto"; + update(); +} + +void CustomHistogram::setEnabled(bool status) +{ + if (status == true) { + const QPen blackPen(Qt::black); + grid->setPen(blackPen); + fBarChart->attach(this); + setTitle(title); + } else { + const QPen grayPen(Qt::gray); + grid->setPen(grayPen); + fBarChart->detach(); + setTitle(""); + } + fEnabled = status; + update(); +} + +void CustomHistogram::setLogY(bool logscale) +{ + if (logscale) { +#if QWT_VERSION > 0x060100 + setAxisScaleEngine(QwtPlot::yLeft, new QwtLogScaleEngine()); +#else + setAxisScaleEngine(QwtPlot::yLeft, new QwtLog10ScaleEngine()); +#endif + setAxisAutoScale(QwtPlot::yLeft, false); + fBarChart->setBaseline(1e-12); + fLogY = true; + } else { + setAxisScaleEngine(QwtPlot::yLeft, new QwtLinearScaleEngine()); + setAxisAutoScale(QwtPlot::yLeft, true); + fBarChart->setBaseline(0); + fLogY = false; + } +} + +void CustomHistogram::setXMin(double val) +{ + fMin = val; + rescalePlot(); +} + +void CustomHistogram::setXMax(double val) +{ + fMax = val; + rescalePlot(); +} + +void CustomHistogram::rescalePlot() +{ + double margin = 0.05 * (fMax - fMin); + setAxisScale(QwtPlot::xBottom, fMin - margin, fMax + margin); +} diff --git a/gui/src/custom_plot_widget.cpp b/gui/src/custom_plot_widget.cpp new file mode 100644 index 00000000..e62a832a --- /dev/null +++ b/gui/src/custom_plot_widget.cpp @@ -0,0 +1,225 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#define LOG_BASELINE 0.1 + +QwtPlotCurve CustomPlot::INVALID_CURVE; + +CustomPlot::~CustomPlot() +{ + for (auto it = fCurveMap.begin(); it != fCurveMap.end(); ++it) { + if (*it != nullptr) + delete *it; + } + if (grid != nullptr) { + delete grid; + grid = nullptr; + } +} + +void CustomPlot::initialize() +{ + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + setStyleSheet("background-color: white; border: 0px;"); + setAutoReplot(false); + enableAxis(QwtPlot::yLeft, true); + setAxisAutoScale(QwtPlot::xBottom, true); + setAxisAutoScale(QwtPlot::yRight, true); + + grid = new QwtPlotGrid(); + const QPen blackPen(Qt::black); + grid->setPen(blackPen); + grid->attach(this); + + this->setContextMenuPolicy(Qt::CustomContextMenu); + connect(this, SIGNAL(customContextMenuRequested(const QPoint&)), this, SLOT(popUpMenu(const QPoint&))); + + show(); +} + +QwtPlotCurve& CustomPlot::curve(const QString& curveName) +{ + auto it = fCurveMap.find(curveName); + if (it != fCurveMap.end()) + return **it; + return INVALID_CURVE; +} + +void CustomPlot::addCurve(const QString& name, const QColor& curveColor) +{ + QwtPlotCurve* curve = new QwtPlotCurve(); + curve->setYAxis(QwtPlot::yLeft); + curve->setRenderHint(QwtPlotCurve::RenderAntialiased, true); + const QPen pen(curveColor); + curve->setPen(pen); + fCurveMap[name] = curve; + fCurveMap[name]->attach(this); +} + +void CustomPlot::popUpMenu(const QPoint& pos) +{ + QMenu contextMenu(tr("Context menu"), this); + + QAction action1("&Log Y", this); + action1.setCheckable(true); + action1.setChecked(getLogY()); + connect(&action1, &QAction::toggled, this, [this](bool checked) { this->setLogY(checked); this->replot(); }); + contextMenu.addAction(&action1); + contextMenu.addSeparator(); + QAction action3("&Export", this); + connect(&action3, &QAction::triggered, this, &CustomPlot::exportToFile); + contextMenu.addAction(&action3); + + contextMenu.exec(mapToGlobal(pos)); +} + +void CustomPlot::rescale() +{ + double ymin = 1e30; + double ymax = -1e30; + double xmin = 1e30; + double xmax = -1e30; + + for (auto it = fCurveMap.begin(); it != fCurveMap.end(); ++it) { + if ((*it)->dataSize()) { + if (xmin > (*it)->minXValue()) + xmin = (*it)->minXValue(); + if (xmax < (*it)->maxXValue()) + xmax = (*it)->maxXValue(); + if (ymin > (*it)->minYValue()) + ymin = (*it)->minYValue(); + if (ymax < (*it)->maxYValue()) + ymax = (*it)->maxYValue(); + } + } + + if (fLogY) { + if (this->axisInterval(QwtPlot::yLeft).minValue() <= 0.) { + } + if (this->axisAutoScale(QwtPlot::yLeft)) { + } else { + } + } else { + } +} + +void CustomPlot::setLogY(bool logscale) +{ + if (logscale) { + if (this->axisInterval(QwtPlot::yLeft).minValue() <= 0.) { + this->setAxisScale(QwtPlot::yLeft, LOG_BASELINE, axisInterval(QwtPlot::yLeft).maxValue()); + } +#if QWT_VERSION > 0x060100 + setAxisScaleEngine(QwtPlot::yLeft, new QwtLogScaleEngine()); +#else + setAxisScaleEngine(QwtPlot::yLeft, new QwtLog10ScaleEngine()); +#endif + setAxisAutoScale(QwtPlot::yLeft, true); + fLogY = true; + } else { + setAxisScaleEngine(QwtPlot::yLeft, new QwtLinearScaleEngine()); + setAxisAutoScale(QwtPlot::yLeft, true); + fLogY = false; + } + emit scalingChanged(); +} + +void CustomPlot::setEnabled(bool enabled) +{ + + if (enabled) { + for (auto& curve : fCurveMap) { + curve->attach(this); + } + } else { + for (auto& curve : fCurveMap) { + curve->detach(); + } + } + + replot(); + QwtPlot::setEnabled(enabled); +} + +void CustomPlot::exportToFile() +{ + QPixmap qPix = grab(); + if (qPix.isNull()) { + qDebug("Failed to capture the plot for saving"); + return; + } + QString types("JPEG file (*.jpeg);;" // Set up the possible graphics formats + "Portable Network Graphics file (*.png);;" + "Bitmap file (*.bmp);;" + "Portable Document Format (*.pdf);;" + "Scalable Vector Graphics Format (*.svg);;" + "ASCII raw data (*.txt)"); + QString filter; // Type of filter + QString jpegExt = ".jpeg", pngExt = ".png", tifExt = ".tif", bmpExt = ".bmp", tif2Ext = "tiff"; // Suffix for the files + QString pdfExt = ".pdf", svgExt = ".svg"; + QString txtExt = ".txt"; + QString suggestedName = ""; + QString fn = QFileDialog::getSaveFileName(this, tr("Export Plot"), + suggestedName, types, &filter); + + if (!fn.isEmpty()) { // If filename is not null + if (fn.contains(jpegExt)) { // Remove file extension if already there + fn.remove(jpegExt); + } else if (fn.contains(pngExt)) { + fn.remove(pngExt); + } else if (fn.contains(bmpExt)) { + fn.remove(bmpExt); + } else if (fn.contains(pdfExt)) { + fn.remove(pdfExt); + } else if (fn.contains(svgExt)) { + fn.remove(svgExt); + } else if (fn.contains(txtExt)) { + fn.remove(txtExt); + } + + if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save + fn += jpegExt; + qPix.save(fn, "JPEG"); + } else if (filter.contains(pngExt)) { // OR, Test to see if png and save + fn += pngExt; + qPix.save(fn, "PNG"); + } else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save + fn += bmpExt; + qPix.save(fn, "BMP"); + } else if (filter.contains(pdfExt)) { + fn += pdfExt; + QwtPlotRenderer renderer(this); + renderer.renderDocument(this, fn, "pdf", QSizeF(297 / 2, 210 / 2), 72); + } else if (filter.contains(svgExt)) { + fn += svgExt; + QwtPlotRenderer renderer(this); + renderer.renderDocument(this, fn, "svg", QSizeF(297 / 2, 210 / 2), 72); + } else if (filter.contains(txtExt)) { + fn += txtExt; + // export histo in asci raw data format + QFile file(fn); + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) + return; + QTextStream out(&file); + + foreach (QwtPlotCurve* curve, fCurveMap) { + out << "# " << this->title().text() << "\n"; + out << "# " << curve->title().text() << "\n"; + out << "# " << this->axisTitle(QwtPlot::xBottom).text() << " " << this->axisTitle(QwtPlot::yLeft).text() << "\n"; + for (size_t i = 0; i < curve->dataSize(); i++) { + out << QString::number(curve->sample(static_cast(i)).x(), 'g', 10) << " " << QString::number(curve->sample(static_cast(i)).y(), 'g', 10) << "\n"; + } + } + } + } +} diff --git a/gui/src/gnssposwidget.cpp b/gui/src/gnssposwidget.cpp new file mode 100644 index 00000000..6914074a --- /dev/null +++ b/gui/src/gnssposwidget.cpp @@ -0,0 +1,496 @@ +#include "gnssposwidget.h" +#include "ui_gnssposwidget.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#define _USE_MATH_DEFINES +#include + +using namespace std; + +namespace Detail { +double constexpr sqrtNewtonRaphson(double x, double curr, double prev) +{ + return curr == prev + ? curr + : sqrtNewtonRaphson(x, 0.5 * (curr + x / curr), curr); +} +double constexpr sqrt(double x) +{ + return x >= 0 && x < std::numeric_limits::infinity() + ? Detail::sqrtNewtonRaphson(x, x, 0) + : std::numeric_limits::quiet_NaN(); +} +} +constexpr double pi() { return M_PI; } +constexpr double sqrt2() { return Detail::sqrt(2.); } + +const int MAX_SAT_TRACK_ENTRIES = 1000; + +static const QList GNSS_COLORS = { Qt::darkGreen, Qt::darkYellow, Qt::blue, Qt::magenta, Qt::gray, Qt::cyan, Qt::red, Qt::black }; + +int GnssPosWidget::alphaFromCnr(int cnr) +{ + int alpha = cnr * 255 / ui->cnrRangeSpinBox->value(); + if (alpha > 255) + alpha = 255; + return alpha; +} + +GnssPosWidget::GnssPosWidget(QWidget* parent) + : QWidget(parent) + , ui(new Ui::GnssPosWidget) +{ + ui->setupUi(this); + ui->satLabel->setText(QString::number(ui->satLabel->width()) + "x" + QString::number(ui->satLabel->height())); + connect(ui->receivedSatsCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); + connect(ui->satLabelsCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); + connect(ui->tracksCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); + this->setContextMenuPolicy(Qt::CustomContextMenu); + connect(this, SIGNAL(customContextMenuRequested(const QPoint&)), this, SLOT(popUpMenu(const QPoint&))); + connect(ui->cartPolarCheckBox, &QCheckBox::toggled, this, [this](bool /*checked*/) { resizeEvent(nullptr); }); + connect(ui->cnrRangeSpinBox, static_cast(&QSpinBox::valueChanged), this, [this](int) { replot(); }); +} + +GnssPosWidget::~GnssPosWidget() +{ + delete ui; +} + +void GnssPosWidget::resizeEvent(QResizeEvent* /*event*/) +{ + int w = ui->hostWidget->width(); + int h = ui->hostWidget->height(); + if (ui->cartPolarCheckBox->isChecked()) { + if (h < w) + w = h; + else + h = w; + } else { + // no constraints + } + w -= 10; + h -= 10; + if (w < 10) + w = 10; + if (h < 10) + h = 10; + ui->satLabel->resize(w, h); + + replot(); +} + +QPolygonF GnssPosWidget::getPolarUnitPolygon(const QPointF& pos, int controlPoints) +{ + const double step = 1. / (controlPoints + 1); + QPolygonF path; + QPointF p(pos + QPointF(-0.5, -0.5)); + for (int side = 0; side < 4; side++) { + for (int i = 0; i < controlPoints + 1; i++) { + QPointF incrPoint; + switch (side) { + case 0: + incrPoint = QPointF(step, 0.); + break; + case 1: + incrPoint = QPointF(0., step); + break; + case 2: + incrPoint = QPointF(-step, 0.); + break; + case 3: + incrPoint = QPointF(0., -step); + break; + default: + break; + } + p = p + incrPoint; + path.append(p); + } + } + return path; +} + +QPolygonF GnssPosWidget::getCartPolygonUnity(const QPointF& polarPos) +{ + QPolygonF polarRect = getPolarUnitPolygon(polarPos, DEFAULT_CONTROL_POINTS + qAbs(polarPos.y() / 10)); + QPolygonF cartPolygon; + for (QPointF p : polarRect) { + cartPolygon.append(polar2cartUnity(p)); + } + return cartPolygon; +} + +QPointF GnssPosWidget::polar2cartUnity(const QPointF& pol) +{ + if (pol.y() >= 90.) + return QPointF(0., 0.); + double magn = (90. - pol.y()) / 180.; + double xpos = magn * sin(pi() * pol.x() / 180.); + double ypos = -magn * cos(pi() * pol.x() / 180.); + return QPointF(xpos, ypos); +} + +void GnssPosWidget::drawPolarPixMap(QPixmap& pm) +{ + + QVector newlist; + QString str; + + const int satPosPixmapSize = pm.width(); + const QPointF originOffset(satPosPixmapSize / 2., satPosPixmapSize / 2.); + + pm.fill(Qt::white); + QPainter satPosPainter(&pm); + satPosPainter.setPen(QPen(Qt::black)); + satPosPainter.drawEllipse(QPoint(satPosPixmapSize / 2, satPosPixmapSize / 2), satPosPixmapSize / 6, satPosPixmapSize / 6); + satPosPainter.drawEllipse(QPoint(satPosPixmapSize / 2, satPosPixmapSize / 2), satPosPixmapSize / 3, satPosPixmapSize / 3); + satPosPainter.drawEllipse(QPoint(satPosPixmapSize / 2, satPosPixmapSize / 2), satPosPixmapSize / 2, satPosPixmapSize / 2); + satPosPainter.drawLine(QPoint(satPosPixmapSize / 2, 0), QPoint(satPosPixmapSize / 2, satPosPixmapSize)); + satPosPainter.drawLine(QPoint(0, satPosPixmapSize / 2), QPoint(satPosPixmapSize, satPosPixmapSize / 2)); + satPosPainter.drawText(satPosPixmapSize / 2 + 2, 3, 18, 18, Qt::AlignHCenter, "N"); + satPosPainter.drawText(satPosPixmapSize / 2 + 2, satPosPixmapSize - 19, 18, 18, Qt::AlignHCenter, "S"); + satPosPainter.drawText(4, satPosPixmapSize / 2 - 19, 18, 18, Qt::AlignHCenter, "W"); + satPosPainter.drawText(satPosPixmapSize - 19, satPosPixmapSize / 2 - 19, 18, 18, Qt::AlignHCenter, "E"); + + QFont font = satPosPainter.font(); + font.setPointSize(font.pointSize() - 2); + satPosPainter.setFont(font); + satPosPainter.drawText(satPosPixmapSize / 2 - 14, satPosPixmapSize - 12, 18, 18, Qt::AlignHCenter, "0°"); + satPosPainter.drawText(satPosPixmapSize / 2 - 16, satPosPixmapSize * 5 / 6 - 12, 18, 18, Qt::AlignHCenter, "30°"); + satPosPainter.drawText(satPosPixmapSize / 2 - 16, satPosPixmapSize * 2 / 3 - 12, 18, 18, Qt::AlignHCenter, "60°"); + + // set up coordinate transformation + QTransform trafo; + trafo.translate(originOffset.x(), originOffset.y()); + trafo.scale(satPosPixmapSize, satPosPixmapSize); + satPosPainter.setTransform(trafo); + + // draw the sat tracks first + if (ui->tracksCheckBox->isChecked()) { + for (const auto& pointMap : satTracks) { + for (const QVector& pointVector : pointMap) { + if (pointVector.size() == 0) + continue; + double cnr = 0.; + SatHistoryPoint satPoint; + for (int i = 0; i < pointVector.size(); i++) { + satPoint = pointVector[i]; + cnr += satPoint.cnr; + } + satPoint = pointVector.front(); + cnr /= (double)pointVector.size(); + QColor satColor = GNSS_COLORS[satPoint.gnssId]; + satColor.setAlpha(alphaFromCnr(cnr)); + satPosPainter.setPen(QColor("transparent")); + satPosPainter.setBrush(satColor); + QPainterPath path; + path.addPolygon(getCartPolygonUnity(satPoint.posPolar)); + satPosPainter.drawPolygon(path.toFillPolygon(QTransform())); + } + } + } + + // draw the current sat positions now + for (int i = 0; i < fCurrentSatlist.size(); i++) { + if (ui->receivedSatsCheckBox->isChecked()) { + if (fCurrentSatlist[i].fCnr > 0) + newlist.push_back(fCurrentSatlist[i]); + } else + newlist.push_back(fCurrentSatlist[i]); + if (fCurrentSatlist[i].fElev <= 90. && fCurrentSatlist[i].fElev >= -90.) { + if (ui->receivedSatsCheckBox->isChecked() && fCurrentSatlist[i].fCnr == 0) + continue; + QPointF currPos(fCurrentSatlist[i].fAzim, fCurrentSatlist[i].fElev); + QPointF currPoint = polar2cartUnity(currPos); + + QColor satColor = Qt::white; + QColor fillColor = Qt::white; + satColor = GNSS_COLORS[fCurrentSatlist[i].fGnssId]; + satPosPainter.setPen(satColor); + fillColor = satColor; + int alpha = alphaFromCnr(fCurrentSatlist[i].fCnr); + fillColor.setAlpha(alpha); + int satId = fCurrentSatlist[i].fGnssId * 1000 + fCurrentSatlist[i].fSatId; + if (fCurrentSatlist[i].fCnr > 0) { + SatHistoryPoint p; + p.posCart = currPoint; + p.color = fillColor; + p.posPolar = QPoint(currPos.x(), currPos.y()); + p.gnssId = fCurrentSatlist[i].fGnssId; + p.satId = fCurrentSatlist[i].fSatId; + p.cnr = fCurrentSatlist[i].fCnr; + p.time = QDateTime::currentDateTimeUtc(); + satTracks[satId][p.posPolar].push_back(p); + if (satTracks[satId][p.posPolar].size() > MAX_SAT_TRACK_ENTRIES) + satTracks[satId][p.posPolar].pop_front(); + } + satPosPainter.setPen(satColor); + satPosPainter.setBrush(fillColor); + + // somehow, drawEllipse doesn't work with a painter when a transform is set before (bug?) + // so reset the transform of the painter and do the scaling and shifting manually + satPosPainter.setTransform(QTransform()); + currPoint *= satPosPixmapSize; + currPoint += originOffset; + + float satsize = ui->satSizeSpinBox->value(); + satPosPainter.drawEllipse(currPoint, satsize / 2., satsize / 2.); + if (fCurrentSatlist[i].fUsed) + satPosPainter.drawEllipse(currPoint, 1.05 * satsize / 2., 1.05 * satsize / 2.); + currPoint.rx() += satsize / 2 + 4; + if (ui->satLabelsCheckBox->isChecked()) + satPosPainter.drawText(currPoint, QString::number(fCurrentSatlist[i].fSatId)); + } + } +} + +void GnssPosWidget::drawCartesianPixMap(QPixmap& pm) +{ + + QVector newlist; + QString str; + + const QPointF originOffset(0., pm.height() * 0.9); + + pm.fill(Qt::white); + QPainter satPosPainter(&pm); + satPosPainter.setPen(QPen(Qt::black)); + satPosPainter.drawLine(originOffset, originOffset + QPointF(pm.width(), 0)); + satPosPainter.drawLine(0.33 * originOffset, 0.33 * originOffset + QPointF(pm.width(), 0)); + satPosPainter.drawLine(0.67 * originOffset, 0.67 * originOffset + QPointF(pm.width(), 0)); + satPosPainter.drawLine(QPoint(pm.width() / 2, 0), originOffset + QPointF(pm.width() / 2, 0)); + + satPosPainter.drawText(pm.width() / 2 - 3, originOffset.y() + 6, 18, 18, Qt::AlignHCenter, "S"); + satPosPainter.drawText(2, originOffset.y() + 6, 18, 18, Qt::AlignHCenter, "N"); + satPosPainter.drawText(pm.width() - 18, originOffset.y() + 6, 18, 18, Qt::AlignHCenter, "N"); + satPosPainter.drawText(pm.width() / 4 - 3, originOffset.y() + 6, 18, 18, Qt::AlignHCenter, "E"); + satPosPainter.drawText(3 * pm.width() / 4 - 3, originOffset.y() + 6, 18, 18, Qt::AlignHCenter, "W"); + + QFont font = satPosPainter.font(); + font.setPointSize(font.pointSize() - 2); + satPosPainter.setFont(font); + satPosPainter.drawText(pm.width() / 2, originOffset.y() - 10, 18, 18, Qt::AlignHCenter, "0°"); + satPosPainter.drawText(pm.width() / 2, 0.33 * originOffset.y() + 3, 18, 18, Qt::AlignHCenter, "60°"); + satPosPainter.drawText(pm.width() / 2, 0.67 * originOffset.y() + 3, 18, 18, Qt::AlignHCenter, "30°"); + + // draw the sat tracks first + if (ui->tracksCheckBox->isChecked()) { + for (const auto& pointMap : satTracks) { + for (const QVector& pointVector : pointMap) { + if (pointVector.size() == 0) + continue; + double cnr = 0.; + SatHistoryPoint satPoint; + for (int i = 0; i < pointVector.size(); i++) { + satPoint = pointVector[i]; + cnr += satPoint.cnr; + } + satPoint = pointVector.front(); + cnr /= (double)pointVector.size(); + QColor satColor = GNSS_COLORS[satPoint.gnssId]; + satColor.setAlpha(alphaFromCnr(cnr)); + satPosPainter.setPen(QColor("transparent")); + satPosPainter.setBrush(satColor); + + QPainterPath path; + path.addPolygon(getPolarUnitPolygon(satPoint.posPolar)); + + QTransform trafo; + trafo.translate(0., 9 * pm.height() / 10.); + trafo.scale(pm.width() / 360., -9. * pm.height() / 900.); + satPosPainter.drawPolygon(path.toFillPolygon(trafo)); + } + } + } + + // draw the current sat positions now + for (int i = 0; i < fCurrentSatlist.size(); i++) { + if (ui->receivedSatsCheckBox->isChecked()) { + if (fCurrentSatlist[i].fCnr > 0) + newlist.push_back(fCurrentSatlist[i]); + } else + newlist.push_back(fCurrentSatlist[i]); + if (fCurrentSatlist[i].fElev <= 90. && fCurrentSatlist[i].fElev >= -90.) { + if (ui->receivedSatsCheckBox->isChecked() && fCurrentSatlist[i].fCnr == 0) + continue; + QPointF currPos(fCurrentSatlist[i].fAzim, fCurrentSatlist[i].fElev); + QPointF currPoint = polar2cartUnity(currPos); + + QColor satColor = Qt::white; + QColor fillColor = Qt::white; + satColor = GNSS_COLORS[fCurrentSatlist[i].fGnssId]; + satPosPainter.setPen(satColor); + fillColor = satColor; + int alpha = alphaFromCnr(fCurrentSatlist[i].fCnr); + fillColor.setAlpha(alpha); + int satId = fCurrentSatlist[i].fGnssId * 1000 + fCurrentSatlist[i].fSatId; + + if (fCurrentSatlist[i].fCnr > 0) { + SatHistoryPoint p; + p.posCart = currPoint; + p.color = fillColor; + p.posPolar = QPoint(currPos.x(), currPos.y()); + p.gnssId = fCurrentSatlist[i].fGnssId; + p.satId = fCurrentSatlist[i].fSatId; + p.cnr = fCurrentSatlist[i].fCnr; + p.time = QDateTime::currentDateTimeUtc(); + satTracks[satId][p.posPolar].push_back(p); + if (satTracks[satId][p.posPolar].size() > MAX_SAT_TRACK_ENTRIES) + satTracks[satId][p.posPolar].pop_front(); + } + satPosPainter.setPen(satColor); + satPosPainter.setBrush(fillColor); + + currPos = QPointF(currPos.x() / 360. * pm.width(), -currPos.y() / 90. * pm.height() * 0.9 + pm.height() * 0.9); + + float satsize = ui->satSizeSpinBox->value(); + satPosPainter.drawEllipse(currPos, satsize / 2., satsize / 2.); + if (fCurrentSatlist[i].fUsed) + satPosPainter.drawEllipse(currPos, satsize / 2. + 0.5, satsize / 2. + 0.5); + currPos.rx() += satsize / 2 + 4; + if (ui->satLabelsCheckBox->isChecked()) + satPosPainter.drawText(currPos, QString::number(fCurrentSatlist[i].fSatId)); + } + } +} + +void GnssPosWidget::replot() +{ + + const int w = ui->satLabel->width(); + const int h = ui->satLabel->height(); + + QPixmap satPosPixmap(w, h); + if (ui->cartPolarCheckBox->isChecked()) { + drawPolarPixMap(satPosPixmap); + } else { + drawCartesianPixMap(satPosPixmap); + } + + ui->satLabel->setPixmap(satPosPixmap); +} + +void GnssPosWidget::onSatsReceived(const QVector& satlist) +{ + fCurrentSatlist = satlist; + replot(); +} + +void GnssPosWidget::on_satSizeSpinBox_valueChanged(int /*arg1*/) +{ + replot(); +} + +void GnssPosWidget::onUiEnabledStateChange(bool connected) +{ + if (!connected) { + QVector emptylist; + fCurrentSatlist.clear(); + } + this->setEnabled(connected); +} + +void GnssPosWidget::popUpMenu(const QPoint& pos) +{ + QMenu contextMenu(tr("Context menu"), this); + + QAction action2("&Clear Tracks", this); + connect(&action2, &QAction::triggered, this, [this](bool /*checked*/) { satTracks.clear() ; this->replot(); }); + contextMenu.addAction(&action2); + + contextMenu.addSeparator(); + + QAction action3("&Export", this); + connect(&action3, &QAction::triggered, this, &GnssPosWidget::exportToFile); + contextMenu.addAction(&action3); + + contextMenu.exec(mapToGlobal(pos)); +} + +void GnssPosWidget::exportToFile() +{ + const int pixmapSize = 512; + QPixmap satPosPixmap; + if (ui->cartPolarCheckBox->isChecked()) { + satPosPixmap = QPixmap(pixmapSize, pixmapSize); + drawPolarPixMap(satPosPixmap); + } else { + satPosPixmap = QPixmap(sqrt2() * pixmapSize, pixmapSize); + drawCartesianPixMap(satPosPixmap); + } + + QString types("JPEG file (*.jpeg);;" // Set up the possible graphics formats + "Portable Network Graphics file (*.png);;" + "Bitmap file (*.bmp);;" + "ASCII raw data (*.txt)"); + QString filter; // Type of filter + QString jpegExt = ".jpeg", pngExt = ".png", tifExt = ".tif", bmpExt = ".bmp", tif2Ext = "tiff"; // Suffix for the files + QString txtExt = ".txt"; + QString suggestedName = ""; + QString fn = QFileDialog::getSaveFileName(this, tr("Export Pixmap"), + suggestedName, types, &filter); + + if (!fn.isEmpty()) { // If filename is not null + if (fn.contains(jpegExt)) { // Remove file extension if already there + fn.remove(jpegExt); + } else if (fn.contains(pngExt)) { + fn.remove(pngExt); + } else if (fn.contains(bmpExt)) { + fn.remove(bmpExt); + } else if (fn.contains(txtExt)) { + fn.remove(txtExt); + } + + if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save + fn += jpegExt; + satPosPixmap.save(fn, "JPEG"); + } else if (filter.contains(pngExt)) { // OR, Test to see if png and save + fn += pngExt; + satPosPixmap.save(fn, "PNG"); + } else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save + fn += bmpExt; + satPosPixmap.save(fn, "BMP"); + } else if (filter.contains(txtExt)) { + fn += txtExt; + // export sat history in asci raw data format + QFile file(fn); + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) + return; + QTextStream out(&file); + out << "# GNSS sat history from xxx to yyy\n"; + out << "# datetime marks the entrance time into space point (az,el)\n"; + out << "# \n"; + + for (const auto& pointMap : satTracks) { + for (const QVector& pointVector : pointMap) { + if (pointVector.size() == 0) + continue; + double cnr = 0.; + SatHistoryPoint p; + for (int i = 0; i < pointVector.size(); i++) { + p = pointVector[i]; + cnr += p.cnr; + } + p = pointVector.front(); + cnr /= (double)pointVector.size(); + out << p.time.toString(Qt::ISODate) << " " + << p.gnssId << " " + << GNSS_ID_STRING[p.gnssId] << " " + << p.satId << " " + << p.posPolar.x() << " " + << p.posPolar.y() << " " + << cnr << "\n"; + } + } + } + } +} diff --git a/source/gui/src/gnssposwidget.ui b/gui/src/gnssposwidget.ui similarity index 100% rename from source/gui/src/gnssposwidget.ui rename to gui/src/gnssposwidget.ui diff --git a/gui/src/gpssatsform.cpp b/gui/src/gpssatsform.cpp new file mode 100644 index 00000000..31291037 --- /dev/null +++ b/gui/src/gpssatsform.cpp @@ -0,0 +1,308 @@ +#include "gpssatsform.h" +#include "ui_gpssatsform.h" +#include +#include +#include +#include + +const int MAX_IQTRACK_BUFFER = 250; + +// helper function to format human readable numbers with common suffixes (k(ilo), M(ega), m(illi) etc.) +QString printReadableFloat(double value, int prec = 2, int lowOrderInhibit = -12, int highOrderInhibit = 9) +{ + QString str = ""; + QString suffix = ""; + double order = std::log10(std::fabs(value)); + if (order >= lowOrderInhibit && order <= highOrderInhibit) { + if (order >= 9) { + value *= 1e-9; + suffix = "G"; + } else if (order >= 6) { + value *= 1e-6; + suffix = "M"; + } else if (order >= 3) { + value *= 1e-3; + suffix = "k"; + } else if (order >= 0) { + suffix = ""; + } else if (order >= -3) { + value *= 1000.; + suffix = "m"; + } else if (order >= -6) { + value *= 1e6; + suffix = "u"; + } else if (order >= -9) { + value *= 1e9; + suffix = "n"; + } else if (order >= -12) { + value *= 1e12; + suffix = "p"; + } + } + char fmtChar = 'f'; + double newOrder = std::log10(std::fabs(value)); + if (fabs(newOrder) >= 3.) { + fmtChar = 'g'; + } else { + prec = prec - (int)newOrder - 1; + } + if (prec < 0) + prec = 0; + return QString::number(value, fmtChar, prec) + " " + suffix; +} + +GpsSatsForm::GpsSatsForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::GpsSatsForm) +{ + ui->setupUi(this); + ui->satsTableWidget->resizeColumnsToContents(); +} + +GpsSatsForm::~GpsSatsForm() +{ + delete ui; +} + +void GpsSatsForm::onSatsReceived(const QVector& satlist) +{ + ui->gnssPosWidget->onSatsReceived(satlist); + + QVector newlist; + QString str; + QColor color; + + int nrGoodSats = 0; + for (auto it = satlist.begin(); it != satlist.end(); it++) + if (it->fCnr > 0) + nrGoodSats++; + + ui->nrSatsLabel->setText(QString::number(nrGoodSats) + "/" + QString::number(satlist.size())); + + for (int i = 0; i < satlist.size(); i++) { + if (ui->visibleSatsCheckBox->isChecked()) { + if (satlist[i].fCnr > 0) + newlist.push_back(satlist[i]); + } else + newlist.push_back(satlist[i]); + } + + int N = newlist.size(); + ui->satsTableWidget->setRowCount(N); + for (int i = 0; i < N; i++) { + QTableWidgetItem* newItem1 = new QTableWidgetItem(QString::number(newlist[i].fSatId)); + newItem1->setSizeHint(QSize(25, 24)); + ui->satsTableWidget->setItem(i, 0, newItem1); + QTableWidgetItem* newItem2 = new QTableWidgetItem(GNSS_ID_STRING[newlist[i].fGnssId]); + newItem2->setSizeHint(QSize(50, 24)); + ui->satsTableWidget->setItem(i, 1, newItem2); + QTableWidgetItem* newItem3 = new QTableWidgetItem(QString::number(newlist[i].fCnr)); + newItem3->setSizeHint(QSize(70, 24)); + ui->satsTableWidget->setItem(i, 2, newItem3); + QTableWidgetItem* newItem4 = new QTableWidgetItem(QString::number(newlist[i].fAzim)); + newItem4->setSizeHint(QSize(100, 24)); + ui->satsTableWidget->setItem(i, 3, newItem4); + QTableWidgetItem* newItem5 = new QTableWidgetItem(QString::number(newlist[i].fElev)); + newItem5->setSizeHint(QSize(100, 24)); + ui->satsTableWidget->setItem(i, 4, newItem5); + QTableWidgetItem* newItem6 = new QTableWidgetItem(printReadableFloat(newlist[i].fPrRes, 2, 0)); + newItem6->setSizeHint(QSize(60, 24)); + ui->satsTableWidget->setItem(i, 5, newItem6); + QTableWidgetItem* newItem7 = new QTableWidgetItem(QString::number(newlist[i].fQuality)); + color = Qt::green; + float transp = 0.166 * (newlist[i].fQuality - 1); + if (transp < 0.) + transp = 0.; + if (transp > 1.) + transp = 1.; + color.setAlphaF(transp); + newItem7->setBackground(color); + + newItem7->setSizeHint(QSize(25, 24)); + ui->satsTableWidget->setItem(i, 6, newItem7); + str = "n/a"; + if (newlist[i].fHealth < GNSS_HEALTH_STRINGS.size()) + str = GNSS_HEALTH_STRINGS[newlist[i].fHealth]; + if (newlist[i].fHealth == 0) { + color = Qt::lightGray; + } else if (newlist[i].fHealth == 1) { + color = Qt::green; + } else if (newlist[i].fHealth >= 2) { + color = Qt::red; + } + QTableWidgetItem* newItem8 = new QTableWidgetItem(str); + newItem8->setSizeHint(QSize(25, 24)); + ui->satsTableWidget->setItem(i, 7, newItem8); + int orbSrc = newlist[i].fOrbitSource; + if (orbSrc < 0) + orbSrc = 0; + if (orbSrc > 7) + orbSrc = 7; + QTableWidgetItem* newItem9 = new QTableWidgetItem(GNSS_ORBIT_SRC_STRING[orbSrc]); + newItem9->setSizeHint(QSize(50, 24)); + ui->satsTableWidget->setItem(i, 8, newItem9); + QTableWidgetItem* newItem10 = new QTableWidgetItem(); + newItem10->setCheckState(Qt::CheckState::Unchecked); + if (newlist[i].fUsed) + newItem10->setCheckState(Qt::CheckState::Checked); + newItem10->setFlags(newItem10->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user + newItem10->setFlags(newItem10->flags() & (~Qt::ItemIsEditable)); + newItem10->setSizeHint(QSize(20, 24)); + ui->satsTableWidget->setItem(i, 9, newItem10); + QTableWidgetItem* newItem11 = new QTableWidgetItem(); + newItem11->setCheckState(Qt::CheckState::Unchecked); + if (newlist[i].fDiffCorr) + newItem11->setCheckState(Qt::CheckState::Checked); + newItem11->setFlags(newItem11->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user + newItem11->setFlags(newItem11->flags() & (~Qt::ItemIsEditable)); + newItem11->setSizeHint(QSize(20, 24)); + ui->satsTableWidget->setItem(i, 10, newItem11); + } +} + +void GpsSatsForm::onTimeAccReceived(quint32 acc) +{ + double tAcc = acc * 1e-9; + ui->timePrecisionLabel->setText(printReadableFloat(tAcc) + "s"); +} + +void GpsSatsForm::onFreqAccReceived(quint32 acc) +{ + double fAcc = acc * 1e-12; + ui->freqPrecisionLabel->setText(printReadableFloat(fAcc) + "s/s"); +} + +void GpsSatsForm::onIntCounterReceived(quint32 cnt) +{ + ui->intCounterLabel->setText(QString::number(cnt)); +} + +void GpsSatsForm::onGpsMonHWReceived(const GnssMonHwStruct& hwstruct) +{ + ui->lnaNoiseLabel->setText(QString::number(-hwstruct.noise) + " dBHz"); + ui->lnaAgcLabel->setText(QString::number(hwstruct.agc)); + QString str = "n/a"; + if (hwstruct.antStatus < GNSS_ANT_STATUS_STRINGS.size()) + str = GNSS_ANT_STATUS_STRINGS[hwstruct.antStatus]; + switch (hwstruct.antStatus) { + case 0: + ui->antStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); + break; + case 2: + ui->antStatusLabel->setStyleSheet("QLabel { background-color : Window }"); + break; + case 3: + ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); + break; + case 4: + ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); + break; + case 1: + default: + ui->antStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); + } + ui->antStatusLabel->setText(str); + switch (hwstruct.antPower) { + case 0: + str = "off"; + break; + case 1: + str = "on"; + break; + case 2: + default: + str = "unknown"; + } + ui->antPowerLabel->setText(str); + ui->jammingProgressBar->setValue(hwstruct.jamInd / 2.55); +} + +void GpsSatsForm::onGpsMonHW2Received(const GnssMonHw2Struct& hw2struct) +{ + const int iqPixmapSize = 65; + QPixmap iqPixmap(iqPixmapSize, iqPixmapSize); + iqPixmap.fill(Qt::white); + QPainter iqPainter(&iqPixmap); + iqPainter.setPen(QPen(Qt::black)); + iqPainter.drawLine(QPoint(iqPixmapSize / 2, 0), QPoint(iqPixmapSize / 2, iqPixmapSize)); + iqPainter.drawLine(QPoint(0, iqPixmapSize / 2), QPoint(iqPixmapSize, iqPixmapSize / 2)); + QColor col(Qt::blue); + iqPainter.setPen(col); + double x = 0., y = 0.; + for (int i = 0; i < iqTrack.size(); i++) { + iqPainter.drawPoint(iqTrack[i]); + } + x = hw2struct.ofsI * iqPixmapSize / (2 * 127) + iqPixmapSize / 2.; + y = -hw2struct.ofsQ * iqPixmapSize / (2 * 127) + iqPixmapSize / 2.; + col.setAlpha(100); + iqPainter.setBrush(col); + iqPainter.drawEllipse(QPointF(x, y), hw2struct.magI * iqPixmapSize / 512., hw2struct.magQ * iqPixmapSize / 512.); + ui->iqAlignmentLabel->setPixmap(iqPixmap); + iqTrack.push_back(QPointF(x, y)); + if (iqTrack.size() > MAX_IQTRACK_BUFFER) + iqTrack.pop_front(); +} + +void GpsSatsForm::onGpsVersionReceived(const QString& swString, const QString& hwString, const QString& protString) +{ + ui->ubxHwVersionLabel->setText(hwString); + ui->ubxSwVersionLabel->setText(swString); + ui->UBXprotLabel->setText(protString); +} + +void GpsSatsForm::onGpsFixReceived(quint8 val) +{ + QString fixType = "N/A"; + if (val < FIX_TYPE_STRINGS.size()) + fixType = FIX_TYPE_STRINGS[val]; + if (val < 2) + ui->fixTypeLabel->setStyleSheet("QLabel { background-color : red }"); + else if (val == 2) + ui->fixTypeLabel->setStyleSheet("QLabel { background-color : lightgreen }"); + else if (val > 2) + ui->fixTypeLabel->setStyleSheet("QLabel { background-color : green }"); + else + ui->fixTypeLabel->setStyleSheet("QLabel { background-color : Window }"); + ui->fixTypeLabel->setText(fixType); +} + +void GpsSatsForm::onGeodeticPosReceived(const GeodeticPos& pos) +{ + + QString str; + str = printReadableFloat(pos.hAcc / 1000., 2, 4) + "m / " + printReadableFloat(pos.vAcc / 1000., 2, 4) + "m"; + ui->xyzResLabel->setText(str); +} + +void GpsSatsForm::onUiEnabledStateChange(bool connected) +{ + if (!connected) { + QVector emptylist; + onSatsReceived(emptylist); + iqTrack.clear(); + onGpsMonHW2Received(GnssMonHw2Struct()); + ui->jammingProgressBar->setValue(0); + ui->timePrecisionLabel->setText("N/A"); + ui->freqPrecisionLabel->setText("N/A"); + ui->intCounterLabel->setText("N/A"); + ui->lnaNoiseLabel->setText("N/A"); + ui->lnaAgcLabel->setText("N/A"); + ui->antStatusLabel->setText("N/A"); + ui->antPowerLabel->setText("N/A"); + ui->fixTypeLabel->setText("N/A"); + ui->fixTypeLabel->setStyleSheet("QLabel { background-color : Window }"); + ui->xyzResLabel->setText("N/A"); + ui->ubxHwVersionLabel->setText("N/A"); + ui->ubxSwVersionLabel->setText("N/A"); + ui->UBXprotLabel->setText("N/A"); + ui->ubxUptimeLabel->setText("N/A"); + } + ui->jammingProgressBar->setEnabled(connected); + iqTrack.clear(); + this->setEnabled(connected); +} + +void GpsSatsForm::onUbxUptimeReceived(quint32 val) +{ + ui->ubxUptimeLabel->setText(" " + QString::number(val / 3600., 'f', 2) + " h "); +} diff --git a/source/gui/src/gpssatsform.ui b/gui/src/gpssatsform.ui similarity index 100% rename from source/gui/src/gpssatsform.ui rename to gui/src/gpssatsform.ui diff --git a/source/gui/src/histogramdataform.cpp b/gui/src/histogramdataform.cpp similarity index 57% rename from source/gui/src/histogramdataform.cpp rename to gui/src/histogramdataform.cpp index 39de9eb6..a838f4ac 100644 --- a/source/gui/src/histogramdataform.cpp +++ b/gui/src/histogramdataform.cpp @@ -2,21 +2,13 @@ #include "ui_histogramdataform.h" #include -histogramDataForm::histogramDataForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::histogramDataForm) +histogramDataForm::histogramDataForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::histogramDataForm) { ui->setupUi(this); - connect(ui->histoWidget, &CustomHistogram::histogramCleared, [this](const QString histogramName){ + connect(ui->histoWidget, &CustomHistogram::histogramCleared, [this](const QString histogramName) { emit histogramCleared(histogramName); -/* - auto it = fHistoMap.find(histogramName); - if (it!=fHistoMap.end()) { - it->clear(); - this->updateHistoTable(); - } -*/ -// qDebug()<<"sent signal histogramDataForm::histogramCleared("<nrHistosLabel->setText(QString::number(fHistoMap.size())); -/* - ui->histoWidget->setTitle(name); - ui->histoWidget->setData(fHistoMap.first()); -*/ } void histogramDataForm::updateHistoTable() { ui->tableWidget->setRowCount(fHistoMap.size()); - int i=0; - for (auto it=fHistoMap.begin(); it!=fHistoMap.end(); it++) - { - QTableWidgetItem *newItem1 = new QTableWidgetItem(it.key()); - newItem1->setSizeHint(QSize(120,24)); + int i = 0; + for (auto it = fHistoMap.begin(); it != fHistoMap.end(); it++) { + QTableWidgetItem* newItem1 = new QTableWidgetItem(it.key()); + newItem1->setSizeHint(QSize(120, 24)); ui->tableWidget->setItem(i, 0, newItem1); - QTableWidgetItem *newItem2 = new QTableWidgetItem(QString::number(it.value().getEntries())); - newItem2->setSizeHint(QSize(100,24)); + QTableWidgetItem* newItem2 = new QTableWidgetItem(QString::number(it.value().getEntries())); + newItem2->setSizeHint(QSize(100, 24)); ui->tableWidget->setItem(i, 1, newItem2); i++; } if (fCurrentHisto.size()) { - for (int j=0; itableWidget->rowCount(); j++) { - if (ui->tableWidget->item(j,0)->text()==fCurrentHisto) { - on_tableWidget_cellClicked(j,0); + for (int j = 0; i < ui->tableWidget->rowCount(); j++) { + if (ui->tableWidget->item(j, 0)->text() == fCurrentHisto) { + on_tableWidget_cellClicked(j, 0); } } } @@ -65,11 +49,10 @@ void histogramDataForm::updateHistoTable() void histogramDataForm::on_tableWidget_cellClicked(int row, int /*column*/) { - QString name = ui->tableWidget->item(row,0)->text(); -// ui->nrHistosLabel->setText(name); + QString name = ui->tableWidget->item(row, 0)->text(); auto it = fHistoMap.find(name); - if (it!=fHistoMap.end()) { - fCurrentHisto=name; + if (it != fHistoMap.end()) { + fCurrentHisto = name; ui->histoWidget->setTitle(name); ui->histoWidget->setData(*it); ui->histoWidget->setAxisTitle(QwtPlot::xBottom, QString::fromStdString(it->getUnit())); @@ -81,8 +64,8 @@ void histogramDataForm::on_tableWidget_cellClicked(int row, int /*column*/) ui->maxLabel->setText(QString::number(it->getMax())); ui->underflowLabel->setText(QString::number(it->getUnderflow())); ui->overflowLabel->setText(QString::number(it->getOverflow())); - ui->meanLabel->setText(QString::number(it->getMean())+QString::fromStdString(it->getUnit())); - ui->rmsLabel->setText(QString::number(it->getRMS(),'g',4)+QString::fromStdString(it->getUnit())); + ui->meanLabel->setText(QString::number(it->getMean()) + QString::fromStdString(it->getUnit())); + ui->rmsLabel->setText(QString::number(it->getRMS(), 'g', 4) + QString::fromStdString(it->getUnit())); } } @@ -102,7 +85,7 @@ void histogramDataForm::onUiEnabledStateChange(bool connected) ui->rmsLabel->setText("N/A"); ui->nrHistosLabel->setText(QString::number(0)); fHistoMap.clear(); - fCurrentHisto=""; + fCurrentHisto = ""; } this->setEnabled(connected); ui->histoWidget->setEnabled(connected); diff --git a/source/gui/src/histogramdataform.ui b/gui/src/histogramdataform.ui similarity index 100% rename from source/gui/src/histogramdataform.ui rename to gui/src/histogramdataform.ui diff --git a/gui/src/i2cform.cpp b/gui/src/i2cform.cpp new file mode 100644 index 00000000..bdfd1a0b --- /dev/null +++ b/gui/src/i2cform.cpp @@ -0,0 +1,91 @@ +#include +#include +#include + +I2cForm::I2cForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::I2cForm) +{ + ui->setupUi(this); +} + +I2cForm::~I2cForm() +{ + delete ui; +} + +void I2cForm::onI2cStatsReceived(quint32 bytesRead, quint32 bytesWritten, const QVector& deviceList) +{ + ui->nrDevicesLabel->setText("Nr. of devices: " + QString::number(deviceList.size())); + ui->bytesReadLabel->setText("total bytes read: " + QString::number(bytesRead)); + ui->bytesWrittenLabel->setText("total bytes written: " + QString::number(bytesWritten)); + + ui->devicesTableWidget->setRowCount(deviceList.size()); + for (int i = 0; i < deviceList.size(); i++) { + QTableWidgetItem* newItem1 = new QTableWidgetItem("0x" + QString("%1").arg(deviceList[i].address, 2, 16, QChar('0'))); + newItem1->setSizeHint(QSize(120, 24)); + newItem1->setTextAlignment(Qt::AlignCenter); + ui->devicesTableWidget->setItem(i, 0, newItem1); + + QTableWidgetItem* newItem2 = new QTableWidgetItem(deviceList[i].name); + newItem2->setSizeHint(QSize(200, 24)); + newItem2->setTextAlignment(Qt::AlignCenter); + ui->devicesTableWidget->setItem(i, 1, newItem2); + + uint8_t status = deviceList[i].status; + QString str; + QBrush brush = QBrush(Qt::green, Qt::SolidPattern); + if (status == 0) { + str = "unknown"; + brush = QBrush(Qt::lightGray, Qt::SolidPattern); + } + if (status & 0x04) { + str = "missing"; + brush = QBrush(Qt::red, Qt::SolidPattern); + } else { + if (status & 0x01) { + str = "online"; + brush = QBrush(Qt::green, Qt::SolidPattern); + } + if (status & 0x02) { + str = "system"; + brush = QBrush(Qt::blue, Qt::SolidPattern); + } + } + if (status & 0x08) { + str = "bus error"; + brush = QBrush(Qt::red, Qt::SolidPattern); + } + if (status & 0x10) { + str = "locked"; + brush = QBrush(Qt::darkGray, Qt::SolidPattern); + } + + QTableWidgetItem* newItem3 = new QTableWidgetItem(str); + newItem3->setBackground(brush); + newItem3->setSizeHint(QSize(140, 24)); + newItem3->setTextAlignment(Qt::AlignCenter); + ui->devicesTableWidget->setItem(i, 2, newItem3); + } +} + +void I2cForm::onUiEnabledStateChange(bool connected) +{ + if (!connected) { + ui->nrDevicesLabel->setText("Nr. of devices: "); + ui->bytesReadLabel->setText("total bytes read: "); + ui->bytesWrittenLabel->setText("total bytes written: "); + ui->devicesTableWidget->setRowCount(0); + } + this->setEnabled(connected); +} + +void I2cForm::on_statsQueryPushButton_clicked() +{ + emit i2cStatsRequest(); +} + +void I2cForm::on_scanBusPushButton_clicked() +{ + emit scanI2cBusRequest(); +} diff --git a/source/gui/src/i2cform.ui b/gui/src/i2cform.ui similarity index 100% rename from source/gui/src/i2cform.ui rename to gui/src/i2cform.ui diff --git a/source/gui/src/logplotswidget.cpp b/gui/src/logplotswidget.cpp similarity index 70% rename from source/gui/src/logplotswidget.cpp rename to gui/src/logplotswidget.cpp index 310de986..c492a405 100644 --- a/source/gui/src/logplotswidget.cpp +++ b/gui/src/logplotswidget.cpp @@ -1,26 +1,23 @@ #include "logplotswidget.h" #include "ui_logplotswidget.h" #include -#include +#include #include #include -#include - +#include -LogPlotsWidget::LogPlotsWidget(QWidget *parent) : - QWidget(parent), - ui(new Ui::LogPlotsWidget) +LogPlotsWidget::LogPlotsWidget(QWidget* parent) + : QWidget(parent) + , ui(new Ui::LogPlotsWidget) { ui->setupUi(this); - //ui->logPlot->setTitle("temp"); ui->logPlot->setAxisScaleDraw(QwtPlot::xBottom, new QwtDateScaleDraw()); ui->logPlot->setAxisScaleEngine(QwtPlot::xBottom, new QwtDateScaleEngine()); - ui->logPlot->setAxisTitle(QwtPlot::xBottom,"time"); - //ui->logPlot->setAxisTitle(QwtPlot::yLeft,"temp / °C"); - connect(ui->logPlot, &CustomPlot::scalingChanged,this, &LogPlotsWidget::onScalingChanged); + ui->logPlot->setAxisTitle(QwtPlot::xBottom, "time"); + connect(ui->logPlot, &CustomPlot::scalingChanged, this, &LogPlotsWidget::onScalingChanged); ui->logPlot->addCurve("curve1", Qt::blue); ui->logPlot->curve("curve1").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); + QwtSymbol* sym = new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern), QPen(Qt::black), QSize(5, 5)); ui->logPlot->curve("curve1").setSymbol(sym); ui->logPlot->setAxisAutoScale(QwtPlot::xBottom, true); ui->logPlot->setAxisAutoScale(QwtPlot::yLeft, true); @@ -28,7 +25,6 @@ LogPlotsWidget::LogPlotsWidget(QWidget *parent) : ui->logPlot->setMinimumHeight(100); ui->logPlot->replot(); - } LogPlotsWidget::~LogPlotsWidget() @@ -39,7 +35,7 @@ LogPlotsWidget::~LogPlotsWidget() void LogPlotsWidget::onTemperatureReceived(float temp) { auto it = fLogMap.find("Temperature"); - if (it==fLogMap.end()) { + if (it == fLogMap.end()) { fLogMap["Temperature"].setName("Temperature"); fLogMap["Temperature"].setUnit("°C"); } @@ -53,7 +49,7 @@ void LogPlotsWidget::onTemperatureReceived(float temp) void LogPlotsWidget::onTimeAccReceived(quint32 acc) { auto it = fLogMap.find("Time Accuracy"); - if (it==fLogMap.end()) { + if (it == fLogMap.end()) { fLogMap["Time Accuracy"].setName("Time Accuracy"); fLogMap["Time Accuracy"].setUnit("ns"); } @@ -68,7 +64,7 @@ void LogPlotsWidget::onBiasVoltageCalculated(float ubias) { const QString name = "SiPM Bias Voltage"; auto it = fLogMap.find(name); - if (it==fLogMap.end()) { + if (it == fLogMap.end()) { fLogMap[name].setName(name); fLogMap[name].setUnit("V"); } @@ -83,7 +79,7 @@ void LogPlotsWidget::onBiasCurrentCalculated(float ibias) { const QString name = "SiPM Bias Current"; auto it = fLogMap.find(name); - if (it==fLogMap.end()) { + if (it == fLogMap.end()) { fLogMap[name].setName(name); fLogMap[name].setUnit("uA"); } @@ -94,50 +90,45 @@ void LogPlotsWidget::onBiasCurrentCalculated(float ibias) updateLogTable(); } - void LogPlotsWidget::updateLogTable() { ui->nrLogsLabel->setText(QString::number(fLogMap.size())); ui->tableWidget->setRowCount(fLogMap.size()); - int i=0; - for (auto it=fLogMap.begin(); it!=fLogMap.end(); it++) - { - QTableWidgetItem *newItem1 = new QTableWidgetItem(it.key()); - newItem1->setSizeHint(QSize(120,24)); + int i = 0; + for (auto it = fLogMap.begin(); it != fLogMap.end(); it++) { + QTableWidgetItem* newItem1 = new QTableWidgetItem(it.key()); + newItem1->setSizeHint(QSize(120, 24)); ui->tableWidget->setItem(i, 0, newItem1); - QTableWidgetItem *newItem2 = new QTableWidgetItem(QString::number(it.value().data().size())); - newItem2->setSizeHint(QSize(100,24)); + QTableWidgetItem* newItem2 = new QTableWidgetItem(QString::number(it.value().data().size())); + newItem2->setSizeHint(QSize(100, 24)); ui->tableWidget->setItem(i, 1, newItem2); i++; } if (fCurrentLog.size()) { - for (int j=0; itableWidget->rowCount(); j++) { - if (ui->tableWidget->item(j,0)->text()==fCurrentLog) { - on_tableWidget_cellClicked(j,0); + for (int j = 0; i < ui->tableWidget->rowCount(); j++) { + if (ui->tableWidget->item(j, 0)->text() == fCurrentLog) { + on_tableWidget_cellClicked(j, 0); } } } - } void LogPlotsWidget::on_tableWidget_cellClicked(int row, int /*column*/) { - QString name = ui->tableWidget->item(row,0)->text(); -// ui->nrHistosLabel->setText(name); + QString name = ui->tableWidget->item(row, 0)->text(); auto it = fLogMap.find(name); - if (it!=fLogMap.end()) { + if (it != fLogMap.end()) { ui->logPlot->setTitle(name); - //ui->histoWidget->setData(*it); ui->logPlot->curve("curve1").setSamples(it->data()); ui->logPlot->setAxisTitle(QwtPlot::xBottom, "time"); ui->logPlot->setAxisTitle(QwtPlot::yLeft, it->getUnit()); ui->logNameLabel->setText(it->getName()); - if (fCurrentLog==name) { + if (fCurrentLog == name) { ui->logPlot->setAxisAutoScale(QwtPlot::xBottom); ui->logPlot->setAxisAutoScale(QwtPlot::yLeft); } - fCurrentLog=name; + fCurrentLog = name; ui->logPlot->replot(); onScalingChanged(); } @@ -151,7 +142,7 @@ void LogPlotsWidget::onUiEnabledStateChange(bool connected) ui->logNameLabel->setText("N/A"); ui->nrLogsLabel->setText(QString::number(0)); fLogMap.clear(); - fCurrentLog=""; + fCurrentLog = ""; ui->logPlot->replot(); } else { ui->logPlot->curve("curve1").show(); @@ -170,28 +161,32 @@ void LogPlotsWidget::onScalingChanged() void LogPlotsWidget::on_linesCheckBox_clicked() { - if (ui->linesCheckBox->isChecked()) ui->logPlot->curve("curve1").setStyle(QwtPlotCurve::Lines); - else ui->logPlot->curve("curve1").setStyle(QwtPlotCurve::NoCurve); - ui->logPlot->replot(); + if (ui->linesCheckBox->isChecked()) + ui->logPlot->curve("curve1").setStyle(QwtPlotCurve::Lines); + else + ui->logPlot->curve("curve1").setStyle(QwtPlotCurve::NoCurve); + ui->logPlot->replot(); } void LogPlotsWidget::on_pointSizeSpinBox_valueChanged(int arg1) { - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(arg1,arg1)); + QwtSymbol* sym = new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern), QPen(Qt::black), QSize(arg1, arg1)); ui->logPlot->curve("curve1").setSymbol(sym); ui->logPlot->replot(); } -void LogPlotsWidget::onGpioRatesReceived(quint8 whichrate, QVector rates){ +void LogPlotsWidget::onGpioRatesReceived(quint8 whichrate, QVector rates) +{ QString name = "XOR Rate"; - if (whichrate==0){ + if (whichrate == 0) { name = "XOR Rate"; - } else if (whichrate==0){ + } else if (whichrate == 0) { name = "AND Rate"; - } else return; + } else + return; auto it = fLogMap.find(name); - if (it==fLogMap.end()) { + if (it == fLogMap.end()) { fLogMap[name].setName(name); fLogMap[name].setUnit("1/s"); } @@ -204,16 +199,15 @@ void LogPlotsWidget::onGpioRatesReceived(quint8 whichrate, QVector rate updateLogTable(); } -void LogPlotsWidget::onLogInfoReceived(const LogInfoStruct& lis) { +void LogPlotsWidget::onLogInfoReceived(const LogInfoStruct& lis) +{ ui->dataFileNameLineEdit->setText(lis.dataFileName); ui->logFileNameLineEdit->setText(lis.logFileName); - ui->dataSizeLabel->setText(QString::number(lis.dataFileSize/1024.,'f',2)+ " kiB"); - ui->logSizeLabel->setText(QString::number(lis.logFileSize/1024.,'f',2)+ " kiB"); - QString st="failed (0)"; - if (lis.status>0) st="ok ("+QString::number(lis.status)+")"; + ui->dataSizeLabel->setText(QString::number(lis.dataFileSize / 1024., 'f', 2) + " kiB"); + ui->logSizeLabel->setText(QString::number(lis.logFileSize / 1024., 'f', 2) + " kiB"); + QString st = "failed (0)"; + if (lis.status > 0) + st = "ok (" + QString::number(lis.status) + ")"; ui->logStatusLabel->setText(st); - ui->logAgeLabel->setText(QString::number(lis.logAge/3600.,'f',2)+" h"); + ui->logAgeLabel->setText(QString::number(lis.logAge / 3600., 'f', 2) + " h"); } - - - diff --git a/source/gui/src/logplotswidget.ui b/gui/src/logplotswidget.ui similarity index 100% rename from source/gui/src/logplotswidget.ui rename to gui/src/logplotswidget.ui diff --git a/source/gui/src/main.cpp b/gui/src/main.cpp similarity index 93% rename from source/gui/src/main.cpp rename to gui/src/main.cpp index a995f1d9..b2a75060 100644 --- a/source/gui/src/main.cpp +++ b/gui/src/main.cpp @@ -1,10 +1,10 @@ -#include #include #include +#include #include "config.h" -int main(int argc, char *argv[]) +int main(int argc, char* argv[]) { QApplication a(argc, argv); QCoreApplication::setApplicationName("muondetector-gui"); diff --git a/source/gui/src/mainwindow.cpp b/gui/src/mainwindow.cpp similarity index 65% rename from source/gui/src/mainwindow.cpp rename to gui/src/mainwindow.cpp index 247206af..764f896b 100644 --- a/source/gui/src/mainwindow.cpp +++ b/gui/src/mainwindow.cpp @@ -1,38 +1,35 @@ #include "mainwindow.h" -#include "ui_mainwindow.h" -#include "config.h" -#include "ublox_structs.h" -#include "settings.h" -#include "status.h" -#include "tcpmessage_keys.h" -#include "map.h" -#include "i2cform.h" #include "calibform.h" #include "calibscandialog.h" +#include "config.h" #include "gpssatsform.h" #include "histogram.h" #include "histogramdataform.h" +#include "i2cform.h" +#include "logplotswidget.h" +#include "map.h" #include "muondetector_structs.h" #include "parametermonitorform.h" -#include "logplotswidget.h" #include "scanform.h" +#include "settings.h" +#include "status.h" +#include "tcpmessage_keys.h" +#include "ublox_structs.h" +#include "ui_mainwindow.h" -#include -#include -#include #include #include +#include +#include +#include #include -//#include - using namespace std; - -MainWindow::MainWindow(QWidget *parent) : - QMainWindow(parent), - ui(new Ui::MainWindow) +MainWindow::MainWindow(QWidget* parent) + : QMainWindow(parent) + , ui(new Ui::MainWindow) { qRegisterMetaType("TcpMessage"); qRegisterMetaType("GeodeticPos"); @@ -53,15 +50,13 @@ MainWindow::MainWindow(QWidget *parent) : qRegisterMetaType>("std::vector"); qRegisterMetaType>("std::chrono::duration"); qRegisterMetaType("std::string"); -// qRegisterMetaType("LogParameter"); qRegisterMetaType("UbxDopStruct"); qRegisterMetaType("timespec"); + qRegisterMetaType("ADC_SAMPLING_MODE"); ui->setupUi(this); - this->setWindowTitle(QString("muondetector-gui "+QString::fromStdString(MuonPi::Version::software.string()))); + this->setWindowTitle(QString("muondetector-gui " + QString::fromStdString(MuonPi::Version::software.string()))); - ui->discr1Layout->setAlignment(ui->discr1Slider, Qt::AlignHCenter); - ui->discr2Layout->setAlignment(ui->discr2Slider, Qt::AlignHCenter); // aligns the slider in their vertical layout centered QIcon icon(":/res/muon.ico"); this->setWindowIcon(icon); setMaxThreshVoltage(1.0); @@ -70,14 +65,11 @@ MainWindow::MainWindow(QWidget *parent) : addresses = new QStandardItemModel(this); loadSettings(addresses); ui->ipBox->setModel(addresses); - ui->ipBox->setCompleter(new QCompleter{}); + ui->ipBox->setCompleter(new QCompleter {}); ui->ipBox->setEditable(true); - //ui->ipBox->installEventFilter(this); // setup colors - ui->ipStatusLabel->setStyleSheet("QLabel {color : darkGray;}");/* - ui->discr1Hit->setStyleSheet("QLabel {background-color : darkRed;}"); - ui->discr2Hit->setStyleSheet("QLabel {background-color : darkRed;}");*/ + ui->ipStatusLabel->setStyleSheet("QLabel {color : darkGray;}"); // setup event filter ui->ipBox->installEventFilter(this); @@ -99,7 +91,7 @@ MainWindow::MainWindow(QWidget *parent) : ui->XORHit->setFocusPolicy(Qt::NoFocus); // set timer for automatic rate poll - if (automaticRatePoll){ + if (automaticRatePoll) { ratePollTimer.setInterval(5000); ratePollTimer.setSingleShot(false); connect(&ratePollTimer, &QTimer::timeout, this, &MainWindow::sendRequestGpioRates); @@ -107,16 +99,13 @@ MainWindow::MainWindow(QWidget *parent) : ratePollTimer.start(); } - // set mainwindow - //connect(ui->saveDacButton, &QPushButton, this, &MainWindow::on_saveThresholdsButton_clicked); - // set all tabs ui->tabWidget->removeTab(0); - Status *status = new Status(this); + Status* status = new Status(this); connect(this, &MainWindow::setUiEnabledStates, status, &Status::onUiEnabledStateChange); connect(this, &MainWindow::gpioRates, status, &Status::onGpioRatesReceived); - connect(status, &Status::resetRateClicked, this, [this](){ this->sendRequest(TCP_MSG_KEY::MSG_GPIO_RATE_RESET); } ); + connect(status, &Status::resetRateClicked, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_GPIO_RATE_RESET); }); connect(this, &MainWindow::adcSampleReceived, status, &Status::onAdcSampleReceived); connect(this, &MainWindow::dacReadbackReceived, status, &Status::onDacReadbackReceived); connect(status, &Status::inputSwitchChanged, this, &MainWindow::sendInputSwitch); @@ -134,9 +123,9 @@ MainWindow::MainWindow(QWidget *parent) : connect(this, &MainWindow::timepulseReceived, status, &Status::onTimepulseReceived); connect(this, &MainWindow::mqttStatusChanged, status, &Status::onMqttStatusChanged); - ui->tabWidget->addTab(status,"Overview"); + ui->tabWidget->addTab(status, "Overview"); - Settings *settings = new Settings(this); + Settings* settings = new Settings(this); connect(this, &MainWindow::setUiEnabledStates, settings, &Settings::onUiEnabledStateChange); connect(this, &MainWindow::txBufReceived, settings, &Settings::onTxBufReceived); connect(this, &MainWindow::txBufPeakReceived, settings, &Settings::onTxBufPeakReceived); @@ -146,47 +135,45 @@ MainWindow::MainWindow(QWidget *parent) : connect(settings, &Settings::sendRequestUbxMsgRates, this, &MainWindow::sendRequestUbxMsgRates); connect(settings, &Settings::sendSetUbxMsgRateChanges, this, &MainWindow::sendSetUbxMsgRateChanges); connect(settings, &Settings::sendUbxReset, this, &MainWindow::onSendUbxReset); - connect(settings, &Settings::sendUbxConfigDefault, this, [this](){ this->sendRequest(TCP_MSG_KEY::MSG_UBX_CONFIG_DEFAULT); } ); + connect(settings, &Settings::sendUbxConfigDefault, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_UBX_CONFIG_DEFAULT); }); connect(this, &MainWindow::gnssConfigsReceived, settings, &Settings::onGnssConfigsReceived); connect(settings, &Settings::setGnssConfigs, this, &MainWindow::onSetGnssConfigs); connect(this, &MainWindow::gpsTP5Received, settings, &Settings::onTP5Received); connect(settings, &Settings::setTP5Config, this, &MainWindow::onSetTP5Config); - connect(settings, &Settings::sendUbxSaveCfg, this, [this](){ this->sendRequest(TCP_MSG_KEY::MSG_UBX_CFG_SAVE); } ); + connect(settings, &Settings::sendUbxSaveCfg, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_UBX_CFG_SAVE); }); - ui->tabWidget->addTab(settings,"Ublox Settings"); + ui->tabWidget->addTab(settings, "Ublox Settings"); - Map *map = new Map(this); + Map* map = new Map(this); ui->tabWidget->addTab(map, "Map"); connect(this, &MainWindow::geodeticPos, map, &Map::onGeodeticPosReceived); - - - I2cForm *i2cTab = new I2cForm(this); + I2cForm* i2cTab = new I2cForm(this); connect(this, &MainWindow::setUiEnabledStates, i2cTab, &I2cForm::onUiEnabledStateChange); connect(this, &MainWindow::i2cStatsReceived, i2cTab, &I2cForm::onI2cStatsReceived); - connect(i2cTab, &I2cForm::i2cStatsRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_I2C_STATS_REQUEST); } ); - connect(i2cTab, &I2cForm::scanI2cBusRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_I2C_SCAN_BUS); } ); + connect(i2cTab, &I2cForm::i2cStatsRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_I2C_STATS_REQUEST); }); + connect(i2cTab, &I2cForm::scanI2cBusRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_I2C_SCAN_BUS); }); - ui->tabWidget->addTab(i2cTab,"I2C bus"); + ui->tabWidget->addTab(i2cTab, "I2C bus"); calib = new CalibForm(this); connect(this, &MainWindow::setUiEnabledStates, calib, &CalibForm::onUiEnabledStateChange); connect(this, &MainWindow::calibReceived, calib, &CalibForm::onCalibReceived); - connect(calib, &CalibForm::calibRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_CALIB_REQUEST); } ); - connect(calib, &CalibForm::writeCalibToEeprom, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_CALIB_SAVE); } ); + connect(calib, &CalibForm::calibRequest, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_CALIB_REQUEST); }); + connect(calib, &CalibForm::writeCalibToEeprom, this, [this]() { this->sendRequest(TCP_MSG_KEY::MSG_CALIB_SAVE); }); connect(this, &MainWindow::adcSampleReceived, calib, &CalibForm::onAdcSampleReceived); connect(calib, &CalibForm::setBiasDacVoltage, this, &MainWindow::sendSetBiasVoltage); connect(calib, &CalibForm::setDacVoltage, this, &MainWindow::sendSetThresh); connect(calib, &CalibForm::updatedCalib, this, &MainWindow::onCalibUpdated); connect(calib, &CalibForm::setBiasSwitch, this, &MainWindow::sendSetBiasStatus); - ui->tabWidget->addTab(calib,"Calibration"); + ui->tabWidget->addTab(calib, "Calibration"); calibscandialog = new CalibScanDialog(this); calibscandialog->hide(); connect(this, &MainWindow::calibReceived, calibscandialog, &CalibScanDialog::onCalibReceived); connect(this, &MainWindow::adcSampleReceived, calibscandialog, &CalibScanDialog::onAdcSampleReceived); - GpsSatsForm *satsTab = new GpsSatsForm(this); + GpsSatsForm* satsTab = new GpsSatsForm(this); connect(this, &MainWindow::setUiEnabledStates, satsTab, &GpsSatsForm::onUiEnabledStateChange); connect(this, &MainWindow::satsReceived, satsTab, &GpsSatsForm::onSatsReceived); connect(this, &MainWindow::timeAccReceived, satsTab, &GpsSatsForm::onTimeAccReceived); @@ -199,15 +186,15 @@ MainWindow::MainWindow(QWidget *parent) : connect(this, &MainWindow::geodeticPos, satsTab, &GpsSatsForm::onGeodeticPosReceived); connect(this, &MainWindow::ubxUptimeReceived, satsTab, &GpsSatsForm::onUbxUptimeReceived); - ui->tabWidget->addTab(satsTab,"GNSS Data"); + ui->tabWidget->addTab(satsTab, "GNSS Data"); - histogramDataForm *histoTab = new histogramDataForm(this); + histogramDataForm* histoTab = new histogramDataForm(this); connect(this, &MainWindow::setUiEnabledStates, histoTab, &histogramDataForm::onUiEnabledStateChange); connect(this, &MainWindow::histogramReceived, histoTab, &histogramDataForm::onHistogramReceived); connect(histoTab, &histogramDataForm::histogramCleared, this, &MainWindow::onHistogramCleared); - ui->tabWidget->addTab(histoTab,"Statistics"); + ui->tabWidget->addTab(histoTab, "Statistics"); - ParameterMonitorForm *paramTab = new ParameterMonitorForm(this); + ParameterMonitorForm* paramTab = new ParameterMonitorForm(this); connect(this, &MainWindow::setUiEnabledStates, paramTab, &ParameterMonitorForm::onUiEnabledStateChange); connect(this, &MainWindow::adcSampleReceived, paramTab, &ParameterMonitorForm::onAdcSampleReceived); connect(this, &MainWindow::adcTraceReceived, paramTab, &ParameterMonitorForm::onAdcTraceReceived); @@ -220,7 +207,6 @@ MainWindow::MainWindow(QWidget *parent) : connect(this, &MainWindow::temperatureReceived, paramTab, &ParameterMonitorForm::onTemperatureReceived); connect(this, &MainWindow::timeAccReceived, paramTab, &ParameterMonitorForm::onTimeAccReceived); connect(this, &MainWindow::freqAccReceived, paramTab, &ParameterMonitorForm::onFreqAccReceived); -// connect(this, &MainWindow::intCounterReceived, paramTab, &ParameterMonitorForm::onIntCounterReceived); connect(this, &MainWindow::gainSwitchReceived, paramTab, &ParameterMonitorForm::onGainSwitchReceived); connect(this, &MainWindow::calibReceived, paramTab, &ParameterMonitorForm::onCalibReceived); connect(this, &MainWindow::timeMarkReceived, paramTab, &ParameterMonitorForm::onTimeMarkReceived); @@ -234,18 +220,19 @@ MainWindow::MainWindow(QWidget *parent) : connect(paramTab, &ParameterMonitorForm::timingSelectionChanged, this, &MainWindow::sendInputSwitch); connect(paramTab, &ParameterMonitorForm::triggerSelectionChanged, this, &MainWindow::onTriggerSelectionChanged); connect(paramTab, &ParameterMonitorForm::gpioInhibitChanged, this, &MainWindow::gpioInhibit); - ui->tabWidget->addTab(paramTab,"Parameters"); + ui->tabWidget->addTab(paramTab, "Parameters"); - ScanForm *scanTab = new ScanForm(this); + ScanForm* scanTab = new ScanForm(this); connect(this, &MainWindow::setUiEnabledStates, scanTab, &ScanForm::onUiEnabledStateChange); connect(this, &MainWindow::timeMarkReceived, scanTab, &ScanForm::onTimeMarkReceived); + connect(this, &MainWindow::dacReadbackReceived, scanTab, &ScanForm::onDacReadbackReceived); connect(scanTab, &ScanForm::setThresholdVoltage, this, &MainWindow::sendSetThresh); connect(scanTab, &ScanForm::setBiasControlVoltage, this, &MainWindow::sendSetBiasVoltage); connect(scanTab, &ScanForm::gpioInhibitChanged, this, &MainWindow::gpioInhibit); connect(scanTab, &ScanForm::mqttInhibitChanged, this, &MainWindow::mqttInhibit); - ui->tabWidget->addTab(scanTab,"Scans"); + ui->tabWidget->addTab(scanTab, "Scans"); - LogPlotsWidget *logTab = new LogPlotsWidget(this); + LogPlotsWidget* logTab = new LogPlotsWidget(this); connect(this, &MainWindow::temperatureReceived, logTab, &LogPlotsWidget::onTemperatureReceived); connect(this, &MainWindow::timeAccReceived, logTab, &LogPlotsWidget::onTimeAccReceived); connect(this, &MainWindow::setUiEnabledStates, logTab, &LogPlotsWidget::onUiEnabledStateChange); @@ -254,25 +241,14 @@ MainWindow::MainWindow(QWidget *parent) : connect(this, &MainWindow::gpioRates, logTab, &LogPlotsWidget::onGpioRatesReceived, Qt::QueuedConnection); - connect(this, &MainWindow::logInfoReceived, logTab, &LogPlotsWidget::onLogInfoReceived); ui->tabWidget->addTab(logTab, "Log"); - - //sendRequest(calibRequestSig); - - //settings->show(); - // set menu bar actions - //connect(ui->actionsettings, &QAction::triggered, this, &MainWindow::settings_clicked); - - const QStandardItemModel *model = dynamic_cast(ui->biasControlTypeComboBox->model()); - QStandardItem *item = model->item(1); + const QStandardItemModel* model = dynamic_cast(ui->biasControlTypeComboBox->model()); + QStandardItem* item = model->item(1); item->setEnabled(false); // initialise all ui elements that will be inactive at start uiSetDisconnectedState(); - -// printf("WindowSize %d %d\r\n",this->width(),this->height()); - } MainWindow::~MainWindow() @@ -282,19 +258,26 @@ MainWindow::~MainWindow() delete ui; } -void MainWindow::makeConnection(QString ipAddress, quint16 port) { +void MainWindow::makeConnection(QString ipAddress, quint16 port) +{ // add popup windows for errors!!! - QThread *tcpThread = new QThread(); + QThread* tcpThread = new QThread(); tcpThread->setObjectName("muondetector-gui-tcp"); if (!tcpConnection) { - delete(tcpConnection); + delete (tcpConnection); } + ui->ipStatusLabel->setStyleSheet("QLabel {color: darkGray;}"); + ui->ipStatusLabel->setText("Please wait..."); + ui->ipButton->setText("connecting"); + ui->ipButton->setEnabled(false); + ui->ipBox->setEnabled(false); tcpConnection = new TcpConnection(ipAddress, port, verbose); tcpConnection->moveToThread(tcpThread); connect(tcpThread, &QThread::started, tcpConnection, &TcpConnection::makeConnection); connect(tcpThread, &QThread::finished, tcpThread, &QThread::deleteLater); connect(tcpThread, &QThread::finished, tcpConnection, &TcpConnection::deleteLater); connect(tcpConnection, &TcpConnection::connected, this, &MainWindow::connected); + connect(tcpConnection, &TcpConnection::error, this, &MainWindow::connection_error); connect(this, &MainWindow::closeConnection, tcpConnection, &TcpConnection::closeThisConnection); connect(tcpConnection, &TcpConnection::finished, tcpThread, &QThread::quit); connect(this, &MainWindow::sendTcpMessage, tcpConnection, &TcpConnection::sendTcpMessage); @@ -310,22 +293,23 @@ void MainWindow::onTriggerSelectionChanged(GPIO_SIGNAL signal) sendRequest(TCP_MSG_KEY::MSG_EVENTTRIGGER_REQUEST); } -bool MainWindow::saveSettings(QStandardItemModel *model) { - QString file_location {QStandardPaths::writableLocation(QStandardPaths::CacheLocation)}; +bool MainWindow::saveSettings(QStandardItemModel* model) +{ + QString file_location { QStandardPaths::writableLocation(QStandardPaths::CacheLocation) }; if (!QDir(file_location).exists()) { if (!QDir().mkpath(file_location)) { qWarning() << "Could not create cache path"; return false; } } - QFile file{file_location + "/muondetector-gui.save"}; + QFile file { file_location + "/muondetector-gui.save" }; if (!file.open(QIODevice::WriteOnly)) { qWarning() << "file open failed in 'WriteOnly' mode at location " << file.fileName(); return false; } - QDataStream stream{&file}; - qint32 n{model->rowCount()}; + QDataStream stream { &file }; + qint32 n { model->rowCount() }; stream << n; for (int i = 0; i < n; i++) { model->item(i)->write(stream); @@ -334,9 +318,10 @@ bool MainWindow::saveSettings(QStandardItemModel *model) { return true; } -bool MainWindow::loadSettings(QStandardItemModel* model) { - QFile file{QStandardPaths::writableLocation(QStandardPaths::CacheLocation) + "/muondetector-gui.save"}; - if (file.exists() || !file.open(QIODevice::ReadOnly)) { +bool MainWindow::loadSettings(QStandardItemModel* model) +{ + QFile file { QStandardPaths::writableLocation(QStandardPaths::CacheLocation) + "/muondetector-gui.save" }; + if (!file.exists() || !file.open(QIODevice::ReadOnly)) { qDebug() << "file open failed in 'ReadOnly' mode at location " << file.fileName(); return false; } @@ -351,48 +336,34 @@ bool MainWindow::loadSettings(QStandardItemModel* model) { return true; } -bool MainWindow::eventFilter(QObject *object, QEvent *event) +bool MainWindow::eventFilter(QObject* object, QEvent* event) { if (event->type() == QEvent::KeyPress) { - QKeyEvent *ke = static_cast(event); + QKeyEvent* ke = static_cast(event); if (ke->key() == Qt::Key_Escape) { QCoreApplication::quit(); return true; } - /* - if (ke->key() == Qt::Key_Escape) { - if (connectedToDemon){ - onIpButtonClicked(); - }else{ - QCoreApplication::quit(); - } - return true; - } - if (ke->key() == Qt::Key_Enter && !connectedToDemon){ - onIpButtonClicked(); - return true; - }*/ // crashes when alternating escape and enter ...why? - auto combobox = dynamic_cast(object); + auto combobox = dynamic_cast(object); if (combobox == ui->ipBox) { if (ke->key() == Qt::Key_Delete) { ui->ipBox->removeItem(ui->ipBox->currentIndex()); - }else if (ke->key() == Qt::Key_Enter || ke->key() == Qt::Key_Return) { + } else if (ke->key() == Qt::Key_Enter || ke->key() == Qt::Key_Return) { onIpButtonClicked(); - }else{ + } else { return QObject::eventFilter(object, event); } - }else { + } else { return QObject::eventFilter(object, event); } return true; - } - else { + } else { return QObject::eventFilter(object, event); } } -void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { -// quint16 msgID = tcpMessage.getMsgID(); +void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) +{ TCP_MSG_KEY msgID = static_cast(tcpMessage.getMsgID()); if (msgID == TCP_MSG_KEY::MSG_GPIO_EVENT) { unsigned int gpioPin; @@ -401,35 +372,38 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { return; } if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE) { - QMap msgRateCfgs; + QMap msgRateCfgs; *(tcpMessage.dStream) >> msgRateCfgs; - emit addUbxMsgRates(msgRateCfgs); - return; - } - if (msgID == TCP_MSG_KEY::MSG_THRESHOLD){ - quint8 channel; - float threshold; - *(tcpMessage.dStream) >> channel >> threshold; - if (threshold > maxThreshVoltage){ - sendSetThresh(channel,maxThreshVoltage); + emit addUbxMsgRates(msgRateCfgs); return; } - sliderValues[channel] = (int)(2000 * threshold); + if (msgID == TCP_MSG_KEY::MSG_THRESHOLD) { + quint8 channel; + float threshold; + *(tcpMessage.dStream) >> channel >> threshold; + if (threshold > maxThreshVoltage) { + sendSetThresh(channel, maxThreshVoltage); + return; + } + if (std::abs(sliderValues.at(channel) - (1e3 * threshold)) > std::numeric_limits::epsilon()) { + sliderValuesDirty = true; + } + sliderValues.at(channel) = 1e3 * threshold; updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE){ + if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE) { *(tcpMessage.dStream) >> biasDacVoltage; updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_BIAS_SWITCH){ + if (msgID == TCP_MSG_KEY::MSG_BIAS_SWITCH) { *(tcpMessage.dStream) >> biasON; emit biasSwitchReceived(biasON); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH){ + if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH) { quint8 channel; bool state; *(tcpMessage.dStream) >> channel >> state; @@ -437,58 +411,56 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH){ + if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH) { bool gainSwitch; *(tcpMessage.dStream) >> gainSwitch; emit gainSwitchReceived(gainSwitch); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH){ + if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH) { *(tcpMessage.dStream) >> pcaPortMask; - //status->setInputSwitchButtonGroup(pcaPortMask); emit inputSwitchReceived(pcaPortMask); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER){ + if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER) { unsigned int signal; *(tcpMessage.dStream) >> signal; emit triggerSelectionReceived((GPIO_SIGNAL)signal); - //updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE){ + if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE) { quint8 whichRate; QVector rate; *(tcpMessage.dStream) >> whichRate >> rate; float rateYValue; - if (!rate.empty()){ - rateYValue = rate.at(rate.size()-1).y(); - }else{ + if (!rate.empty()) { + rateYValue = rate.at(rate.size() - 1).y(); + } else { rateYValue = 0.0; } - if (whichRate == 0){ - ui->rate1->setText(QString::number(rateYValue,'g',3)+"/s"); + if (whichRate == 0) { + ui->rate1->setText(QString::number(rateYValue, 'g', 3) + "/s"); } - if (whichRate == 1){ - ui->rate2->setText(QString::number(rateYValue,'g',3)+"/s"); + if (whichRate == 1) { + ui->rate2->setText(QString::number(rateYValue, 'g', 3) + "/s"); } emit gpioRates(whichRate, rate); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_QUIT_CONNECTION){ + if (msgID == TCP_MSG_KEY::MSG_QUIT_CONNECTION) { connectedToDemon = false; uiSetDisconnectedState(); } - if (msgID == TCP_MSG_KEY::MSG_GEO_POS){ + if (msgID == TCP_MSG_KEY::MSG_GEO_POS) { GeodeticPos pos; *(tcpMessage.dStream) >> pos.iTOW >> pos.lon >> pos.lat - >> pos.height >> pos.hMSL >> pos.hAcc >> pos.vAcc; + >> pos.height >> pos.hMSL >> pos.hAcc >> pos.vAcc; emit geodeticPos(pos); } - if (msgID == TCP_MSG_KEY::MSG_ADC_SAMPLE){ + if (msgID == TCP_MSG_KEY::MSG_ADC_SAMPLE) { quint8 channel; float value; *(tcpMessage.dStream) >> channel >> value; @@ -496,20 +468,19 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_ADC_TRACE){ + if (msgID == TCP_MSG_KEY::MSG_ADC_TRACE) { quint16 size; QVector sampleBuffer; *(tcpMessage.dStream) >> size; - for (int i=0; i> value; sampleBuffer.push_back(value); } emit adcTraceReceived(sampleBuffer); - //qDebug()<<"trace received. length="<> channel >> value; @@ -517,115 +488,110 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_TEMPERATURE){ + if (msgID == TCP_MSG_KEY::MSG_TEMPERATURE) { float value; *(tcpMessage.dStream) >> value; emit temperatureReceived(value); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_I2C_STATS){ - quint8 nrDevices=0; - quint32 bytesRead = 0; - quint32 bytesWritten = 0; + if (msgID == TCP_MSG_KEY::MSG_I2C_STATS) { + quint8 nrDevices = 0; + quint32 bytesRead = 0; + quint32 bytesWritten = 0; *(tcpMessage.dStream) >> nrDevices >> bytesRead >> bytesWritten; - QVector deviceList; - for (uint8_t i=0; i> addr >> title >> status; - I2cDeviceEntry entry; - entry.address=addr; - entry.name = title; - entry.status=status; - deviceList.push_back(entry); - } + QVector deviceList; + for (uint8_t i = 0; i < nrDevices; i++) { + uint8_t addr = 0; + QString title = "none"; + uint8_t status = 0; + *(tcpMessage.dStream) >> addr >> title >> status; + I2cDeviceEntry entry; + entry.address = addr; + entry.name = title; + entry.status = status; + deviceList.push_back(entry); + } emit i2cStatsReceived(bytesRead, bytesWritten, deviceList); - //updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_SPI_STATS){ + if (msgID == TCP_MSG_KEY::MSG_SPI_STATS) { bool spiPresent; *(tcpMessage.dStream) >> spiPresent; emit spiStatsReceived(spiPresent); } - if (msgID == TCP_MSG_KEY::MSG_CALIB_SET){ - quint16 nrPars=0; - quint64 id = 0; - bool valid = false; - bool eepromValid = 0; + if (msgID == TCP_MSG_KEY::MSG_CALIB_SET) { + quint16 nrPars = 0; + quint64 id = 0; + bool valid = false; + bool eepromValid = 0; *(tcpMessage.dStream) >> valid >> eepromValid >> id >> nrPars; - QVector calibList; - for (uint8_t i=0; i> item; - calibList.push_back(item); - } + QVector calibList; + for (uint8_t i = 0; i < nrPars; i++) { + CalibStruct item; + *(tcpMessage.dStream) >> item; + calibList.push_back(item); + } emit calibReceived(valid, eepromValid, id, calibList); return; } - if (msgID == TCP_MSG_KEY::MSG_GNSS_SATS){ - int nrSats=0; - *(tcpMessage.dStream) >> nrSats; + if (msgID == TCP_MSG_KEY::MSG_GNSS_SATS) { + int nrSats = 0; + *(tcpMessage.dStream) >> nrSats; - QVector satList; - for (uint8_t i=0; i> sat; - satList.push_back(sat); - } + QVector satList; + for (uint8_t i = 0; i < nrSats; i++) { + GnssSatellite sat; + *(tcpMessage.dStream) >> sat; + satList.push_back(sat); + } emit satsReceived(satList); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG){ - int numTrkCh=0; - int nrConfigs=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG) { + int numTrkCh = 0; + int nrConfigs = 0; *(tcpMessage.dStream) >> numTrkCh >> nrConfigs; QVector configList; - for (int i=0; i> config.gnssId >> config.resTrkCh >> - config.maxTrkCh >> config.flags; + *(tcpMessage.dStream) >> config.gnssId >> config.resTrkCh >> config.maxTrkCh >> config.flags; configList.push_back(config); } emit gnssConfigsReceived(numTrkCh, configList); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_TIME_ACCURACY){ - quint32 acc=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_TIME_ACCURACY) { + quint32 acc = 0; *(tcpMessage.dStream) >> acc; emit timeAccReceived(acc); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_FREQ_ACCURACY){ - quint32 acc=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_FREQ_ACCURACY) { + quint32 acc = 0; *(tcpMessage.dStream) >> acc; emit freqAccReceived(acc); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_EVENTCOUNTER){ - quint32 cnt=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_EVENTCOUNTER) { + quint32 cnt = 0; *(tcpMessage.dStream) >> cnt; emit intCounterReceived(cnt); + ui->eventCounter->setText(QString::number(cnt)); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_UPTIME){ - quint32 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_UPTIME) { + quint32 val = 0; *(tcpMessage.dStream) >> val; emit ubxUptimeReceived(val); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_TXBUF){ - quint8 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_TXBUF) { + quint8 val = 0; *(tcpMessage.dStream) >> val; emit txBufReceived(val); if (!tcpMessage.dStream->atEnd()) { @@ -634,8 +600,8 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { } return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_RXBUF){ - quint8 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_RXBUF) { + quint8 val = 0; *(tcpMessage.dStream) >> val; emit rxBufReceived(val); if (!tcpMessage.dStream->atEnd()) { @@ -644,65 +610,51 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { } return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_TXBUF_PEAK){ - quint8 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_TXBUF_PEAK) { + quint8 val = 0; *(tcpMessage.dStream) >> val; emit txBufPeakReceived(val); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_RXBUF_PEAK){ - quint8 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_RXBUF_PEAK) { + quint8 val = 0; *(tcpMessage.dStream) >> val; emit rxBufPeakReceived(val); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_MONHW){ -/* quint16 noise=0; - quint16 agc=0; - quint8 antStatus=0; - quint8 antPower=0; - quint8 jamInd=0; - quint8 flags=0;*/ + if (msgID == TCP_MSG_KEY::MSG_UBX_MONHW) { GnssMonHwStruct hw; - //*(tcpMessage.dStream) >> noise >> agc >> antStatus >> antPower >> jamInd >> flags; - *(tcpMessage.dStream) >> hw; - //emit gpsMonHWReceived(noise,agc,antStatus,antPower,jamInd,flags); + *(tcpMessage.dStream) >> hw; emit gpsMonHWReceived(hw); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_MONHW2){ -/* qint8 ofsI=0, ofsQ=0; - quint8 magI=0, magQ=0; - quint8 cfgSrc=0;*/ - GnssMonHw2Struct hw2; -// *(tcpMessage.dStream) >> hw2.ofsI >> hw2.magI >> hw2.ofsQ >> hw2.magQ >> hw2.cfgSrc; + if (msgID == TCP_MSG_KEY::MSG_UBX_MONHW2) { + GnssMonHw2Struct hw2; *(tcpMessage.dStream) >> hw2; - //qDebug()<<"ofsI="<> sw >> hw >> pv; emit gpsVersionReceived(sw, hw, pv); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_FIXSTATUS){ - quint8 val=0; + if (msgID == TCP_MSG_KEY::MSG_UBX_FIXSTATUS) { + quint8 val = 0; *(tcpMessage.dStream) >> val; emit gpsFixReceived(val); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_TP5){ + if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_TP5) { UbxTimePulseStruct tp; *(tcpMessage.dStream) >> tp; emit gpsTP5Received(tp); return; } - if (msgID == TCP_MSG_KEY::MSG_HISTOGRAM){ + if (msgID == TCP_MSG_KEY::MSG_HISTOGRAM) { Histogram h; *(tcpMessage.dStream) >> h; emit histogramReceived(h); @@ -714,25 +666,25 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { emit adcModeReceived(mode); return; } - if (msgID == TCP_MSG_KEY::MSG_LOG_INFO){ + if (msgID == TCP_MSG_KEY::MSG_LOG_INFO) { LogInfoStruct lis; *(tcpMessage.dStream) >> lis; emit logInfoReceived(lis); return; } - if (msgID == TCP_MSG_KEY::MSG_UBX_TIMEMARK){ + if (msgID == TCP_MSG_KEY::MSG_UBX_TIMEMARK) { UbxTimeMarkStruct tm; *(tcpMessage.dStream) >> tm; emit timeMarkReceived(tm); return; } - if (msgID == TCP_MSG_KEY::MSG_MQTT_STATUS){ + if (msgID == TCP_MSG_KEY::MSG_MQTT_STATUS) { bool connected = false; *(tcpMessage.dStream) >> connected; emit mqttStatusChanged(connected); return; } - if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH){ + if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH) { bool pol1; bool pol2; *(tcpMessage.dStream) >> pol1 >> pol2; @@ -740,93 +692,100 @@ void MainWindow::receivedTcpMessage(TcpMessage tcpMessage) { updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_GPIO_INHIBIT){ + if (msgID == TCP_MSG_KEY::MSG_GPIO_INHIBIT) { bool inhibit; *(tcpMessage.dStream) >> inhibit; emit gpioInhibitReceived(inhibit); updateUiProperties(); return; } - if (msgID == TCP_MSG_KEY::MSG_MQTT_INHIBIT){ + if (msgID == TCP_MSG_KEY::MSG_MQTT_INHIBIT) { bool inhibit; *(tcpMessage.dStream) >> inhibit; emit mqttInhibitReceived(inhibit); updateUiProperties(); return; } - } -void MainWindow::sendRequest(quint16 requestSig){ +void MainWindow::sendRequest(quint16 requestSig) +{ TcpMessage tcpMessage(requestSig); emit sendTcpMessage(tcpMessage); } -void MainWindow::sendRequest(TCP_MSG_KEY requestSig){ +void MainWindow::sendRequest(TCP_MSG_KEY requestSig) +{ TcpMessage tcpMessage(requestSig); emit sendTcpMessage(tcpMessage); } -void MainWindow::sendRequest(quint16 requestSig, quint8 par){ +void MainWindow::sendRequest(quint16 requestSig, quint8 par) +{ TcpMessage tcpMessage(requestSig); *(tcpMessage.dStream) << par; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendRequest(TCP_MSG_KEY requestSig, quint8 par){ +void MainWindow::sendRequest(TCP_MSG_KEY requestSig, quint8 par) +{ TcpMessage tcpMessage(requestSig); *(tcpMessage.dStream) << par; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendRequestUbxMsgRates(){ +void MainWindow::sendRequestUbxMsgRates() +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MSG_RATE_REQUEST); emit sendTcpMessage(tcpMessage); } -void MainWindow::sendSetBiasVoltage(float voltage){ +void MainWindow::sendSetBiasVoltage(float voltage) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_VOLTAGE); *(tcpMessage.dStream) << voltage; emit sendTcpMessage(tcpMessage); -// emit sendRequest(TCP_MSG_KEY::MSG_DAC_REQUEST, 2); - emit sendRequest(TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST); -// emit sendRequest(adcSampleRequestSig, 2); -// emit sendRequest(adcSampleRequestSig, 3); + emit sendRequest(TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST); } -void MainWindow::sendSetBiasStatus(bool status){ +void MainWindow::sendSetBiasStatus(bool status) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_SWITCH); *(tcpMessage.dStream) << status; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendGainSwitch(bool status){ +void MainWindow::sendGainSwitch(bool status) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GAIN_SWITCH); *(tcpMessage.dStream) << status; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendPreamp1Switch(bool status){ +void MainWindow::sendPreamp1Switch(bool status) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PREAMP_SWITCH); *(tcpMessage.dStream) << (quint8)0 << status; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendPreamp2Switch(bool status){ +void MainWindow::sendPreamp2Switch(bool status) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PREAMP_SWITCH); *(tcpMessage.dStream) << (quint8)1 << status; emit sendTcpMessage(tcpMessage); } -void MainWindow::sendSetThresh(uint8_t channel, float value){ +void MainWindow::sendSetThresh(uint8_t channel, float value) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_THRESHOLD); *(tcpMessage.dStream) << channel << value; emit sendTcpMessage(tcpMessage); - emit sendRequest(TCP_MSG_KEY::MSG_THRESHOLD_REQUEST, channel); - //emit sendRequest(TCP_MSG_KEY::MSG_DAC_REQUEST, channel); + emit sendRequest(TCP_MSG_KEY::MSG_THRESHOLD_REQUEST, channel); } -void MainWindow::sendSetUbxMsgRateChanges(QMap changes){ +void MainWindow::sendSetUbxMsgRateChanges(QMap changes) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MSG_RATE); *(tcpMessage.dStream) << changes; emit sendTcpMessage(tcpMessage); @@ -838,44 +797,48 @@ void MainWindow::onSendUbxReset() emit sendTcpMessage(tcpMessage); } -void MainWindow::onHistogramCleared(QString histogramName){ +void MainWindow::onHistogramCleared(QString histogramName) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_HISTOGRAM_CLEAR); *(tcpMessage.dStream) << histogramName; emit sendTcpMessage(tcpMessage); -// qDebug()<<"received signal in slot MainWindow::onHistogramCleared("<(mode); emit sendTcpMessage(tcpMessage); } -void MainWindow::onRateScanStart(uint8_t ch) { +void MainWindow::onRateScanStart(uint8_t ch) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_RATE_SCAN); *(tcpMessage.dStream) << (quint8)ch; emit sendTcpMessage(tcpMessage); } -void MainWindow::onSetGnssConfigs(const QVector& configList){ +void MainWindow::onSetGnssConfigs(const QVector& configList) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG); - int N=configList.size(); + int N = configList.size(); *(tcpMessage.dStream) << (int)N; - for (int i=0; iANDHit->setStyleSheet("QLabel {background-color: darkGreen;}"); andTimer.start(); @@ -905,72 +870,71 @@ void MainWindow::receivedGpioRisingEdge(GPIO_SIGNAL pin) { } } -void MainWindow::resetAndHit() { +void MainWindow::resetAndHit() +{ ui->ANDHit->setStyleSheet("QLabel {background-color: Window;}"); } -void MainWindow::resetXorHit() { +void MainWindow::resetXorHit() +{ ui->XORHit->setStyleSheet("QLabel {background-color: Window;}"); } -void MainWindow::uiSetDisconnectedState() { +void MainWindow::uiSetDisconnectedState() +{ + sliderValuesDirty = true; // set button and color of label ui->ipStatusLabel->setStyleSheet("QLabel {color: darkGray;}"); ui->ipStatusLabel->setText("not connected"); ui->ipButton->setText("connect"); + ui->ipButton->setEnabled(true); ui->ipBox->setEnabled(true); // disable all relevant objects of mainwindow - ui->discr1Label->setStyleSheet("QLabel {color: darkGray;}"); - ui->discr2Label->setStyleSheet("QLabel {color: darkGray;}"); ui->discr1Slider->setValue(0); - ui->discr1Slider->setDisabled(true); ui->discr1Edit->clear(); - ui->discr1Edit->setDisabled(true); ui->discr2Slider->setValue(0); - ui->discr2Slider->setDisabled(true); ui->discr2Edit->clear(); - ui->discr2Edit->setDisabled(true); - ui->ANDHit->setDisabled(true); - ui->ANDHit->setStyleSheet("QLabel {background-color: Window;}"); - ui->XORHit->setDisabled(true); - ui->XORHit->setStyleSheet("QLabel {background-color: Window;}"); - ui->rate1->setDisabled(true); - ui->rate2->setDisabled(true); - ui->biasPowerLabel->setDisabled(true); ui->biasPowerLabel->setStyleSheet("QLabel {color: darkGray;}"); - ui->biasPowerButton->setDisabled(true); + ui->tabWidget->setEnabled(false); + ui->controlWidget->setEnabled(false); // disable other widgets emit setUiEnabledStates(false); } -void MainWindow::uiSetConnectedState() { +void MainWindow::uiSetConnectedState() +{ + sliderValuesDirty = true; // change color and text of labels and buttons + ui->tabWidget->setEnabled(true); + ui->controlWidget->setEnabled(true); ui->ipStatusLabel->setStyleSheet("QLabel {color: darkGreen;}"); ui->ipStatusLabel->setText("connected"); ui->ipButton->setText("disconnect"); + ui->ipButton->setEnabled(true); ui->ipBox->setDisabled(true); - ui->discr1Label->setStyleSheet("QLabel {color: black;}"); - ui->discr2Label->setStyleSheet("QLabel {color: black;}"); // enable other widgets emit setUiEnabledStates(true); } -void MainWindow::updateUiProperties() { +void MainWindow::updateUiProperties() +{ mouseHold = true; - ui->discr1Slider->setEnabled(true); - ui->discr1Slider->setValue(sliderValues.at(0)); - ui->discr1Edit->setEnabled(true); - ui->discr1Edit->setText(QString::number(sliderValues.at(0) / 2.0) + "mV"); + if (sliderValuesDirty) { + ui->discr1Slider->setEnabled(true); + ui->discr1Slider->setValue(sliderValues.at(0)); + ui->discr1Edit->setEnabled(true); + + ui->discr2Slider->setEnabled(true); + ui->discr2Slider->setValue(sliderValues.at(1)); + ui->discr2Edit->setEnabled(true); - ui->discr2Slider->setEnabled(true); - ui->discr2Slider->setValue(sliderValues.at(1)); - ui->discr2Edit->setEnabled(true); - ui->discr2Edit->setText(QString::number(sliderValues.at(1) / 2.0) + "mV"); - double biasVoltage = biasCalibOffset + biasDacVoltage*biasCalibSlope; + sliderValuesDirty = false; + } + double biasVoltage = biasCalibOffset + biasDacVoltage * biasCalibSlope; ui->biasVoltageSlider->blockSignals(true); ui->biasVoltageDoubleSpinBox->blockSignals(true); ui->biasVoltageDoubleSpinBox->setValue(biasVoltage); - ui->biasVoltageSlider->setValue(100*biasVoltage/maxBiasVoltage); + ui->biasVoltageSlider->setValue(100 * biasVoltage / maxBiasVoltage); ui->biasVoltageSlider->blockSignals(false); ui->biasVoltageDoubleSpinBox->blockSignals(false); // equation: @@ -978,33 +942,31 @@ void MainWindow::updateUiProperties() { // (UBias - c0)/c1 = UDac ui->ANDHit->setEnabled(true); - //ui->ANDHit->setStyleSheet("QLabel {background-color: darkRed; color: white;}"); ui->XORHit->setEnabled(true); - //ui->XORHit->setStyleSheet("QLabel {background-color: darkRed; color: white;}"); ui->rate1->setEnabled(true); ui->rate2->setEnabled(true); ui->biasPowerButton->setEnabled(true); ui->biasPowerLabel->setEnabled(true); if (biasON) { - ui->biasPowerButton->setText("Disable Bias"); + ui->biasPowerButton->setText("Disable"); ui->biasPowerLabel->setText("Bias ON"); ui->biasPowerLabel->setStyleSheet("QLabel {background-color: darkGreen; color: white;}"); - } - else { - ui->biasPowerButton->setText("Enable Bias"); + } else { + ui->biasPowerButton->setText("Enable"); ui->biasPowerLabel->setText("Bias OFF"); ui->biasPowerLabel->setStyleSheet("QLabel {background-color: red; color: white;}"); } mouseHold = false; } -void MainWindow::connected() { +void MainWindow::connected() +{ connectedToDemon = true; saveSettings(addresses); uiSetConnectedState(); sendValueUpdateRequests(); - sendRequest(TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST,0); - sendRequest(TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST,1); + sendRequest(TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST, 0); + sendRequest(TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST, 1); sendRequest(TCP_MSG_KEY::MSG_GAIN_SWITCH_REQUEST); sendRequest(TCP_MSG_KEY::MSG_THRESHOLD_REQUEST); sendRequest(TCP_MSG_KEY::MSG_PCA_SWITCH_REQUEST); @@ -1012,24 +974,26 @@ void MainWindow::connected() { sendRequestGpioRateBuffer(); sendRequest(TCP_MSG_KEY::MSG_CALIB_REQUEST); sendRequest(TCP_MSG_KEY::MSG_ADC_MODE_REQUEST); - sendRequest(TCP_MSG_KEY::MSG_POLARITY_SWITCH_REQUEST); + sendRequest(TCP_MSG_KEY::MSG_POLARITY_SWITCH_REQUEST); } +void MainWindow::connection_error(int error_code, const QString message) +{ + uiSetDisconnectedState(); + ui->ipStatusLabel->setStyleSheet("QLabel {color: red;}"); + ui->ipStatusLabel->setText("Connection error: (" + QString::number(error_code) + ") '" + message + "'"); +} -void MainWindow::sendValueUpdateRequests() { +void MainWindow::sendValueUpdateRequests() +{ sendRequest(TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST); sendRequest(TCP_MSG_KEY::MSG_BIAS_SWITCH_REQUEST); -// sendRequest(preampRequestSig,0); -// sendRequest(preampRequestSig,1); -// sendRequest(threshRequestSig); - for (int i=0; i<4; i++) sendRequest(TCP_MSG_KEY::MSG_DAC_REQUEST,i); - for (int i=1; i<4; i++) sendRequest(TCP_MSG_KEY::MSG_ADC_SAMPLE_REQUEST,i); -// sendRequest(pcaChannelRequestSig); -// sendRequestUbxMsgRates(); -// sendRequestGpioRateBuffer(); + for (int i = 0; i < 4; i++) + sendRequest(TCP_MSG_KEY::MSG_DAC_REQUEST, i); + for (int i = 1; i < 4; i++) + sendRequest(TCP_MSG_KEY::MSG_ADC_SAMPLE_REQUEST, i); sendRequest(TCP_MSG_KEY::MSG_TEMPERATURE_REQUEST); sendRequest(TCP_MSG_KEY::MSG_I2C_STATS_REQUEST); -// sendRequest(calibRequestSig); } void MainWindow::onIpButtonClicked() @@ -1054,93 +1018,50 @@ void MainWindow::onIpButtonClicked() if (ipAddress == "local" || ipAddress == "localhost") { ipAddress = "127.0.0.1"; } - QString portString; + int port { MuonPi::Settings::gui.port }; if (ipAndPort.size() == 2) { - portString = ipAndPort.at(1); - } - else { - portString = "51508"; + port = ipAndPort.at(1).toInt(); } - makeConnection(ipAddress, portString.toUInt()); + makeConnection(ipAddress, port); if (!ui->ipBox->currentText().isEmpty() && ui->ipBox->findText(ui->ipBox->currentText()) == -1) { // if text not already in there, put it in there ui->ipBox->addItem(ui->ipBox->currentText()); } } -void MainWindow::on_discr1Slider_sliderPressed() +void MainWindow::on_discr1Save_clicked() { - mouseHold = true; -} - -void MainWindow::on_discr1Slider_sliderReleased() -{ - mouseHold = false; - on_discr1Slider_valueChanged(ui->discr1Slider->value()); + sendSetThresh(0, 1e-3 * ui->discr1Edit->value()); + sliderValuesDirty = true; } -void MainWindow::on_discr1Edit_editingFinished() +void MainWindow::on_discr2Save_clicked() { - float value = parseValue(ui->discr1Edit->text()); - if (value < 0) { - return; - } - ui->discr1Slider->setValue((int)(value * 2 + 0.5)); + sendSetThresh(1, 1e-3 * ui->discr2Edit->value()); + sliderValuesDirty = true; } -void MainWindow::on_discr1Slider_valueChanged(int value) +void MainWindow::setMaxThreshVoltage(float voltage) { - float thresh0 = (float)(value / 2000.0); - ui->discr1Edit->setText(QString::number((float)value / 2.0) + "mV"); - if (!mouseHold) { - sendSetThresh(0, thresh0); - } -} + // we have 0.5 mV resolution so we have (int)(mVolts)*2 steps on the slider + // the '+0.5' is to round up or down like in mathematics + maxThreshVoltage = voltage; -void MainWindow::on_discr2Slider_sliderPressed() -{ - mouseHold = true; -} + ui->discr1Slider->setUpperBound(1e3 * voltage); + ui->discr2Slider->setUpperBound(1e3 * voltage); + ui->discr1Edit->setMaximum(1e3 * voltage); + ui->discr2Edit->setMaximum(1e3 * voltage); -void MainWindow::on_discr2Slider_sliderReleased() -{ - mouseHold = false; - on_discr2Slider_valueChanged(ui->discr2Slider->value()); -} - -void MainWindow::on_discr2Edit_editingFinished() -{ - float value = parseValue(ui->discr2Edit->text()); - if (value < 0) { - return; + if (sliderValues.at(0) > voltage) { + sendSetThresh(0, voltage); + } + if (sliderValues.at(1) > voltage) { + sendSetThresh(1, voltage); } - ui->discr2Slider->setValue((int)(value * 2 + 0.5)); } -void MainWindow::on_discr2Slider_valueChanged(int value) +float MainWindow::parseValue(QString text) { - float thresh1 = (float)(value / 2000.0); - ui->discr2Edit->setText(QString::number((float)(value / 2.0)) + "mV"); - if (!mouseHold) { - sendSetThresh(1, thresh1); - } -} -void MainWindow::setMaxThreshVoltage(float voltage){ - // we have 0.5 mV resolution so we have (int)(mVolts)*2 steps on the slider - // the '+0.5' is to round up or down like in mathematics - maxThreshVoltage = voltage; - int maximum = (int)(voltage*2000+0.5); - ui->discr1Slider->setMaximum(maximum); - ui->discr2Slider->setMaximum(maximum); - int bigger = (sliderValues.at(0)>sliderValues.at(1))?0:1; - if( sliderValues.at(bigger) > maximum){ - sendSetThresh(bigger,voltage); - if (sliderValues.at(!bigger) > maximum){ - sendSetThresh(!bigger,voltage); - } - } -} -float MainWindow::parseValue(QString text) { // ignores everything that is not a number or at least most of it QRegExp alphabetical = QRegExp("[a-z]+[A-Z]+"); QRegExp specialCharacters = QRegExp( @@ -1170,7 +1091,8 @@ void MainWindow::on_biasPowerButton_clicked() sendSetBiasStatus(!biasON); } -void MainWindow::sendInputSwitch(uint8_t id) { +void MainWindow::sendInputSwitch(uint8_t id) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PCA_SWITCH); *(tcpMessage.dStream) << (quint8)id; emit sendTcpMessage(tcpMessage); @@ -1185,13 +1107,15 @@ void MainWindow::on_biasVoltageSlider_sliderReleased() void MainWindow::on_biasVoltageSlider_valueChanged(int value) { - if (!mouseHold) - { - double biasVoltage = (double)value/ui->biasVoltageSlider->maximum()*maxBiasVoltage; - if (fabs(biasCalibSlope)<1e-5) return; - double dacVoltage = (biasVoltage-biasCalibOffset)/biasCalibSlope; - if (dacVoltage<0.) dacVoltage=0.; - if (dacVoltage>3.3) dacVoltage=3.3; + if (!mouseHold) { + double biasVoltage = (double)value / ui->biasVoltageSlider->maximum() * maxBiasVoltage; + if (fabs(biasCalibSlope) < 1e-5) + return; + double dacVoltage = (biasVoltage - biasCalibOffset) / biasCalibSlope; + if (dacVoltage < 0.) + dacVoltage = 0.; + if (dacVoltage > 3.3) + dacVoltage = 3.3; sendSetBiasVoltage(dacVoltage); } // equation: @@ -1201,17 +1125,18 @@ void MainWindow::on_biasVoltageSlider_valueChanged(int value) void MainWindow::on_biasVoltageSlider_sliderPressed() { - mouseHold=true; + mouseHold = true; } void MainWindow::onCalibUpdated(const QVector& items) { - if (calib==nullptr) return; + if (calib == nullptr) + return; TcpMessage tcpMessage(TCP_MSG_KEY::MSG_CALIB_SET); if (items.size()) { *(tcpMessage.dStream) << (quint8)items.size(); - for (int i=0; i& items) uint8_t flags = calib->getCalibParameter("CALIB_FLAGS").toUInt(); bool calibedBias = false; - if (flags & CalibStruct::CALIBFLAGS_VOLTAGE_COEFFS) calibedBias=true; + if (flags & CalibStruct::CALIBFLAGS_VOLTAGE_COEFFS) + calibedBias = true; - const QStandardItemModel *model = dynamic_cast(ui->biasControlTypeComboBox->model()); - QStandardItem *item = model->item(1); + const QStandardItemModel* model = dynamic_cast(ui->biasControlTypeComboBox->model()); + QStandardItem* item = model->item(1); item->setEnabled(calibedBias); -/* - item->setFlags(disable ? item->flags() & ~(Qt::ItemIsSelectable|Qt::ItemIsEnabled) - : Qt::ItemIsSelectable|Qt::ItemIsEnabled)); - // visually disable by greying out - works only if combobox has been painted already and palette returns the wanted color - item->setData(disable ? ui->comboBox->palette().color(QPalette::Disabled, QPalette::Text) - : QVariant(), // clear item data in order to use default color - Qt::TextColorRole); -*/ - ui->biasControlTypeComboBox->setCurrentIndex((calibedBias)?1:0); -// sendRequest(biasVoltageRequestSig); + ui->biasControlTypeComboBox->setCurrentIndex((calibedBias) ? 1 : 0); } void MainWindow::on_biasControlTypeComboBox_currentIndexChanged(int index) { - if (index==1) { - if (calib==nullptr) return; + if (index == 1) { + if (calib == nullptr) + return; QString str = calib->getCalibParameter("COEFF0"); - if (!str.size()) return; + if (!str.size()) + return; double c0 = str.toDouble(); str = calib->getCalibParameter("COEFF1"); - if (!str.size()) return; + if (!str.size()) + return; double c1 = str.toDouble(); - biasCalibOffset=c0; biasCalibSlope=c1; - minBiasVoltage=0.; maxBiasVoltage=40.; + biasCalibOffset = c0; + biasCalibSlope = c1; + minBiasVoltage = 0.; + maxBiasVoltage = 40.; ui->biasVoltageDoubleSpinBox->setMaximum(maxBiasVoltage); ui->biasVoltageDoubleSpinBox->setSingleStep(0.1); } else { - biasCalibOffset=0.; biasCalibSlope=1.; - minBiasVoltage=0.; maxBiasVoltage=3.3; + biasCalibOffset = 0.; + biasCalibSlope = 1.; + minBiasVoltage = 0.; + maxBiasVoltage = 3.3; ui->biasVoltageDoubleSpinBox->setMaximum(maxBiasVoltage); ui->biasVoltageDoubleSpinBox->setSingleStep(0.01); } @@ -1263,28 +1187,33 @@ void MainWindow::on_biasControlTypeComboBox_currentIndexChanged(int index) void MainWindow::on_biasVoltageDoubleSpinBox_valueChanged(double arg1) { double biasVoltage = arg1; - if (fabs(biasCalibSlope)<1e-5) return; - double dacVoltage = (biasVoltage-biasCalibOffset)/biasCalibSlope; - if (dacVoltage<0.) dacVoltage=0.; - if (dacVoltage>3.3) dacVoltage=3.3; + if (fabs(biasCalibSlope) < 1e-5) + return; + double dacVoltage = (biasVoltage - biasCalibOffset) / biasCalibSlope; + if (dacVoltage < 0.) + dacVoltage = 0.; + if (dacVoltage > 3.3) + dacVoltage = 3.3; sendSetBiasVoltage(dacVoltage); } -void MainWindow::gpioInhibit(bool inhibit) { +void MainWindow::gpioInhibit(bool inhibit) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_INHIBIT); *(tcpMessage.dStream) << inhibit; emit sendTcpMessage(tcpMessage); } -void MainWindow::mqttInhibit(bool inhibit) { +void MainWindow::mqttInhibit(bool inhibit) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_MQTT_INHIBIT); *(tcpMessage.dStream) << inhibit; emit sendTcpMessage(tcpMessage); } -void MainWindow::onPolarityChanged(bool pol1, bool pol2){ +void MainWindow::onPolarityChanged(bool pol1, bool pol2) +{ TcpMessage tcpMessage(TCP_MSG_KEY::MSG_POLARITY_SWITCH); *(tcpMessage.dStream) << pol1 << pol2; emit sendTcpMessage(tcpMessage); } - diff --git a/gui/src/mainwindow.ui b/gui/src/mainwindow.ui new file mode 100644 index 00000000..e9c5a79e --- /dev/null +++ b/gui/src/mainwindow.ui @@ -0,0 +1,611 @@ + + + MainWindow + + + true + + + + 0 + 0 + 658 + 638 + + + + muondetector-gui + + + + + + + + 0 + 0 + + + + + + + + + connect to: + + + + + + + + 200 + 22 + + + + Qt::WheelFocus + + + + + + true + + + + + + QComboBox::InsertAlphabetically + + + 1 + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + connect + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + not connected + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + false + + + + + + Thresholds + + + + + + Store DAC settings + + + + + + + Channel 1 + + + + + + 1000.000000000000000 + + + 100.000000000000000 + + + 2000 + + + QwtSlider::TrailingScale + + + + + + + mV + + + 1 + + + 1000.000000000000000 + + + 0.500000000000000 + + + 100.000000000000000 + + + + + + + Set + + + + + + + + + + Channel 2 + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 1000.000000000000000 + + + 100.000000000000000 + + + 2000 + + + QwtSlider::TrailingScale + + + + + + + mV + + + 1 + + + 1000.000000000000000 + + + 0.500000000000000 + + + 100.000000000000000 + + + + + + + Set + + + + + + + + + + + + + Bias + + + + + + QFrame::Box + + + Bias OFF + + + Qt::AlignCenter + + + + + + + Enable + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + V + + + 3.300000000000000 + + + 0.010000000000000 + + + 0.700000000000000 + + + + + + + + 0 + 0 + + + + 10 + + + Qt::Horizontal + + + + + + + + Bias DAC Control + + + + + Bias Voltage + + + + + + + + + + + + 0 + 0 + + + + Event info + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + xRate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + QFrame::Box + + + XOR + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + QFrame::Box + + + AND + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + aRate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + QFrame::Box + + + Total + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 54 + 24 + + + + count + + + Qt::AlignCenter + + + + + + + + + + + + + false + + + + 1 + 0 + + + + + 16777215 + 16777215 + + + + true + + + + + + + + + + + + + + data acquisition mode + + + + + settings + + + + + + + QwtSlider + QWidget +
qwt_slider.h
+
+
+ + + + discr2Edit + valueChanged(double) + discr2Slider + setValue(double) + + + 214 + 231 + + + 204 + 163 + + + + + discr2Slider + valueChanged(double) + discr2Edit + setValue(double) + + + 204 + 163 + + + 214 + 231 + + + + + discr1Edit + valueChanged(double) + discr1Slider + setValue(double) + + + 89 + 231 + + + 79 + 163 + + + + + discr1Slider + valueChanged(double) + discr1Edit + setValue(double) + + + 79 + 163 + + + 89 + 231 + + + + +
diff --git a/source/gui/src/man/apt_cache_search.sh b/gui/src/man/apt_cache_search.sh similarity index 100% rename from source/gui/src/man/apt_cache_search.sh rename to gui/src/man/apt_cache_search.sh diff --git a/source/gui/src/man/man1/muondetector-gui.1 b/gui/src/man/man1/muondetector-gui.1 similarity index 100% rename from source/gui/src/man/man1/muondetector-gui.1 rename to gui/src/man/man1/muondetector-gui.1 diff --git a/source/gui/src/man/pack_all_man.sh b/gui/src/man/pack_all_man.sh similarity index 100% rename from source/gui/src/man/pack_all_man.sh rename to gui/src/man/pack_all_man.sh diff --git a/source/gui/src/man/unpack_all_man.sh b/gui/src/man/unpack_all_man.sh similarity index 100% rename from source/gui/src/man/unpack_all_man.sh rename to gui/src/man/unpack_all_man.sh diff --git a/gui/src/map.cpp b/gui/src/map.cpp new file mode 100644 index 00000000..b66e9f03 --- /dev/null +++ b/gui/src/map.cpp @@ -0,0 +1,40 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +Map::Map(QWidget* parent) + : QWidget(parent) + , mapUi(new Ui::Map) +{ + QVariantMap parameters; + mapUi->setupUi(this); + mapUi->quickWidget->setResizeMode(QQuickWidget::SizeRootObjectToView); + + QQmlEngine* engine = new QQmlEngine(this); + QQmlComponent* component = new QQmlComponent(engine, "qrc:/qml/CustomMap.qml"); + mapComponent = component->create(); + mapUi->quickWidget->setContent(component->url(), component, mapComponent); + mapUi->quickWidget->show(); +} + +Map::~Map() +{ + delete mapComponent; + delete mapUi; +} + +void Map::onGeodeticPosReceived(GeodeticPos pos) +{ + if (mapComponent == nullptr) { + return; + } + QMetaObject::invokeMethod(mapComponent, "setCircle", + Q_ARG(QVariant, ((double)pos.lon) * 1e-7), + Q_ARG(QVariant, ((double)pos.lat) * 1e-7), + Q_ARG(QVariant, ((double)pos.hAcc) / 1000)); +} diff --git a/source/gui/src/map.ui b/gui/src/map.ui similarity index 100% rename from source/gui/src/map.ui rename to gui/src/map.ui diff --git a/source/gui/src/parametermonitorform.cpp b/gui/src/parametermonitorform.cpp similarity index 54% rename from source/gui/src/parametermonitorform.cpp rename to gui/src/parametermonitorform.cpp index 73d9257f..ddc45812 100644 --- a/source/gui/src/parametermonitorform.cpp +++ b/gui/src/parametermonitorform.cpp @@ -1,45 +1,47 @@ -#include #include "parametermonitorform.h" #include "ui_parametermonitorform.h" #include +#include -ParameterMonitorForm::ParameterMonitorForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::ParameterMonitorForm) +ParameterMonitorForm::ParameterMonitorForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::ParameterMonitorForm) { ui->setupUi(this); + ui->adcTracePlot->setMinimumHeight(30); ui->adcTracePlot->setTitle("ADC trace"); - ui->adcTracePlot->setAxisTitle(QwtPlot::xBottom,"sample nr. since trigger"); - ui->adcTracePlot->setAxisTitle(QwtPlot::yLeft,"U / V"); + ui->adcTracePlot->setAxisTitle(QwtPlot::xBottom, "sample nr. since trigger"); + ui->adcTracePlot->setAxisTitle(QwtPlot::yLeft, "U / V"); ui->adcTracePlot->addCurve("curve1", Qt::blue); ui->adcTracePlot->curve("curve1").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); + QwtSymbol* sym = new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern), QPen(Qt::black), QSize(5, 5)); ui->adcTracePlot->curve("curve1").setSymbol(sym); ui->adcTracePlot->setAxisAutoScale(QwtPlot::xBottom, false); ui->adcTracePlot->setAxisAutoScale(QwtPlot::yLeft, false); - ui->adcTracePlot->setAxisScale(QwtPlot::xBottom, -10., 40. ); - ui->adcTracePlot->setAxisScale(QwtPlot::yLeft, 0., 3.5 ); + ui->adcTracePlot->setAxisScale(QwtPlot::xBottom, -10., 40.); + ui->adcTracePlot->setAxisScale(QwtPlot::yLeft, 0., 3.5); ui->adcTracePlot->replot(); + ui->adcTracePlot->setEnabled(false); + foreach (GpioSignalDescriptor item, GPIO_SIGNAL_MAP) { - if (item.direction==DIR_IN) ui->adcTriggerSelectionComboBox->addItem(item.name); + if (item.direction == DIR_IN) + ui->adcTriggerSelectionComboBox->addItem(item.name); } ui->timingSelectionComboBox->clear(); foreach (QString item, TIMING_MUX_SIGNAL_NAMES) { ui->timingSelectionComboBox->addItem(item); } - connect(ui->adcTraceGroupBox, &QGroupBox::clicked, this, [this](bool checked) - { - emit adcModeChanged((checked)?ADC_MODE_TRACE:ADC_MODE_PEAK); - } ); - connect( ui->preamp1EnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::preamp1EnableChanged ); - connect( ui->preamp2EnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::preamp2EnableChanged ); - connect( ui->biasEnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::biasEnableChanged ); - connect( ui->hiGainCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::gainSwitchChanged ); - connect( ui->pol1CheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::onPolarityCheckBoxClicked ); - connect( ui->pol2CheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::onPolarityCheckBoxClicked ); - - ui->adcTracePlot->setMinimumHeight(30); + connect(ui->adcTraceGroupBox, &QGroupBox::clicked, this, [this](bool checked) { + emit adcModeChanged((checked) ? ADC_SAMPLING_MODE::TRACE : ADC_SAMPLING_MODE::PEAK); + ui->adcTracePlot->setEnabled(checked); + }); + connect(ui->preamp1EnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::preamp1EnableChanged); + connect(ui->preamp2EnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::preamp2EnableChanged); + connect(ui->biasEnCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::biasEnableChanged); + connect(ui->hiGainCheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::gainSwitchChanged); + connect(ui->pol1CheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::onPolarityCheckBoxClicked); + connect(ui->pol2CheckBox, &QCheckBox::clicked, this, &ParameterMonitorForm::onPolarityCheckBoxClicked); } void ParameterMonitorForm::on_timingSelectionComboBox_currentIndexChanged(int index) @@ -49,9 +51,9 @@ void ParameterMonitorForm::on_timingSelectionComboBox_currentIndexChanged(int in void ParameterMonitorForm::on_adcTriggerSelectionComboBox_currentIndexChanged(int index) { - for (auto signalIt=GPIO_SIGNAL_MAP.begin(); signalIt!=GPIO_SIGNAL_MAP.end(); ++signalIt) { - const GPIO_SIGNAL signalId=signalIt.key(); - if (GPIO_SIGNAL_MAP[signalId].name==ui->adcTriggerSelectionComboBox->itemText(index)) { + for (auto signalIt = GPIO_SIGNAL_MAP.begin(); signalIt != GPIO_SIGNAL_MAP.end(); ++signalIt) { + const GPIO_SIGNAL signalId = signalIt.key(); + if (GPIO_SIGNAL_MAP[signalId].name == ui->adcTriggerSelectionComboBox->itemText(index)) { emit triggerSelectionChanged(signalId); return; } @@ -63,77 +65,47 @@ ParameterMonitorForm::~ParameterMonitorForm() delete ui; } -void ParameterMonitorForm::onCalibReceived(bool /*valid*/, bool /*eepromValid*/, quint64 /*id*/, const QVector & calibList) +void ParameterMonitorForm::onCalibReceived(bool /*valid*/, bool /*eepromValid*/, quint64 /*id*/, const QVector& calibList) { fCalibList.clear(); - for (int i=0; ihwVersionLabel->setText(QString::number(ver)); -/* - double rsense = 0.1*getCalibParameter("RSENSE").toInt(); - ui->rsenseDoubleSpinBox->setValue(rsense); - double vdiv = 0.01*getCalibParameter("VDIV").toInt(); - ui->vdivDoubleSpinBox->setValue(vdiv); - int eepCycles = getCalibParameter("WRITE_CYCLES").toInt(); - ui->eepromWriteCyclesLabel->setText(QString::number(eepCycles)); - int featureFlags = getCalibParameter("FEATURE_FLAGS").toInt(); - ui->featureGnssCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_GNSS); - ui->featureEnergyCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_ENERGY); - ui->featureDetBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_DETBIAS); - ui->featurePreampBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_PREAMP_BIAS); -*/ -/* - if (voltageCalibValid()) { - fSlope1 = getCalibParameter("COEFF1").toDouble(); - fOffs1 = getCalibParameter("COEFF0").toDouble(); - } - if (currentCalibValid()) { - fSlope2 = getCalibParameter("COEFF3").toDouble(); - fOffs2 = getCalibParameter("COEFF2").toDouble(); - } - updateCalibTable(); - QVector emptyList; - emit updatedCalib(emptyList); -*/ } - void ParameterMonitorForm::onAdcSampleReceived(uint8_t channel, float value) { - if (channel==0) - ui->adcLabel1->setText(QString::number(value,'f',4)); - else if (channel==1) - ui->adcLabel2->setText(QString::number(value,'f',4)); - else if (channel==2) { - ui->adcLabel3->setText(QString::number(value,'f',4)); + if (channel == 0) + ui->adcLabel1->setText(QString::number(value, 'f', 4)); + else if (channel == 1) + ui->adcLabel2->setText(QString::number(value, 'f', 4)); + else if (channel == 2) { + ui->adcLabel3->setText(QString::number(value, 'f', 4)); fLastBiasVoltageHi = value; - } - else if (channel==3) { - ui->adcLabel4->setText(QString::number(value,'f',4)); + } else if (channel == 3) { + ui->adcLabel4->setText(QString::number(value, 'f', 4)); if (!fCalibList.empty()) { - double vdiv=getCalibParameter("VDIV").toDouble()*0.01; - double ubias = value*vdiv; - ui->biasVoltageLabel->setText(QString::number(ubias,'f',2)); + double vdiv = getCalibParameter("VDIV").toDouble() * 0.01; + double ubias = value * vdiv; + ui->biasVoltageLabel->setText(QString::number(ubias, 'f', 2)); emit biasVoltageCalculated(ubias); double ioffs = 0.; if (currentCalibValid()) { double fSlope2 = getCalibParameter("COEFF3").toDouble(); double fOffs2 = getCalibParameter("COEFF2").toDouble(); - ioffs = ubias*fSlope2+fOffs2; - + ioffs = ubias * fSlope2 + fOffs2; } - double rsense = getCalibParameter("RSENSE").toDouble()*0.1/1000.; // RSense in MOhm - double ibias = (fLastBiasVoltageHi-value)*vdiv/rsense-ioffs; + double rsense = getCalibParameter("RSENSE").toDouble() * 0.1 / 1000.; // RSense in MOhm + double ibias = (fLastBiasVoltageHi - value) * vdiv / rsense - ioffs; - if (fLastBiasVoltageHi>-900.) { + if (fLastBiasVoltageHi > -900.) { emit biasCurrentCalculated(ibias); - ui->biasCurrentLabel->setText(QString::number(ibias,'f',1)); + ui->biasCurrentLabel->setText(QString::number(ibias, 'f', 1)); } } fLastBiasVoltageLo = value; @@ -150,18 +122,18 @@ void ParameterMonitorForm::onDacReadbackReceived(uint8_t channel, float value) ui->dacSlider2->blockSignals(true); ui->dacSlider3->blockSignals(true); ui->dacSlider4->blockSignals(true); - if (channel==0) { + if (channel == 0) { ui->dacSpinBox1->setValue(value); - ui->dacSlider1->setValue(value*1000); - } else if (channel==1) { + ui->dacSlider1->setValue(value * 1000); + } else if (channel == 1) { ui->dacSpinBox2->setValue(value); - ui->dacSlider2->setValue(value*1000); - } else if (channel==2) { + ui->dacSlider2->setValue(value * 1000); + } else if (channel == 2) { ui->dacSpinBox3->setValue(value); - ui->dacSlider3->setValue(value*1000); - } else if (channel==3) { + ui->dacSlider3->setValue(value * 1000); + } else if (channel == 3) { ui->dacSpinBox4->setValue(value); - ui->dacSlider4->setValue(value*1000); + ui->dacSlider4->setValue(value * 1000); } ui->dacSpinBox1->blockSignals(false); ui->dacSpinBox2->blockSignals(false); @@ -185,18 +157,22 @@ void ParameterMonitorForm::onBiasSwitchReceived(bool state) void ParameterMonitorForm::onPreampSwitchReceived(uint8_t channel, bool state) { - if (channel==0) ui->preamp1EnCheckBox->setChecked(state); - else if (channel==1) ui->preamp2EnCheckBox->setChecked(state); + if (channel == 0) + ui->preamp1EnCheckBox->setChecked(state); + else if (channel == 1) + ui->preamp2EnCheckBox->setChecked(state); } void ParameterMonitorForm::onTriggerSelectionReceived(GPIO_SIGNAL signal) { - int i=0; - while (iadcTriggerSelectionComboBox->count()) { - if (ui->adcTriggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name)==0) break; + int i = 0; + while (i < ui->adcTriggerSelectionComboBox->count()) { + if (ui->adcTriggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name) == 0) + break; i++; } - if (i>=ui->adcTriggerSelectionComboBox->count()) return; + if (i >= ui->adcTriggerSelectionComboBox->count()) + return; ui->adcTriggerSelectionComboBox->blockSignals(true); ui->adcTriggerSelectionComboBox->setEnabled(true); ui->adcTriggerSelectionComboBox->setCurrentIndex(i); @@ -215,7 +191,6 @@ void ParameterMonitorForm::onTemperatureReceived(float temp) void ParameterMonitorForm::onTimepulseReceived() { - // } void ParameterMonitorForm::onTimeMarkReceived(const UbxTimeMarkStruct& tm) @@ -223,47 +198,43 @@ void ParameterMonitorForm::onTimeMarkReceived(const UbxTimeMarkStruct& tm) ui->ubloxCounterLabel->setText(QString::number(tm.evtCounter)); } -void ParameterMonitorForm::onAdcTraceReceived(const QVector &sampleBuffer) +void ParameterMonitorForm::onAdcTraceReceived(const QVector& sampleBuffer) { QVector vec; - for (int i=0; iadcTracePlot->curve("curve1").setSamples(vec); ui->adcTracePlot->replot(); - } void ParameterMonitorForm::onTimeAccReceived(quint32 acc) { - ui->timePrecLabel->setText(QString::number(acc*1e-9, 'g', 6)); + ui->timePrecLabel->setText(QString::number(acc * 1e-9, 'g', 6)); } void ParameterMonitorForm::onFreqAccReceived(quint32 /*acc*/) -{// - +{ } void ParameterMonitorForm::onIntCounterReceived(quint32 /*cnt*/) { - //ui->ubloxCounterLabel->setText(QString::number(cnt)); } void ParameterMonitorForm::onPolaritySwitchReceived(bool pol1, bool pol2) { - ui->pol1CheckBox->blockSignals(true); - ui->pol2CheckBox->blockSignals(true); - ui->pol1CheckBox->setChecked(pol1); - ui->pol2CheckBox->setChecked(pol2); - ui->pol1CheckBox->blockSignals(false); - ui->pol2CheckBox->blockSignals(false); + ui->pol1CheckBox->blockSignals(true); + ui->pol2CheckBox->blockSignals(true); + ui->pol1CheckBox->setChecked(pol1); + ui->pol2CheckBox->setChecked(pol2); + ui->pol1CheckBox->blockSignals(false); + ui->pol2CheckBox->blockSignals(false); } - void ParameterMonitorForm::on_dacSpinBox1_valueChanged(double arg1) { emit setDacVoltage(0, arg1); @@ -286,32 +257,32 @@ void ParameterMonitorForm::on_dacSpinBox4_valueChanged(double arg1) void ParameterMonitorForm::on_dacSlider1_valueChanged(int value) { - double voltage = value/1000.; + double voltage = value / 1000.; emit setDacVoltage(0, voltage); } void ParameterMonitorForm::on_dacSlider2_valueChanged(int value) { - double voltage = value/1000.; + double voltage = value / 1000.; emit setDacVoltage(1, voltage); } void ParameterMonitorForm::on_dacSlider3_valueChanged(int value) { - double voltage = value/1000.; + double voltage = value / 1000.; emit setDacVoltage(2, voltage); } void ParameterMonitorForm::on_dacSlider4_valueChanged(int value) { - double voltage = value/1000.; + double voltage = value / 1000.; emit setDacVoltage(3, voltage); } -QString ParameterMonitorForm::getCalibParameter(const QString &name) +QString ParameterMonitorForm::getCalibParameter(const QString& name) { if (!fCalibList.empty()) { - auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); + auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s) { return s.name == name.toStdString(); }); if (result != fCalibList.end()) { return QString::fromStdString(result->value); } @@ -322,24 +293,29 @@ QString ParameterMonitorForm::getCalibParameter(const QString &name) bool ParameterMonitorForm::currentCalibValid() { int calibFlags = getCalibParameter("CALIB_FLAGS").toUInt(); - if (calibFlags & CalibStruct::CALIBFLAGS_CURRENT_COEFFS) return true; + if (calibFlags & CalibStruct::CALIBFLAGS_CURRENT_COEFFS) + return true; return false; } void ParameterMonitorForm::on_gpioInhibitCheckBox_clicked(bool checked) { emit gpioInhibitChanged(checked); -// qDebug()<<"set inhibit to "<pol1CheckBox->isChecked(); - bool pol2=ui->pol2CheckBox->isChecked(); +void ParameterMonitorForm::onPolarityCheckBoxClicked(bool /*checked*/) +{ + bool pol1 = ui->pol1CheckBox->isChecked(); + bool pol2 = ui->pol2CheckBox->isChecked(); emit polarityChanged(pol1, pol2); } void ParameterMonitorForm::onUiEnabledStateChange(bool connected) { - this->setEnabled(connected); + if (connected) { + ui->adcTracePlot->setEnabled(ui->adcTraceGroupBox->isChecked()); + } else { + ui->adcTracePlot->setEnabled(false); + } + this->setEnabled(connected); } diff --git a/source/gui/src/parametermonitorform.ui b/gui/src/parametermonitorform.ui old mode 100644 new mode 100755 similarity index 96% rename from source/gui/src/parametermonitorform.ui rename to gui/src/parametermonitorform.ui index b5306524..55bb17a3 --- a/source/gui/src/parametermonitorform.ui +++ b/gui/src/parametermonitorform.ui @@ -7,7 +7,7 @@ 0 0 613 - 620 + 607 @@ -26,6 +26,12 @@ Form + + 4 + + + 4 + @@ -50,6 +56,12 @@ ADC + + 6 + + + 6 + @@ -405,30 +417,6 @@ - - - - - 0 - 0 - - - - Pulse View - - - true - - - false - - - - - - - - @@ -453,8 +441,20 @@ DAC + + 6 + + + 6 + + + 4 + + + 4 + @@ -556,6 +556,9 @@ + + 4 + @@ -651,6 +654,9 @@ + + 4 + @@ -746,6 +752,9 @@ + + 4 + @@ -842,7 +851,33 @@ - + + + + Qt::Vertical + + + + 20 + 2 + + + + + + + + Qt::Vertical + + + + 20 + 2 + + + + + @@ -854,20 +889,14 @@ Switches - - - - - 9 - - - - SiPM Bias Enabled - - - + + 4 + + + 4 + @@ -934,11 +963,78 @@ - + + + + 4 + + + + + + 9 + + + + ADC Trigger + + + Qt::AlignBottom|Qt::AlignHCenter + + + + + + + + 9 + + + + + + + + + + + 9 + + + + GPIO Inhibit + + + + + + + + 9 + + + + Peak Det Hi Gain + + + + + + + + 9 + + + + SiPM Bias Enabled + + + + - 0 + 130 0 @@ -961,10 +1057,10 @@ - 0 + 10 30 - 127 - 80 + 111 + 81 @@ -1088,57 +1184,10 @@ Bias
- - - - - - - 9 - - - - ADC Trigger - - - Qt::AlignBottom|Qt::AlignHCenter - - - - - - - - 9 - - - - - - - - - - GPIO Inhibit - - - - - - - - 9 - - - - Peak Det Hi Gain - - - - + QFrame::StyledPanel @@ -1147,6 +1196,12 @@ Bias QFrame::Raised + + 8 + + + 8 + @@ -1646,31 +1701,29 @@ Bias - - - - Qt::Vertical + + + + + 0 + 0 + - - - 20 - 6 - + + Pulse View - - - - - - Qt::Vertical + + true - - - 20 - 6 - + + false - + + + + + + diff --git a/gui/src/plotcustom.cpp b/gui/src/plotcustom.cpp new file mode 100644 index 00000000..22a9fc2f --- /dev/null +++ b/gui/src/plotcustom.cpp @@ -0,0 +1,163 @@ +#include +#include +#include +#include +#include +#include +#include + +class TimeScaleDraw : public QwtScaleDraw { +public: + TimeScaleDraw(const QTime& base, const bool invert = true) + : invertValues(invert) + , baseTime(base) + { + } + virtual QwtText label(qreal v) const + { + if (invertValues) { + QTime upTime = baseTime.addSecs(-(int)v); + return QString("- " + upTime.toString()); + } else { + QTime upTime = baseTime.addSecs((int)v); + return QString(upTime.toString()); + } + } + +private: + bool invertValues; + QTime baseTime; +}; + +void PlotCustom::initialize() +{ + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + setStyleSheet("background-color: white; border: 0px;"); + setAutoReplot(false); + enableAxis(QwtPlot::yLeft, false); + enableAxis(QwtPlot::yRight, true); + setAxisAutoScale(QwtPlot::yRight, true); + + QwtLegend* legend = new QwtLegend(this); + legend->setDefaultItemMode(QwtLegendData::Checkable); + this->insertLegend(legend, QwtPlot::BottomLegend); + + const QPen grayPen(Qt::gray); + grid.setPen(grayPen); + grid.attach(this); + + xorCurve.setAxes(QwtPlot::xBottom, QwtPlot::yRight); + xorCurve.setRenderHint(QwtPlotCurve::RenderAntialiased, true); + QColor xorCurveColor = Qt::darkGreen; + xorCurveColor.setAlphaF(0.3); + const QPen greenPen(xorCurveColor); + xorCurve.setTitle(QwtText("xor-curve")); + xorCurve.setPen(greenPen); + xorCurve.setBrush(xorCurveColor); + xorCurve.attach(this); + + andCurve.setTitle(QwtText("and-curve")); + andCurve.setAxes(QwtPlot::xBottom, QwtPlot::yRight); + andCurve.setRenderHint(QwtPlotCurve::RenderAntialiased, true); + QColor andCurveColor = Qt::darkBlue; + andCurveColor.setAlphaF(0.3); + const QPen bluePen(andCurveColor); + andCurve.setPen(bluePen); + andCurve.setBrush(andCurveColor); + andCurve.attach(this); + connect(legend, &QwtLegend::checked, this, [this](const QVariant& itemInfo, bool on, int /*index*/) { + if (on) { + if (itemInfo == "xor-curve") { + xorCurve.show(); + } + if (itemInfo == "xor-curve") { + andCurve.show(); + } + } else { + if (itemInfo == "xor-curve") { + xorCurve.hide(); + } + if (itemInfo == "xor-curve") { + andCurve.hide(); + } + } + this->replot(); + }); + legend->checked(QString(""), true, 0); + legend->checked(QString(""), true, 1); + replot(); + show(); +} + +void PlotCustom::plotSamples(QVector& samples, QwtPlotCurve& curve) +{ + if (!isEnabled()) + return; + QVector someSamples; + for (auto sample : samples) { + someSamples.push_back(sample); + someSamples.last().setX(sample.x() - samples.at(samples.size() - 1).x()); + } + + qreal xMin = 0.0; + qreal xMax = 0.0; + if (!someSamples.isEmpty()) { + xMin = someSamples.first().x(); + } + qreal step = (double)(int)((xMax - xMin) / 6); + if (this->size().width() < 450) { + step = (double)(int)((xMax - xMin) / 3); + } + setAxisScale(QwtPlot::xBottom, xMin, xMax, step); + QwtPointSeriesData* dat = new QwtPointSeriesData(someSamples); + curve.setData(dat); + replot(); +} + +void PlotCustom::plotXorSamples(QVector& xorSamples) +{ + setPreset(""); + plotSamples(xorSamples, xorCurve); +} + +void PlotCustom::plotAndSamples(QVector& andSamples) +{ + setPreset(""); + plotSamples(andSamples, andCurve); +} + +void PlotCustom::setPreset(QString preset) +{ + if (!preset.isEmpty()) { + xAxisPreset = preset; + } + if (xAxisPreset == "seconds") { + setAxisScaleDraw(QwtPlot::xBottom, new QwtScaleDraw()); + } + if (xAxisPreset == "hh:mm:ss") { + setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw(QTime(0, 0, 0, 0), true)); + } + if (xAxisPreset == "time") { + setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw(QTime::currentTime(), false)); + } + replot(); +} + +void PlotCustom::setStatusEnabled(bool status) +{ + if (status == true) { + xorCurve.attach(this); + andCurve.attach(this); + const QPen blackPen(Qt::black); + grid.setPen(blackPen); + setTitle(title); + replot(); + } else { + xorCurve.detach(); + andCurve.detach(); + const QPen grayPen(Qt::gray); + grid.setPen(grayPen); + setTitle(""); + replot(); + } +} diff --git a/gui/src/scanform.cpp b/gui/src/scanform.cpp new file mode 100644 index 00000000..cbf7d0d3 --- /dev/null +++ b/gui/src/scanform.cpp @@ -0,0 +1,319 @@ +#include "scanform.h" +#include "ui_scanform.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +constexpr double EPSILON { 1e-9 }; + +ScanForm::ScanForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::ScanForm) +{ + ui->setupUi(this); + ui->scanParComboBox->clear(); + foreach (QString item, SP_NAMES) { + ui->scanParComboBox->addItem(item); + } + ui->observableComboBox->clear(); + foreach (QString item, OP_NAMES) { + ui->observableComboBox->addItem(item); + } + ui->minRangeLineEdit->setValidator(new QDoubleValidator(.001, 3.3, 4, ui->minRangeLineEdit)); + ui->maxRangeLineEdit->setValidator(new QDoubleValidator(.001, 3.3, 4, ui->maxRangeLineEdit)); + ui->stepSizeLineEdit->setValidator(new QDoubleValidator(0., 1.0, 5, ui->stepSizeLineEdit)); + + ui->scanPlot->setTitle("Parameter Scan"); + ui->scanPlot->setAxisTitle(QwtPlot::xBottom, "scanpar"); + ui->scanPlot->setAxisTitle(QwtPlot::yLeft, "observable"); + + ui->scanPlot->addCurve("parscan", Qt::blue); + ui->scanPlot->curve("parscan").setStyle(QwtPlotCurve::NoCurve); + QwtSymbol* sym = new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern), QPen(Qt::black), QSize(5, 5)); + ui->scanPlot->curve("parscan").setSymbol(sym); + + ui->scanPlot->setAxisAutoScale(QwtPlot::xBottom, true); + ui->scanPlot->setAxisAutoScale(QwtPlot::yLeft, true); + //ui->scanPlot->replot(); + ui->scanPlot->setEnabled(false); + + connect(ui->exportDataPushButton, &QPushButton::clicked, this, &ScanForm::exportData); + ui->exportDataPushButton->setEnabled(false); + ui->currentScanGroupBox->setEnabled(false); + ui->scanProgressBar->reset(); +} + +ScanForm::~ScanForm() +{ + delete ui; +} + +void ScanForm::onDacReadbackReceived(uint8_t channel, float value) +{ + if (channel > 3 || active) + return; + fLastDacs[channel] = value; +} + +void ScanForm::onTimeMarkReceived(const UbxTimeMarkStruct& tm) +{ + if (!tm.risingValid) { + std::cerr << "received invalid timemark"; + return; + } + if (active && OP_NAMES[obsPar] == "UBXRATE") { + if (waitForFirst) { + currentCounts = 0; + currentTimeInterval = 0.; + waitForFirst = false; + } else { + currentCounts += (uint16_t)(tm.evtCounter - lastTM.evtCounter); + double interval = (tm.rising.tv_nsec - lastTM.rising.tv_nsec) * 1e-9; + interval += tm.rising.tv_sec - lastTM.rising.tv_sec; + currentTimeInterval += interval; + if ((currentTimeInterval > maxMeasurementTimeInterval) + || ((currentCounts > maxMeasurementStatistics) + && (currentTimeInterval > 1))) { + scanParIteration(); + } + } + } + lastTM = tm; +} + +void ScanForm::scanParIteration() +{ + if (!active) + return; + if (OP_NAMES[obsPar] == "UBXRATE") { + double rate = currentCounts / currentTimeInterval; + scanData[currentScanPar].value = rate; + scanData[currentScanPar].error = std::sqrt(currentCounts) / currentTimeInterval; + ui->currentScanparLabel->setText(QString::number(currentScanPar)); + ui->currentObservableLabel->setText(QString::number(rate) + " +- " + QString::number(scanData[currentScanPar].error)); + updateScanPlot(); + } + currentScanPar += stepSize; + if ( currentScanPar > maxRange + EPSILON ) { + // measurement finished + finishScan(); + return; + } + adjustScanPar(SP_NAMES[scanPar], currentScanPar); + ui->scanProgressBar->setValue(std::lround((currentScanPar - minRange) / stepSize)); + waitForFirst = true; +} + +void ScanForm::adjustScanPar(QString scanParName, double value) +{ + if (scanParName == "THR1") { + emit setThresholdVoltage(0, value); + } else if (scanParName == "THR2") { + emit setThresholdVoltage(1, value); + } else if (scanParName == "BIAS") { + emit setBiasControlVoltage(value); + } else return; + QThread::msleep(100); +} + +void ScanForm::on_scanParComboBox_currentIndexChanged(int index) +{ + if ( index < 0 || index >= SP_NAMES.size() ) return; + if (SP_NAMES[index] == "TIME") { + ui->minRangeLineEdit->setEnabled(false); + ui->maxRangeLineEdit->setEnabled(false); + //ui->stepSizeLineEdit->setEnabled(false); + ui->activateNrMeasurementsCheckBox->setChecked(true); + ui->limitStatisticsCheckBox->setEnabled(false); + ui->maxStatisticsComboBox->setEnabled(false); + } else { + ui->minRangeLineEdit->setEnabled(true); + ui->maxRangeLineEdit->setEnabled(true); + //ui->stepSizeLineEdit->setEnabled(true); + ui->limitStatisticsCheckBox->setEnabled(true); + ui->maxStatisticsComboBox->setEnabled(ui->limitStatisticsCheckBox->isChecked()); + } +} + +void ScanForm::on_scanStartPushButton_clicked() +{ + if (active) { + finishScan(); + return; + } + + maxMeasurementTimeInterval = ui->timeIntervalSpinBox->value(); + + bool ok = false; + minRange = ui->minRangeLineEdit->text().toDouble(&ok); + if (!ok) + return; + maxRange = ui->maxRangeLineEdit->text().toDouble(&ok); + if (!ok) + return; + if ( ui->activateNrMeasurementsCheckBox->isChecked() ) { + if ( ui->nrMeasurementSpinBox->value() < 2 ) { + stepSize = maxRange + 2. * EPSILON; + } else { + stepSize = ( maxRange - minRange ) / ( ui->nrMeasurementSpinBox->value() - 1 ); + } + } else { + stepSize = ui->stepSizeLineEdit->text().toDouble(&ok); + if (!ok) + return; + } + + scanPar = ui->scanParComboBox->currentIndex(); + if (SP_NAMES[scanPar] == "VOID") { + return; + } + obsPar = ui->observableComboBox->currentIndex(); + if (OP_NAMES[obsPar] == "VOID") { + return; + } + if (ui->limitStatisticsCheckBox->isChecked()) { + int power = ui->maxStatisticsComboBox->currentIndex() + 1; + maxMeasurementStatistics = std::pow(10, power); + } else { + maxMeasurementStatistics = std::numeric_limits::max(); + } + if (SP_NAMES[scanPar] == "TIME") { + minRange = 0.; + maxRange = maxMeasurementTimeInterval * ( ui->nrMeasurementSpinBox->value() - 1 ); + stepSize = maxMeasurementTimeInterval; + } + + if (OP_NAMES[obsPar] == "UBXRATE") { + emit gpioInhibitChanged(true); + emit mqttInhibitChanged(true); + } + // values seem to be valid + // start the scan + ui->scanStartPushButton->setText(tr("Stop Scan")); + currentScanPar = minRange; + adjustScanPar(SP_NAMES[scanPar], currentScanPar); + + active = true; + waitForFirst = true; + scanData.clear(); + ui->scanProgressBar->setRange(0, 1 + std::lround(std::abs(maxRange - minRange) / stepSize)); + ui->scanProgressBar->setValue(0); + ui->currentScanGroupBox->setEnabled(true); + ui->scanparNameLabel->setText(SP_NAMES[scanPar]); + ui->observableNameLabel->setText(OP_NAMES[obsPar]); + ui->currentScanparLabel->setText(QString::number(minRange)); + ui->currentObservableLabel->setText("---"); +} + +void ScanForm::finishScan() +{ + ui->scanStartPushButton->setText(tr("Start Scan")); + if (scanPar > 0) + adjustScanPar(SP_NAMES[scanPar], fLastDacs[scanPar - 1]); + active = false; + emit gpioInhibitChanged(false); + emit mqttInhibitChanged(false); + updateScanPlot(); + ui->exportDataPushButton->setEnabled(true); + ui->currentScanGroupBox->setEnabled(false); + ui->scanProgressBar->reset(); +} + +void ScanForm::updateScanPlot() +{ + QVector vec; + for (auto it = scanData.constBegin(); it != scanData.constEnd(); ++it) { + QPointF p1; + if (!plotDifferential) { + p1.rx() = it.key(); + p1.ry() = it.value().value; + } else { + if (it == --scanData.constEnd()) + continue; + p1.rx() = it.key(); + auto it2 = it; + ++it2; + p1.ry() = it.value().value - it2.value().value; + if (ui->scanPlot->getLogY() && p1.ry() <= 0.) + continue; + } + vec.push_back(p1); + } + + ui->scanPlot->curve("parscan").setSamples(vec); + ui->scanPlot->replot(); +} + +void ScanForm::on_plotDifferentialCheckBox_toggled(bool checked) +{ + plotDifferential = checked; + updateScanPlot(); +} + +void ScanForm::onUiEnabledStateChange(bool connected) +{ + if (connected) { + } else { + if (active) + finishScan(); + } + this->setEnabled(connected); + ui->scanPlot->setEnabled(connected); +} + +void ScanForm::exportData() +{ + QString types("ASCII raw data (*.txt)"); + QString filter; // Type of filter + QString txtExt = ".txt"; + QString suggestedName = ""; + QString fn = QFileDialog::getSaveFileName(this, tr("Export Plot"), + suggestedName, types, &filter); + + if (!fn.isEmpty()) { // If filename is not null + if (fn.contains(txtExt)) { + fn.remove(txtExt); + } + + if (filter.contains(txtExt)) { + fn += txtExt; + // export histo in asci raw data format + QFile file(fn); + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) + return; + QTextStream out(&file); + + out << "# Parameter Scan\n"; + out << "# scanparValue measValue measError diffMeasValue diffMeasError temp\n"; + for (auto it = scanData.constBegin(); it != scanData.constEnd(); ++it) { + double x = it.key(); + ScanPoint point1 = it.value(); + ScanPoint point2 {}; + bool hasSuccessor { false }; + if (it != --scanData.constEnd()) { + hasSuccessor = true; + auto it2 = it; + ++it2; + point2 = it2.value(); + } + out << QString::number(x, 'g', 10) << " " + << QString::number(point1.value, 'g', 10) << " " + << QString::number(point1.error, 'g', 10) << " "; + + if (hasSuccessor) { + out << QString::number(point1.value - point2.value, 'g', 10) << " " + << QString::number(point1.error + point2.error, 'g', 10) << " "; + } else { + out << "0 0 "; + } + out << QString::number(point1.temp, 'g', 10) << "\n"; + } + } + } +} diff --git a/gui/src/scanform.ui b/gui/src/scanform.ui new file mode 100644 index 00000000..919896c2 --- /dev/null +++ b/gui/src/scanform.ui @@ -0,0 +1,532 @@ + + + ScanForm + + + + 0 + 0 + 608 + 420 + + + + Form + + + + + + Qt::Horizontal + + + + + + + Parameters && Range + + + + + + + + + + Observable + + + + + + + + UBX Rate + + + + + GPIO Rate + + + + + + + + + + + + Scan Parameter + + + + + + + + THR1 + + + + + THR2 + + + + + + + + + + + + Scan Range from: + + + + + + + 0 + + + + + + + to: + + + + + + + 1 + + + + + + + + + + + + + Step Size + + + + + + + + 60 + 0 + + + + 0.005 + + + + + + + + + + + Nr of Points + + + + + + + false + + + 1 + + + 10000000 + + + 10 + + + + + + + + + + + + + + 0 + 0 + + + + Meas.Time Interval + + + + + + + 1 + + + 10000 + + + + + + + s + + + + + + + + + + + limit statistics + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + max counts: + + + + + + + false + + + 2 + + + + 10 + + + + + 100 + + + + + 1k + + + + + 10k + + + + + 100k + + + + + 1M + + + + + 10M + + + + + 100M + + + + + 1G + + + + + 10G + + + + + 100G + + + + + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 18 + + + + + + + + Start Scan + + + + + + + + + false + + + Current Scan + + + + + + + + Scan Par + + + Qt::AlignCenter + + + + + + + + 11 + + + + QFrame::Panel + + + N/A + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 93 + 20 + + + + + + + + + + Observable + + + Qt::AlignCenter + + + + + + + + 11 + + + + QFrame::Panel + + + N/A + + + false + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 93 + 20 + + + + + + + + + + + 0 + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + + + differential + + + + + + + export data + + + + + + + + + + + + CustomPlot + QWidget +
custom_plot_widget.h
+ 1 +
+
+ + + + limitStatisticsCheckBox + toggled(bool) + maxStatisticsComboBox + setEnabled(bool) + + + 83 + 176 + + + 295 + 176 + + + + + activateNrMeasurementsCheckBox + toggled(bool) + nrMeasurementSpinBox + setEnabled(bool) + + + 218 + 153 + + + 323 + 153 + + + + + activateNrMeasurementsCheckBox + toggled(bool) + stepSizeLineEdit + setDisabled(bool) + + + 218 + 153 + + + 125 + 153 + + + + +
diff --git a/source/gui/src/settings.cpp b/gui/src/settings.cpp similarity index 58% rename from source/gui/src/settings.cpp rename to gui/src/settings.cpp index c6f447ff..2d874d1a 100644 --- a/source/gui/src/settings.cpp +++ b/gui/src/settings.cpp @@ -1,82 +1,61 @@ +#include #include -#include #include -#include - +#include -Settings::Settings(QWidget *parent) : QDialog(parent), -ui(new Ui::Settings) +Settings::Settings(QWidget* parent) + : QDialog(parent) + , ui(new Ui::Settings) { ui->setupUi(this); ui->ubloxSignalStates->setColumnCount(2); ui->ubloxSignalStates->verticalHeader()->setVisible(false); ui->ubloxSignalStates->setShowGrid(false); ui->ubloxSignalStates->setAlternatingRowColors(true); - ui->ubloxSignalStates->setHorizontalHeaderLabels(QStringList({"Signature","Update Rate"})); + ui->ubloxSignalStates->setHorizontalHeaderLabels(QStringList({ "Signature", "Update Rate" })); ui->ubloxSignalStates->horizontalHeader()->setSectionResizeMode(QHeaderView::Fixed); connect(ui->settingsButtonBox, &QDialogButtonBox::clicked, this, &Settings::onSettingsButtonBoxClicked); connect(ui->ubloxSignalStates, &QTableWidget::itemChanged, this, &Settings::onItemChanged); ui->ubloxSignalStates->blockSignals(true); - connect(ui->gnssConfigButtonGroup, static_cast(&QButtonGroup::buttonClicked), this, [this](int) - { - this->fGnssConfigChanged=true; - this->onConfigChanged(); -/* - this->ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setEnabled(true); - this->ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setEnabled(true); -*/ - } ); - connect(ui->tpConfigButtonGroup, static_cast(&QButtonGroup::buttonClicked), this, [this](int) - { - this->fTpConfigChanged=true; - this->onConfigChanged(); -/* - this->fTpConfigChanged=true; - this->ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setEnabled(true); - this->ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setEnabled(true); -*/ - } ); -/* - connect(ui->syncedPulseGroupBox, &QGroupBox::toggled, this, [this](bool) { - this->fTpConfigChanged=true; + connect(ui->gnssConfigButtonGroup, static_cast(&QButtonGroup::buttonClicked), this, [this](int) { + this->fGnssConfigChanged = true; this->onConfigChanged(); }); - connect(ui->unsyncedPulseGroupBox, &QGroupBox::toggled, this, [this](bool) { - this->fTpConfigChanged=true; + connect(ui->tpConfigButtonGroup, static_cast(&QButtonGroup::buttonClicked), this, [this](int) { + this->fTpConfigChanged = true; this->onConfigChanged(); }); -*/ this->setDisabled(true); emit sendRequestUbxMsgRates(); } - void Settings::onConfigChanged() { - this->fTpConfigChanged=true; + this->fTpConfigChanged = true; this->ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setEnabled(true); this->ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setEnabled(true); } - -void Settings::onItemChanged(QTableWidgetItem *item){ +void Settings::onItemChanged(QTableWidgetItem* item) +{ ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setEnabled(true); ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setEnabled(true); - if (item->column()==0){ + if (item->column() == 0) { return; } bool ok = false; - if (item->text().toInt(&ok)!=((UbxMsgRateTableItem*)item)->rate){ - if(!ok){ + if (item->text().toInt(&ok) != ((UbxMsgRateTableItem*)item)->rate) { + if (!ok) { qDebug() << "rate is no integer"; } - ui->ubloxSignalStates->item(item->row(),0)->setCheckState(Qt::Unchecked); - }else{ - ui->ubloxSignalStates->item(item->row(),0)->setCheckState(Qt::Checked); + ui->ubloxSignalStates->item(item->row(), 0)->setCheckState(Qt::Unchecked); + } else { + ui->ubloxSignalStates->item(item->row(), 0)->setCheckState(Qt::Checked); } } -void Settings::addUbxMsgRates(QMap ubxMsgRates) { +void Settings::addUbxMsgRates(QMap ubxMsgRates) +{ ui->ubloxSignalStates->clearContents(); ui->ubloxSignalStates->setRowCount(0); ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(true); @@ -84,22 +63,21 @@ void Settings::addUbxMsgRates(QMap ubxMsgRates) { ui->ubloxSignalStates->blockSignals(true); oldSettings = ubxMsgRates; for (QMap::iterator it = ubxMsgRates.begin(); it != ubxMsgRates.end(); it++) { - UbxMsgRateTableItem *item = new UbxMsgRateTableItem(); - UbxMsgRateTableItem *value = new UbxMsgRateTableItem(); + UbxMsgRateTableItem* item = new UbxMsgRateTableItem(); + UbxMsgRateTableItem* value = new UbxMsgRateTableItem(); item->setCheckState(Qt::CheckState::Checked); item->setFlags(item->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user item->setFlags(item->flags() & (~Qt::ItemIsEditable)); item->key = it.key(); item->name = ubxMsgKeyNameMap.value(it.key()); item->setText(item->name); - item->setSizeHint(QSize(120,24)); + item->setSizeHint(QSize(120, 24)); value->key = it.key(); value->rate = it.value(); value->setText(QString::number(value->rate).rightJustified(3, '0')); - //item->setText(QString(item->name)); ui->ubloxSignalStates->insertRow(ui->ubloxSignalStates->rowCount()); - ui->ubloxSignalStates->setItem(ui->ubloxSignalStates->rowCount()-1,0,item); - ui->ubloxSignalStates->setItem(ui->ubloxSignalStates->rowCount()-1,1,value); + ui->ubloxSignalStates->setItem(ui->ubloxSignalStates->rowCount() - 1, 0, item); + ui->ubloxSignalStates->setItem(ui->ubloxSignalStates->rowCount() - 1, 1, value); // I don't know why item gets (sometimes) uncheckd when transfered to the TableView // it seems to work now though: item->setCheckState(Qt::CheckState::Checked); @@ -107,55 +85,55 @@ void Settings::addUbxMsgRates(QMap ubxMsgRates) { ui->ubloxSignalStates->blockSignals(false); ui->ubloxSignalStates->resizeColumnsToContents(); ui->ubloxSignalStates->resizeRowsToContents(); - ui->ubloxSignalStates->setColumnWidth(0,143); - ui->ubloxSignalStates->setColumnWidth(1,100); + ui->ubloxSignalStates->setColumnWidth(0, 143); + ui->ubloxSignalStates->setColumnWidth(1, 100); } -void Settings::onSettingsButtonBoxClicked(QAbstractButton *button){ - if (button == ui->settingsButtonBox->button(QDialogButtonBox::Apply)){ +void Settings::onSettingsButtonBoxClicked(QAbstractButton* button) +{ + if (button == ui->settingsButtonBox->button(QDialogButtonBox::Apply)) { ui->ubloxSignalStates->blockSignals(true); QMap changedSettings; - for (int i=0; i < ui->ubloxSignalStates->rowCount(); i++){ - UbxMsgRateTableItem *item = (UbxMsgRateTableItem*)ui->ubloxSignalStates->item(i,0); - if (item->checkState()==Qt::Checked){ + for (int i = 0; i < ui->ubloxSignalStates->rowCount(); i++) { + UbxMsgRateTableItem* item = (UbxMsgRateTableItem*)ui->ubloxSignalStates->item(i, 0); + if (item->checkState() == Qt::Checked) { continue; } - UbxMsgRateTableItem *value = (UbxMsgRateTableItem*)ui->ubloxSignalStates->item(i,1); + UbxMsgRateTableItem* value = (UbxMsgRateTableItem*)ui->ubloxSignalStates->item(i, 1); bool ok = false; int newRate = value->text().toInt(&ok); - if (ok && value->rate != newRate){ - changedSettings.insert(value->key, newRate); + if (ok && value->rate != newRate) { + changedSettings.insert(value->key, newRate); } } - if (changedSettings.size()>0){ + if (changedSettings.size() > 0) { emit sendSetUbxMsgRateChanges(changedSettings); } else if (fGnssConfigChanged) { - fGnssConfigChanged=false; + fGnssConfigChanged = false; writeGnssConfig(); } else if (fTpConfigChanged) { - fTpConfigChanged=false; + fTpConfigChanged = false; writeTpConfig(); } ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(true); ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(true); ui->ubloxSignalStates->blockSignals(false); } - if (button == ui->settingsButtonBox->button(QDialogButtonBox::Discard)){ + if (button == ui->settingsButtonBox->button(QDialogButtonBox::Discard)) { onTP5Received(fTpConfig); ui->ubloxSignalStates->blockSignals(true); emit sendRequestUbxMsgRates(); ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(true); ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(true); } - if (button == ui->settingsButtonBox->button(QDialogButtonBox::RestoreDefaults)){ - //settingsUi->ubloxSignalStates->blockSignals(true); + if (button == ui->settingsButtonBox->button(QDialogButtonBox::RestoreDefaults)) { emit sendUbxConfigDefault(); - } } -void Settings::onUiEnabledStateChange(bool connected){ - if (connected){ +void Settings::onUiEnabledStateChange(bool connected) +{ + if (connected) { this->setEnabled(true); ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(true); ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(true); @@ -196,7 +174,7 @@ void Settings::onTxBufReceived(quint8 val) void Settings::onTxBufPeakReceived(quint8 val) { - ui->txPeakLabel->setText("max: "+QString::number(val)+"%"); + ui->txPeakLabel->setText("max: " + QString::number(val) + "%"); } void Settings::onRxBufReceived(quint8 val) @@ -206,34 +184,33 @@ void Settings::onRxBufReceived(quint8 val) void Settings::onRxBufPeakReceived(quint8 val) { - ui->rxPeakLabel->setText("max: "+QString::number(val)+"%"); + ui->rxPeakLabel->setText("max: " + QString::number(val) + "%"); } -//const QString GNSS_ID_STRING[] = { " GPS","SBAS"," GAL","BEID","IMES","QZSS","GLNS"," N/A" }; -void Settings::onGnssConfigsReceived(quint8 numTrkCh, const QVector &configList) +void Settings::onGnssConfigsReceived(quint8 numTrkCh, const QVector& configList) { ui->gnssConfigButtonGroup->blockSignals(true); ui->numTrkChannelsLabel->setText(QString::number(numTrkCh)); - for (int i=0; ignssGpsCheckBox->setEnabled(true); ui->gnssGpsCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==1) { // SBAS + } else if (configList[i].gnssId == 1) { // SBAS ui->gnssSbasCheckBox->setEnabled(true); ui->gnssSbasCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==2) { // GAL + } else if (configList[i].gnssId == 2) { // GAL ui->gnssGalCheckBox->setEnabled(true); ui->gnssGalCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==3) { // BEID + } else if (configList[i].gnssId == 3) { // BEID ui->gnssBeidCheckBox->setEnabled(true); ui->gnssBeidCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==4) { // IMES + } else if (configList[i].gnssId == 4) { // IMES ui->gnssImesCheckBox->setEnabled(true); ui->gnssImesCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==5) { // QZSS + } else if (configList[i].gnssId == 5) { // QZSS ui->gnssQzssCheckBox->setEnabled(true); ui->gnssQzssCheckBox->setChecked(configList[i].flags & 0x01); - } else if (configList[i].gnssId==6) { // GLNS + } else if (configList[i].gnssId == 6) { // GLNS ui->gnssGlnsCheckBox->setEnabled(true); ui->gnssGlnsCheckBox->setChecked(configList[i].flags & 0x01); } @@ -244,9 +221,9 @@ void Settings::onGnssConfigsReceived(quint8 numTrkCh, const QVectorsettingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(true); } -void Settings::onTP5Received(const UbxTimePulseStruct &tp) +void Settings::onTP5Received(const UbxTimePulseStruct& tp) { - fTpConfig=tp; + fTpConfig = tp; ui->tpConfigButtonGroup->blockSignals(true); ui->syncedPulseGroupBox->blockSignals(true); ui->unsyncedPulseGroupBox->blockSignals(true); @@ -260,12 +237,10 @@ void Settings::onTP5Received(const UbxTimePulseStruct &tp) ui->tpActiveCheckBox->setChecked(tp.flags & UbxTimePulseStruct::ACTIVE); ui->lockGpsCheckBox->setChecked(tp.flags & UbxTimePulseStruct::LOCK_GPS); - //ui->syncedPulseGroupBox->setChecked(tp.flags & UbxTimePulseStruct::LOCK_GPS); ui->lockOtherCheckBox->setChecked(tp.flags & UbxTimePulseStruct::LOCK_OTHER); - //ui->unsyncedPulseGroupBox->setChecked(tp.flags & UbxTimePulseStruct::LOCK_OTHER); - ui->timeGridComboBox->setCurrentIndex((tp.flags & UbxTimePulseStruct::GRID_UTC_GPS)>>7); + ui->timeGridComboBox->setCurrentIndex((tp.flags & UbxTimePulseStruct::GRID_UTC_GPS) >> 7); ui->tpPolarityCheckBox->setChecked((tp.flags & UbxTimePulseStruct::POLARITY)); ui->tpAlignTowCheckBox->setChecked((tp.flags & UbxTimePulseStruct::ALIGN_TO_TOW)); ui->tpConfigButtonGroup->blockSignals(false); @@ -273,97 +248,119 @@ void Settings::onTP5Received(const UbxTimePulseStruct &tp) ui->unsyncedPulseGroupBox->blockSignals(false); } - void Settings::on_ubxResetPushButton_clicked() { // reset Ublox device emit sendUbxReset(); } - void Settings::writeGnssConfig() { QVector configList; if (ui->gnssGpsCheckBox->isEnabled()) { // GPS - GnssConfigStruct config; - config.gnssId=0; config.maxTrkCh=14; config.resTrkCh=8; - config.flags = (ui->gnssGpsCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 0; + config.maxTrkCh = 14; + config.resTrkCh = 8; + config.flags = (ui->gnssGpsCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssSbasCheckBox->isEnabled()) { // SBAS - GnssConfigStruct config; - config.gnssId=1; config.maxTrkCh=3; config.resTrkCh=1; - config.flags = (ui->gnssSbasCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 1; + config.maxTrkCh = 3; + config.resTrkCh = 1; + config.flags = (ui->gnssSbasCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssGalCheckBox->isEnabled()) { // GAL - GnssConfigStruct config; - config.gnssId=2; config.maxTrkCh=8; config.resTrkCh=4; - config.flags = (ui->gnssGalCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 2; + config.maxTrkCh = 8; + config.resTrkCh = 4; + config.flags = (ui->gnssGalCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssBeidCheckBox->isEnabled()) { // BEID - GnssConfigStruct config; - config.gnssId=3; config.maxTrkCh=10; config.resTrkCh=4; - config.flags = (ui->gnssBeidCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 3; + config.maxTrkCh = 10; + config.resTrkCh = 4; + config.flags = (ui->gnssBeidCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssImesCheckBox->isEnabled()) { // IMES - GnssConfigStruct config; - config.gnssId=4; config.maxTrkCh=8; config.resTrkCh=0; - config.flags = (ui->gnssImesCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 4; + config.maxTrkCh = 8; + config.resTrkCh = 0; + config.flags = (ui->gnssImesCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssQzssCheckBox->isEnabled()) { // QZSS - GnssConfigStruct config; - config.gnssId=5; config.maxTrkCh=3; config.resTrkCh=0; - config.flags = (ui->gnssQzssCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 5; + config.maxTrkCh = 3; + config.resTrkCh = 0; + config.flags = (ui->gnssQzssCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } if (ui->gnssGlnsCheckBox->isEnabled()) { // GLNS - GnssConfigStruct config; - config.gnssId=6; config.maxTrkCh=12; config.resTrkCh=6; - config.flags = (ui->gnssGlnsCheckBox->isChecked())?0x00000001:0; - configList.push_back(config); + GnssConfigStruct config; + config.gnssId = 6; + config.maxTrkCh = 12; + config.resTrkCh = 6; + config.flags = (ui->gnssGlnsCheckBox->isChecked()) ? 0x00000001 : 0; + configList.push_back(config); } - if (configList.size()) emit setGnssConfigs(configList); + if (configList.size()) + emit setGnssConfigs(configList); } void Settings::writeTpConfig() { UbxTimePulseStruct tp; - tp.tpIndex=0; - bool ok=false; - tp.antCableDelay=ui->antDelayLineEdit->text().toInt(&ok); - if (!ok) return; - tp.rfGroupDelay=ui->groupDelayLineEdit->text().toInt(&ok); - if (!ok) return; - tp.userConfigDelay=ui->userDelayLineEdit->text().toLong(&ok); - if (!ok) return; - tp.freqPeriod=ui->freqPeriodLineEdit->text().toLong(&ok); - if (!ok) return; - tp.freqPeriodLock=ui->freqPeriodLockLineEdit->text().toLong(&ok); - if (!ok) return; - tp.pulseLenRatio=ui->pulseLenLineEdit->text().toLong(&ok); - if (!ok) return; - tp.pulseLenRatioLock=ui->pulseLenLockLineEdit->text().toLong(&ok); - if (!ok) return; + tp.tpIndex = 0; + bool ok = false; + tp.antCableDelay = ui->antDelayLineEdit->text().toInt(&ok); + if (!ok) + return; + tp.rfGroupDelay = ui->groupDelayLineEdit->text().toInt(&ok); + if (!ok) + return; + tp.userConfigDelay = ui->userDelayLineEdit->text().toLong(&ok); + if (!ok) + return; + tp.freqPeriod = ui->freqPeriodLineEdit->text().toLong(&ok); + if (!ok) + return; + tp.freqPeriodLock = ui->freqPeriodLockLineEdit->text().toLong(&ok); + if (!ok) + return; + tp.pulseLenRatio = ui->pulseLenLineEdit->text().toLong(&ok); + if (!ok) + return; + tp.pulseLenRatioLock = ui->pulseLenLockLineEdit->text().toLong(&ok); + if (!ok) + return; tp.flags = UbxTimePulseStruct::IS_LENGTH; - if (ui->tpActiveCheckBox->isChecked()) tp.flags |= UbxTimePulseStruct::ACTIVE; - if (ui->tpPolarityCheckBox->isChecked()) tp.flags |= UbxTimePulseStruct::POLARITY; + if (ui->tpActiveCheckBox->isChecked()) + tp.flags |= UbxTimePulseStruct::ACTIVE; + if (ui->tpPolarityCheckBox->isChecked()) + tp.flags |= UbxTimePulseStruct::POLARITY; - if (ui->lockGpsCheckBox->isChecked()) tp.flags |= UbxTimePulseStruct::LOCK_GPS; -// if (ui->syncedPulseGroupBox->isChecked()) tp.flags |= UbxTimePulseStruct::LOCK_GPS; + if (ui->lockGpsCheckBox->isChecked()) + tp.flags |= UbxTimePulseStruct::LOCK_GPS; - if (ui->lockOtherCheckBox->isChecked()) tp.flags |= UbxTimePulseStruct::LOCK_OTHER; -// if (ui->unsyncedPulseGroupBox->isChecked()) tp.flags |= UbxTimePulseStruct::LOCK_OTHER; + if (ui->lockOtherCheckBox->isChecked()) + tp.flags |= UbxTimePulseStruct::LOCK_OTHER; - if (ui->tpAlignTowCheckBox->isChecked()) tp.flags |= UbxTimePulseStruct::ALIGN_TO_TOW; - tp.flags |= ((ui->timeGridComboBox->currentIndex()<<7) & UbxTimePulseStruct::GRID_UTC_GPS); + if (ui->tpAlignTowCheckBox->isChecked()) + tp.flags |= UbxTimePulseStruct::ALIGN_TO_TOW; + tp.flags |= ((ui->timeGridComboBox->currentIndex() << 7) & UbxTimePulseStruct::GRID_UTC_GPS); emit setTP5Config(tp); } - void Settings::on_timeGridComboBox_currentIndexChanged(int /*index*/) { fTpConfigChanged = true; @@ -375,14 +372,11 @@ void Settings::on_freqPeriodLineEdit_editingFinished() { bool ok = false; ui->freqPeriodLineEdit->text().toLong(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -390,14 +384,11 @@ void Settings::on_freqPeriodLockLineEdit_editingFinished() { bool ok = false; ui->freqPeriodLockLineEdit->text().toLong(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -405,14 +396,11 @@ void Settings::on_pulseLenLineEdit_editingFinished() { bool ok = false; ui->pulseLenLineEdit->text().toLong(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -420,14 +408,11 @@ void Settings::on_pulseLenLockLineEdit_editingFinished() { bool ok = false; ui->pulseLenLockLineEdit->text().toLong(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -435,14 +420,11 @@ void Settings::on_antDelayLineEdit_editingFinished() { bool ok = false; ui->antDelayLineEdit->text().toInt(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -450,14 +432,11 @@ void Settings::on_groupDelayLineEdit_editingFinished() { bool ok = false; ui->groupDelayLineEdit->text().toInt(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -465,14 +444,11 @@ void Settings::on_userDelayLineEdit_editingFinished() { bool ok = false; ui->userDelayLineEdit->text().toLong(&ok); - if (!ok) onTP5Received(fTpConfig); + if (!ok) + onTP5Received(fTpConfig); else { fTpConfigChanged = true; this->onConfigChanged(); -/* - ui->settingsButtonBox->button(QDialogButtonBox::Apply)->setDisabled(false); - ui->settingsButtonBox->button(QDialogButtonBox::Discard)->setDisabled(false); -*/ } } @@ -480,5 +456,4 @@ void Settings::on_saveConfigPushButton_clicked() { // save config emit sendUbxSaveCfg(); - } diff --git a/source/gui/src/settings.ui b/gui/src/settings.ui similarity index 100% rename from source/gui/src/settings.ui rename to gui/src/settings.ui diff --git a/source/gui/src/spiform.cpp b/gui/src/spiform.cpp similarity index 57% rename from source/gui/src/spiform.cpp rename to gui/src/spiform.cpp index db4cb0a5..2c65b5df 100644 --- a/source/gui/src/spiform.cpp +++ b/gui/src/spiform.cpp @@ -1,9 +1,9 @@ #include "spiform.h" #include "ui_spiform.h" -SpiForm::SpiForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::SpiForm) +SpiForm::SpiForm(QWidget* parent) + : QWidget(parent) + , ui(new Ui::SpiForm) { ui->setupUi(this); } diff --git a/source/gui/src/spiform.ui b/gui/src/spiform.ui similarity index 100% rename from source/gui/src/spiform.ui rename to gui/src/spiform.ui diff --git a/source/gui/src/status.cpp b/gui/src/status.cpp similarity index 51% rename from source/gui/src/status.cpp rename to gui/src/status.cpp index 8ddb4d53..9f3d2fb4 100644 --- a/source/gui/src/status.cpp +++ b/gui/src/status.cpp @@ -1,118 +1,122 @@ +#include #include +#include #include #include -#include -#include - -static quint64 rateSecondsBuffered = 60*120; // 120 min +static quint64 rateSecondsBuffered = 60 * 120; // 120 min static const int MAX_BINS = 200; // bins in pulse height histogram static const float MAX_ADC_VOLTAGE = 4.0; -Status::Status(QWidget *parent) : - QWidget(parent), - statusUi(new Ui::Status) +Status::Status(QWidget* parent) + : QWidget(parent) + , statusUi(new Ui::Status) { statusUi->setupUi(this); - statusUi->pulseHeightHistogram->title="Pulse Height"; - - statusUi->pulseHeightHistogram->setXMin(0.0); - statusUi->pulseHeightHistogram->setXMax(MAX_ADC_VOLTAGE); - statusUi->pulseHeightHistogram->setNrBins(MAX_BINS); - statusUi->pulseHeightHistogram->setLogY(false); - - statusUi->ratePlotPresetComboBox->addItems(QStringList() << "seconds" << "hh:mm:ss" << "time"); + + statusUi->pulseHeightHistogram->title = "Pulse Height"; + + statusUi->pulseHeightHistogram->setXMin(0.0); + statusUi->pulseHeightHistogram->setXMax(MAX_ADC_VOLTAGE); + statusUi->pulseHeightHistogram->setNrBins(MAX_BINS); + statusUi->pulseHeightHistogram->setLogY(false); + statusUi->pulseHeightHistogram->setEnabled(false); + statusUi->pulseHeightHistogramGroupBox->setChecked(false); + + statusUi->ratePlotPresetComboBox->addItems(QStringList() << "seconds" + << "hh:mm:ss" + << "time"); statusUi->ratePlotBufferEdit->setText(QString("%1:%2:%3:%4") - .arg(rateSecondsBuffered/(3600*24),2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600*24))/3600,2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600))/60,2,10,QChar('0')) - .arg(rateSecondsBuffered%60,2,10,QChar('0'))); + .arg(rateSecondsBuffered / (3600 * 24), 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600 * 24)) / 3600, 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600)) / 60, 2, 10, QChar('0')) + .arg(rateSecondsBuffered % 60, 2, 10, QChar('0'))); - connect(statusUi->ratePlotBufferEdit, &QLineEdit::editingFinished, this, [this](){this->setRateSecondsBuffered(statusUi->ratePlotBufferEdit->text());}); + connect(statusUi->ratePlotBufferEdit, &QLineEdit::editingFinished, this, [this]() { this->setRateSecondsBuffered(statusUi->ratePlotBufferEdit->text()); }); connect(statusUi->ratePlotPresetComboBox, &QComboBox::currentTextChanged, statusUi->ratePlot, &PlotCustom::setPreset); connect(statusUi->resetHistoPushButton, &QPushButton::clicked, this, &Status::clearPulseHeightHisto); connect(statusUi->resetRatePushButton, &QPushButton::clicked, this, &Status::clearRatePlot); - connect(statusUi->resetRatePushButton, &QPushButton::clicked, this, [this](){ this->resetRateClicked(); } ); + connect(statusUi->resetRatePushButton, &QPushButton::clicked, this, [this]() { this->resetRateClicked(); }); connect(statusUi->ratePlotGroupBox, &QGroupBox::toggled, statusUi->ratePlot, &PlotCustom::setStatusEnabled); - connect(statusUi->pulseHeightHistogramGroupBox, &QGroupBox::toggled, statusUi->pulseHeightHistogram, &CustomHistogram::setStatusEnabled); + connect(statusUi->pulseHeightHistogramGroupBox, &QGroupBox::toggled, statusUi->pulseHeightHistogram, &CustomHistogram::setEnabled); connect(statusUi->biasEnableCheckBox, &QCheckBox::clicked, this, &Status::biasSwitchChanged); connect(statusUi->highGainCheckBox, &QCheckBox::clicked, this, &Status::gainSwitchChanged); connect(statusUi->preamp1CheckBox, &QCheckBox::clicked, this, &Status::preamp1SwitchChanged); connect(statusUi->preamp2CheckBox, &QCheckBox::clicked, this, &Status::preamp2SwitchChanged); - + fInputSwitchButtonGroup = new QButtonGroup(this); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton0,0); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton1,1); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton2,2); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton3,3); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton4,4); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton5,5); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton6,6); - fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton7,7); - connect(fInputSwitchButtonGroup, static_cast(&QButtonGroup::buttonClicked), [=](int id){ emit inputSwitchChanged(id); }); -// connect(fInputSwitchButtonGroup, QOverload::of(&QButtonGroup::buttonClicked), [=](int id){ emit inputSwitchChanged(id); }); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton0, 0); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton1, 1); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton2, 2); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton3, 3); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton4, 4); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton5, 5); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton6, 6); + fInputSwitchButtonGroup->addButton(statusUi->InputSelectRadioButton7, 7); + connect(fInputSwitchButtonGroup, static_cast(&QButtonGroup::buttonClicked), [=](int id) { emit inputSwitchChanged(id); }); foreach (GpioSignalDescriptor item, GPIO_SIGNAL_MAP) { - if (item.direction==DIR_IN) statusUi->triggerSelectionComboBox->addItem(item.name); + if (item.direction == DIR_IN) + statusUi->triggerSelectionComboBox->addItem(item.name); } - //timepulseTimer = new QTimer(this); timepulseTimer.setSingleShot(true); timepulseTimer.setInterval(3000); connect(&timepulseTimer, &QTimer::timeout, this, [this]() { - statusUi->timePulseLabel->setStyleSheet("QLabel {background-color: red;}"); + statusUi->timePulseLabel->setStyleSheet("QLabel {background-color: red;}"); }); } -void Status::onGpioRatesReceived(quint8 whichrate, QVector rates){ - if (whichrate==0){ - if (xorSamples.size()>0){ - for (int k = rates.size()-1; k>=0; k--){ +void Status::onGpioRatesReceived(quint8 whichrate, QVector rates) +{ + if (whichrate == 0) { + if (xorSamples.size() > 0) { + for (int k = rates.size() - 1; k >= 0; k--) { bool foundK = false; // if foundK it has found an index k where the x values of the input points // are smaller or equal to the x values of the already existing points -> overlap - for (int i = xorSamples.size()-1; i>=xorSamples.size()-1-rates.size(); i--){ - if (rates.at(k).x() <= xorSamples.at(i).x()){ + for (int i = xorSamples.size() - 1; i >= xorSamples.size() - 1 - rates.size(); i--) { + if (rates.at(k).x() <= xorSamples.at(i).x()) { foundK = true; } } - if (foundK && kratePlot->plotXorSamples(xorSamples); } - if (whichrate==1){ - if (andSamples.size()>0){ - for (int k = rates.size()-1; k>=0; k--){ + if (whichrate == 1) { + if (andSamples.size() > 0) { + for (int k = rates.size() - 1; k >= 0; k--) { bool foundK = false; // if foundK it has found an index k where the x values of the input points // are smaller or equal to the x values of the already existing points -> overlap - for (int i = andSamples.size()-1; i>=andSamples.size()-1-rates.size(); i--){ - if (rates.at(k).x()<=andSamples.at(i).x()){ + for (int i = andSamples.size() - 1; i >= andSamples.size() - 1 - rates.size(); i--) { + if (rates.at(k).x() <= andSamples.at(i).x()) { foundK = true; } } - if (foundK && k0) && (andSamples.first().x() < (rates.last().x() - rateSecondsBuffered))){ + while ((andSamples.size() > 0) && (andSamples.first().x() < (rates.last().x() - rateSecondsBuffered))) { andSamples.pop_front(); } @@ -120,38 +124,38 @@ void Status::onGpioRatesReceived(quint8 whichrate, QVector rates){ } } -void Status::setRateSecondsBuffered(const QString& bufferTime){ +void Status::setRateSecondsBuffered(const QString& bufferTime) +{ QStringList values = bufferTime.split(':'); quint64 secs = 0; - if (values.size()>4){ + if (values.size() > 4) { statusUi->ratePlotBufferEdit->setText(QString("%1:%2:%3:%4") - .arg(rateSecondsBuffered/(3600*24),2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600*24))/3600,2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600))/60,2,10,QChar('0')) - .arg(rateSecondsBuffered%60,2,10,QChar('0'))); + .arg(rateSecondsBuffered / (3600 * 24), 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600 * 24)) / 3600, 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600)) / 60, 2, 10, QChar('0')) + .arg(rateSecondsBuffered % 60, 2, 10, QChar('0'))); return; } - for (int i = values.size()-1; i >= 0; i--){ - if (i == values.size()-1){ + for (int i = values.size() - 1; i >= 0; i--) { + if (i == values.size() - 1) { secs += values.at(i).toInt(); } - if (i == values.size()-2){ - secs += 60*values.at(i).toInt(); - + if (i == values.size() - 2) { + secs += 60 * values.at(i).toInt(); } - if (i == values.size()-3){ - secs += 3600*values.at(i).toInt(); + if (i == values.size() - 3) { + secs += 3600 * values.at(i).toInt(); } - if (i == values.size()-4){ - secs += 3600*24*values.at(i).toInt(); + if (i == values.size() - 4) { + secs += 3600 * 24 * values.at(i).toInt(); } } rateSecondsBuffered = secs; statusUi->ratePlotBufferEdit->setText(QString("%1:%2:%3:%4") - .arg(rateSecondsBuffered/(3600*24),2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600*24))/3600,2,10,QChar('0')) - .arg((rateSecondsBuffered%(3600))/60,2,10,QChar('0')) - .arg(rateSecondsBuffered%60,2,10,QChar('0'))); + .arg(rateSecondsBuffered / (3600 * 24), 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600 * 24)) / 3600, 2, 10, QChar('0')) + .arg((rateSecondsBuffered % (3600)) / 60, 2, 10, QChar('0')) + .arg(rateSecondsBuffered % 60, 2, 10, QChar('0'))); } void Status::clearRatePlot() @@ -164,12 +168,14 @@ void Status::clearRatePlot() void Status::onTriggerSelectionReceived(GPIO_SIGNAL signal) { - int i=0; - while (itriggerSelectionComboBox->count()) { - if (statusUi->triggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name)==0) break; + int i = 0; + while (i < statusUi->triggerSelectionComboBox->count()) { + if (statusUi->triggerSelectionComboBox->itemText(i).compare(GPIO_SIGNAL_MAP[signal].name) == 0) + break; i++; } - if (i>=statusUi->triggerSelectionComboBox->count()) return; + if (i >= statusUi->triggerSelectionComboBox->count()) + return; statusUi->triggerSelectionComboBox->blockSignals(true); statusUi->triggerSelectionComboBox->setEnabled(true); statusUi->triggerSelectionComboBox->setCurrentIndex(i); @@ -184,53 +190,51 @@ void Status::onTimepulseReceived() void Status::clearPulseHeightHisto() { - statusUi->pulseHeightHistogram->clear(); - //fPulseHeightHistogramMap.clear(); - updatePulseHeightHistogram(); + statusUi->pulseHeightHistogram->clear(); + updatePulseHeightHistogram(); } void Status::onAdcSampleReceived(uint8_t channel, float value) { - if (channel==0) { - statusUi->ADCLabel1->setText("Ch1: "+QString::number(value,'f',3)+" V"); -// int binNr = (MAX_BINS-1)*value/MAX_ADC_VOLTAGE; - statusUi->pulseHeightHistogram->fill(value); - updatePulseHeightHistogram(); - - } else if (channel==1) - statusUi->ADCLabel2->setText("Ch2: "+QString::number(value,'f',3)+" V"); - else if (channel==2) - statusUi->ADCLabel3->setText("Ch3: "+QString::number(value,'f',3)+" V"); - else if (channel==3) - statusUi->ADCLabel4->setText("Ch4: "+QString::number(value,'f',3)+" V"); + if (channel == 0) { + statusUi->ADCLabel1->setText("Ch1: " + QString::number(value, 'f', 3) + " V"); + if (statusUi->pulseHeightHistogram->enabled()) { + statusUi->pulseHeightHistogram->fill(value); + updatePulseHeightHistogram(); + } + } else if (channel == 1) + statusUi->ADCLabel2->setText("Ch2: " + QString::number(value, 'f', 3) + " V"); + else if (channel == 2) + statusUi->ADCLabel3->setText("Ch3: " + QString::number(value, 'f', 3) + " V"); + else if (channel == 3) + statusUi->ADCLabel4->setText("Ch4: " + QString::number(value, 'f', 3) + " V"); } void Status::updatePulseHeightHistogram() { -// statusUi->pulseHeightHistogram->replot(); - statusUi->pulseHeightHistogram->update(); - long int entries = statusUi->pulseHeightHistogram->getEntries(); - statusUi->PulseHeightHistogramEntriesLabel->setText(QString::number(entries)+" entries"); + statusUi->pulseHeightHistogram->update(); + long int entries = statusUi->pulseHeightHistogram->getEntries(); + statusUi->PulseHeightHistogramEntriesLabel->setText(QString::number(entries) + " entries"); } -void Status::onUiEnabledStateChange(bool connected){ - if (connected){ - if (statusUi->ratePlotGroupBox->isChecked()){ +void Status::onUiEnabledStateChange(bool connected) +{ + if (connected) { + if (statusUi->ratePlotGroupBox->isChecked()) { statusUi->ratePlot->setStatusEnabled(true); } - if (statusUi->pulseHeightHistogramGroupBox->isChecked()){ - statusUi->pulseHeightHistogram->setStatusEnabled(true); + if (statusUi->pulseHeightHistogramGroupBox->isChecked()) { + statusUi->pulseHeightHistogram->setEnabled(true); } this->setEnabled(true); timepulseTimer.start(); - }else{ + } else { andSamples.clear(); xorSamples.clear(); -// updatePulseHeightHistogram(); statusUi->ratePlot->setStatusEnabled(false); statusUi->pulseHeightHistogram->clear(); - statusUi->pulseHeightHistogram->setStatusEnabled(false); + statusUi->pulseHeightHistogram->setEnabled(false); statusUi->triggerSelectionComboBox->setEnabled(false); timepulseTimer.stop(); statusUi->timePulseLabel->setStyleSheet("QLabel {background-color: Window;}"); @@ -246,43 +250,42 @@ void Status::on_histoLogYCheckBox_clicked() void Status::onInputSwitchReceived(uint8_t id) { - fInputSwitchButtonGroup->button(id)->setChecked(true); + fInputSwitchButtonGroup->button(id)->setChecked(true); } void Status::onBiasSwitchReceived(bool state) { - statusUi->biasEnableCheckBox->setChecked(state); + statusUi->biasEnableCheckBox->setChecked(state); } void Status::onGainSwitchReceived(bool state) { - statusUi->highGainCheckBox->setChecked(state); + statusUi->highGainCheckBox->setChecked(state); } void Status::onPreampSwitchReceived(uint8_t channel, bool state) { - if (channel==0) - statusUi->preamp1CheckBox->setChecked(state); - else if (channel==1) - statusUi->preamp2CheckBox->setChecked(state); + if (channel == 0) + statusUi->preamp1CheckBox->setChecked(state); + else if (channel == 1) + statusUi->preamp2CheckBox->setChecked(state); } void Status::onDacReadbackReceived(uint8_t channel, float value) { - if (channel==0) - statusUi->DACLabel1->setText("Ch1: "+QString::number(value,'f',3)+" V"); - else if (channel==1) - statusUi->DACLabel2->setText("Ch2: "+QString::number(value,'f',3)+" V"); - else if (channel==2) - statusUi->DACLabel3->setText("Ch3: "+QString::number(value,'f',3)+" V"); - else if (channel==3) - statusUi->DACLabel4->setText("Ch4: "+QString::number(value,'f',3)+" V"); - + if (channel == 0) + statusUi->DACLabel1->setText("Ch1: " + QString::number(value, 'f', 3) + " V"); + else if (channel == 1) + statusUi->DACLabel2->setText("Ch2: " + QString::number(value, 'f', 3) + " V"); + else if (channel == 2) + statusUi->DACLabel3->setText("Ch3: " + QString::number(value, 'f', 3) + " V"); + else if (channel == 3) + statusUi->DACLabel4->setText("Ch4: " + QString::number(value, 'f', 3) + " V"); } void Status::onTemperatureReceived(float value) { - statusUi->temperatureLabel->setText("Temperature: "+QString::number(value,'f',2)+" °C"); + statusUi->temperatureLabel->setText("Temperature: " + QString::number(value, 'f', 2) + " °C"); } Status::~Status() @@ -291,21 +294,22 @@ Status::~Status() delete fInputSwitchButtonGroup; } -void Status::on_triggerSelectionComboBox_currentIndexChanged(const QString &arg1) +void Status::on_triggerSelectionComboBox_currentIndexChanged(const QString& arg1) { - for (auto signalIt=GPIO_SIGNAL_MAP.begin(); signalIt!=GPIO_SIGNAL_MAP.end(); ++signalIt) { - const GPIO_SIGNAL signalId=signalIt.key(); - if (GPIO_SIGNAL_MAP[signalId].name==arg1) { - emit triggerSelectionChanged(signalId); - return; - } - } + for (auto signalIt = GPIO_SIGNAL_MAP.begin(); signalIt != GPIO_SIGNAL_MAP.end(); ++signalIt) { + const GPIO_SIGNAL signalId = signalIt.key(); + if (GPIO_SIGNAL_MAP[signalId].name == arg1) { + emit triggerSelectionChanged(signalId); + return; + } + } } -void Status::onMqttStatusChanged(bool connected){ - if (connected){ +void Status::onMqttStatusChanged(bool connected) +{ + if (connected) { statusUi->mqttStatusLabel->setStyleSheet("QLabel {background-color: lightGreen;}"); - }else{ + } else { statusUi->mqttStatusLabel->setStyleSheet("QLabel {background-color: red;}"); } } diff --git a/source/gui/src/status.ui b/gui/src/status.ui similarity index 100% rename from source/gui/src/status.ui rename to gui/src/status.ui diff --git a/source/gui/windows.rc b/gui/windows.rc similarity index 100% rename from source/gui/windows.rc rename to gui/windows.rc diff --git a/source/library/apt_cache_search.sh b/library/apt_cache_search.sh similarity index 100% rename from source/library/apt_cache_search.sh rename to library/apt_cache_search.sh diff --git a/source/library/config/version.h b/library/config/version.h similarity index 69% rename from source/library/config/version.h rename to library/config/version.h index 3bab90c4..fa722254 100644 --- a/source/library/config/version.h +++ b/library/config/version.h @@ -5,6 +5,8 @@ namespace MuonPi::CMake::Version { constexpr int major { @PROJECT_VERSION_MAJOR@ }; constexpr int minor { @PROJECT_VERSION_MINOR@ }; constexpr int patch { @PROJECT_VERSION_PATCH@ }; +constexpr const char* additional { "@PROJECT_VERSION_ADDITIONAL@" }; +constexpr const char* hash { "@PROJECT_VERSION_HASH@" }; } #endif // MUONDETECTOR_VERSION_H diff --git a/source/library/include/.gitignore b/library/include/.gitignore similarity index 100% rename from source/library/include/.gitignore rename to library/include/.gitignore diff --git a/library/include/config.h b/library/include/config.h new file mode 100644 index 00000000..7a344d24 --- /dev/null +++ b/library/include/config.h @@ -0,0 +1,89 @@ +#ifndef MUONPI_CONFIG_H +#define MUONPI_CONFIG_H + +#include "version.h" + +#include +#include + +namespace MuonPi::Version { +constexpr struct Version { + int major; + int minor; + int patch; + const char* additional { "" }; + const char* hash { "" }; + + [[nodiscard]] auto string() const -> std::string; +} hardware { 3, 0, 0 }, + software { CMake::Version::major, CMake::Version::minor, CMake::Version::patch, CMake::Version::additional, CMake::Version::hash }; +} + +namespace MuonPi::Config { +constexpr const char* file { "/etc/muondetector/muondetector.conf" }; +constexpr int event_count_deadtime_ticks { 1000 }; +constexpr int event_count_max_pileups { 50 }; + +namespace MQTT { + constexpr const char* host { "data.muonpi.org" }; + constexpr int port { 1883 }; + constexpr int timeout { 10000 }; + constexpr int qos { 1 }; + constexpr int keepalive_interval { 45 }; + constexpr const char* data_topic { "muonpi/data/" }; + constexpr const char* log_topic { "muonpi/log/" }; +} +namespace Log { + constexpr int interval { 1 }; + constexpr int max_geohash_length { 6 }; +} +namespace Upload { + constexpr int reminder { 5 }; + constexpr std::size_t timeout { 600000UL }; + constexpr const char* url { "balu.physik.uni-giessen.de:/cosmicshower" }; + constexpr int port { 35221 }; +} +namespace Hardware { + namespace OLED { + constexpr int update_interval { 2000 }; + } + namespace ADC { + constexpr int buffer_size { 50 }; + constexpr int pretrigger { 10 }; + constexpr int deadtime { 8 }; + } + namespace DAC { + namespace Voltage { + constexpr float bias { 0.5 }; + constexpr float threshold[2] { 0.1, 1.0 }; + } + } + namespace GPIO::Clock::Measurement { + constexpr int interval { 100 }; + constexpr int buffer_size { 500 }; + } + constexpr int trace_sampling_interval { 5 }; + constexpr int monitor_interval { 5000 }; + namespace RateScan { + constexpr int iterations { 10 }; + constexpr int interval { 400 }; + } +} + +} // namespace MuonPi::Config + +namespace MuonPi::Settings { +struct { + int max_geohash_length { Config::Log::max_geohash_length }; +} log; + +struct { + bool store_local { false }; +} events; + +struct { + int port { 51508 }; +} gui; +} + +#endif // MUONPI_CONFIG_H diff --git a/library/include/gpio_pin_definitions.h b/library/include/gpio_pin_definitions.h new file mode 100644 index 00000000..15184a1d --- /dev/null +++ b/library/include/gpio_pin_definitions.h @@ -0,0 +1,82 @@ +#ifndef GPIO_SIGNAL_DEFINITIONS_H +#define GPIO_SIGNAL_DEFINITIONS_H + +#include "muondetector_shared_global.h" + +#include +#include +#include +#include + +// Define the signals of the hardware interface to the MuonPi HAT +// Note: The pin definitions are enum constants and have nothing to do with the actual pin numbers +// of the RPi GPIO header. To be independent of the specific hardware implementation, +// the pin numbers for these signals are defined in gpio_pin_mapping.h on the daemon side through the static map GPIO_PINMAP + +enum GPIO_SIGNAL { UBIAS_EN, + PREAMP_1, + PREAMP_2, + EVT_AND, + EVT_XOR, + GAIN_HL, + ADC_READY, + TIMEPULSE, + TIME_MEAS_OUT, + STATUS1, + STATUS2, + STATUS3, + PREAMP_FAULT, + EXT_TRIGGER, + TDC_INTB, + TDC_STATUS, + IN_POL1, + IN_POL2, + UNDEFINED_SIGNAL = 255 +}; + +enum SIGNAL_DIRECTION { DIR_UNDEFINED, + DIR_IN, + DIR_OUT, + DIR_IO }; + +struct GpioSignalDescriptor { + QString name; + SIGNAL_DIRECTION direction; +}; + +static const QMap GPIO_SIGNAL_MAP = { { UBIAS_EN, { "UBIAS_EN", DIR_OUT } }, + { PREAMP_1, { "PREAMP_1", DIR_OUT } }, + { PREAMP_2, { "PREAMP_2", DIR_OUT } }, + { EVT_AND, { "EVT_AND", DIR_IN } }, + { EVT_XOR, { "EVT_XOR", DIR_IN } }, + { GAIN_HL, { "GAIN_HL", DIR_OUT } }, + { ADC_READY, { "ADC_READY", DIR_IN } }, + { TIMEPULSE, { "TIMEPULSE", DIR_IN } }, + { TIME_MEAS_OUT, { "TIME_MEAS_OUT", DIR_IN } }, + { STATUS1, { "STATUS1", DIR_OUT } }, + { STATUS2, { "STATUS2", DIR_OUT } }, + { STATUS3, { "STATUS3", DIR_OUT } }, + { PREAMP_FAULT, { "PREAMP_FAULT", DIR_IN } }, + { EXT_TRIGGER, { "EXT_TRIGGER", DIR_IN } }, + { TDC_INTB, { "TDC_INTB", DIR_IN } }, + { TDC_STATUS, { "TDC_STATUS", DIR_OUT } }, + { IN_POL1, { "IN_POL1", DIR_OUT } }, + { IN_POL2, { "IN_POL2", DIR_OUT } }, + { UNDEFINED_SIGNAL, { "UNDEFINED_SIGNAL", DIR_UNDEFINED} } + }; + +static const QVector TIMING_MUX_SIGNAL_NAMES = { + "AND", "XOR", "DISCR1", "DISCR2", "N/A", "TIMEPULSE", "N/A", "EXT" +}; + +enum class TIMING_MUX_SELECTION : uint8_t { + AND = 0, + XOR = 1, + DISCR1 = 2, + DISCR2 = 3, + TIMEPULSE = 5, + EXT = 7, + UNDEFINED = 255 +}; + +#endif // GPIO_SIGNAL_DEFINITIONS_H diff --git a/library/include/histogram.h b/library/include/histogram.h new file mode 100644 index 00000000..0b82e650 --- /dev/null +++ b/library/include/histogram.h @@ -0,0 +1,64 @@ +#ifndef HISTOGRAM_H +#define HISTOGRAM_H + +#include "muondetector_shared_global.h" + +#include +//#include +#include +#include + +class Histogram { +public: + Histogram() = default; + Histogram(const std::string& name, int nrBins, double min, double max); + ~Histogram(); + void clear(); + void setName(const std::string& name); + void setUnit(const std::string& unit); + void setNrBins(int bins); + int getNrBins() const; + void setMin(double val); + double getMin() const; + void setMax(double val); + double getMax() const; + double getRange() const; + double getCenter() const; + double getBinCenter(int bin) const; + int getLowestOccupiedBin() const; + int getHighestOccupiedBin() const; + void fill(double x, double mult = 1.); + void setBinContent(int bin, double value); + double getBinContent(int bin) const; + double getMean(); + double getRMS(); + double getUnderflow() const; + double getOverflow() const; + double getEntries(); + void rescale(double center, double width); + void rescale(double center); + void rescale(); + void setAutoscale( bool autoscale = true ); + + friend QDataStream& operator<<(QDataStream& out, const Histogram& h); + friend QDataStream& operator>>(QDataStream& in, Histogram& h); + + const std::string& getName() const { return fName; } + const std::string& getUnit() const { return fUnit; } + +protected: + int value2Bin(double value) const; + double bin2Value(int bin) const; + + std::string fName = "defaultHisto"; + std::string fUnit = "A.U."; + int fNrBins = 100; + double fMin = 0.0; + double fMax = 1.0; + double fOverflow = 0; + double fUnderflow = 0; + std::map fHistogramMap; + bool fAutoscale { false }; +}; + +#endif // HISTOGRAM_H diff --git a/source/library/include/mqtthandler.h b/library/include/mqtthandler.h similarity index 99% rename from source/library/include/mqtthandler.h rename to library/include/mqtthandler.h index 998e1da7..8bf21d51 100644 --- a/source/library/include/mqtthandler.h +++ b/library/include/mqtthandler.h @@ -42,6 +42,8 @@ class MUONDETECTORSHARED MqttHandler : public QObject void request_timer_start(int); void request_timer_restart(int); + void giving_up(); + public slots: void start(const QString& username, const QString& password); diff --git a/source/library/include/muondetector_shared_global.h b/library/include/muondetector_shared_global.h similarity index 99% rename from source/library/include/muondetector_shared_global.h rename to library/include/muondetector_shared_global.h index 83b9f8d1..1786d376 100644 --- a/source/library/include/muondetector_shared_global.h +++ b/library/include/muondetector_shared_global.h @@ -3,7 +3,6 @@ #include - #ifdef MUONDETECTOR_LIBRARY_EXPORT #define MUONDETECTORSHARED Q_DECL_EXPORT #else diff --git a/library/include/muondetector_structs.h b/library/include/muondetector_structs.h new file mode 100644 index 00000000..0d5deee9 --- /dev/null +++ b/library/include/muondetector_structs.h @@ -0,0 +1,526 @@ +#ifndef MUONDETECTOR_STRUCTS_H +#define MUONDETECTOR_STRUCTS_H + +#include "histogram.h" +#include "muondetector_shared_global.h" +#include "gpio_pin_definitions.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using EventTime = std::chrono::time_point; + +enum class ADC_SAMPLING_MODE { + DISABLED = 0, + PEAK = 1, + TRACE = 2 +}; + +//enum TIMING_MUX_INPUTS { MUX_AND=0, MUX_XOR=1, MUX_DISC1=2, MUX_DISC2=3 }; + +class GeneralEvent { +public: + explicit GeneralEvent( std::function fn ); +public slots: + void trigger(); +protected: + std::function fFn; +}; + + +struct IoConfiguration { + TIMING_MUX_SELECTION timing_input { TIMING_MUX_SELECTION::UNDEFINED }; + GPIO_SIGNAL event_trigger { GPIO_SIGNAL::UNDEFINED_SIGNAL }; + GeneralEvent led1_event; + GeneralEvent led2_event; +}; + + +struct CalibStruct { +public: + enum { + CALIBFLAGS_NO_CALIB = 0x00, + CALIBFLAGS_COMPONENTS = 0x01, + CALIBFLAGS_VOLTAGE_COEFFS = 0x02, + CALIBFLAGS_CURRENT_COEFFS = 0x04 + }; + + enum { + FEATUREFLAGS_NONE = 0x00, + FEATUREFLAGS_GNSS = 0x01, + FEATUREFLAGS_ENERGY = 0x02, + FEATUREFLAGS_DETBIAS = 0x04, + FEATUREFLAGS_PREAMP_BIAS = 0x08, + FEATUREFLAGS_DUAL_CHANNEL = 0x10 + }; + + CalibStruct() = default; + CalibStruct(const std::string& a_name, const std::string& a_type, uint8_t a_address, const std::string& a_value) + : name(a_name) + , type(a_type) + , address(a_address) + , value(a_value) + { + } + ~CalibStruct() = default; + CalibStruct(const CalibStruct& s) + : name(s.name) + , type(s.type) + , address(s.address) + , value(s.value) + { + } + std::string name = ""; + std::string type = ""; + uint16_t address = 0; + std::string value = ""; +}; + +struct GeodeticPos { + uint32_t iTOW; + int32_t lon; // longitude 1e-7 scaling (increase by 1 means 100 nano degrees) + int32_t lat; // latitude 1e-7 scaling (increase by 1 means 100 nano degrees) + int32_t height; // height above ellipsoid + int32_t hMSL; // height above main sea level + uint32_t hAcc; // horizontal accuracy estimate + uint32_t vAcc; // vertical accuracy estimate +}; + +struct GnssConfigStruct { + uint8_t gnssId; + uint8_t resTrkCh; + uint8_t maxTrkCh; + uint32_t flags; +}; + +class GnssSatellite { +public: + GnssSatellite() { } + GnssSatellite(int gnssId, int satId, int cnr, int elev, int azim, float prRes, uint32_t flags) + : fGnssId(gnssId) + , fSatId(satId) + , fCnr(cnr) + , fElev(elev) + , fAzim(azim) + , fPrRes(prRes) + { + fQuality = (int)(flags & 0x07); + if (flags & 0x08) + fUsed = true; + else + fUsed = false; + fHealth = (int)(flags >> 4 & 0x03); + fOrbitSource = (flags >> 8 & 0x07); + fSmoothed = (flags & 0x80); + fDiffCorr = (flags & 0x40); + } + + GnssSatellite(int gnssId, int satId, int cnr, int elev, int azim, float prRes, + int quality, int health, int orbitSource, bool used, bool diffCorr, bool smoothed) + : fGnssId(gnssId) + , fSatId(satId) + , fCnr(cnr) + , fElev(elev) + , fAzim(azim) + , fPrRes(prRes) + , fQuality(quality) + , fHealth(health) + , fOrbitSource(orbitSource) + , fUsed(used) + , fDiffCorr(diffCorr) + , fSmoothed(smoothed) + { + } + + ~GnssSatellite() { } + + static void PrintHeader(bool wIndex); + void Print(bool wHeader) const; + void Print(int index, bool wHeader) const; + + static bool sortByCnr(const GnssSatellite& sat1, const GnssSatellite& sat2) + { + return sat1.getCnr() > sat2.getCnr(); + } + + inline int getCnr() const { return fCnr; } + + friend QDataStream& operator<<(QDataStream& out, const GnssSatellite& sat); + friend QDataStream& operator>>(QDataStream& in, GnssSatellite& sat); + +public: + int fGnssId = 0, fSatId = 0, fCnr = 0, fElev = 0, fAzim = 0; + float fPrRes = 0.; + int fQuality = 0, fHealth = 0; + int fOrbitSource = 0; + bool fUsed = false, fDiffCorr = false, fSmoothed = false; +}; + +struct UbxTimePulseStruct { + enum { ACTIVE = 0x01, + LOCK_GPS = 0x02, + LOCK_OTHER = 0x04, + IS_FREQ = 0x08, + IS_LENGTH = 0x10, + ALIGN_TO_TOW = 0x20, + POLARITY = 0x40, + GRID_UTC_GPS = 0x780 }; + uint8_t tpIndex = 0; + uint8_t version = 0; + int16_t antCableDelay = 0; + int16_t rfGroupDelay = 0; + uint32_t freqPeriod = 0; + uint32_t freqPeriodLock = 0; + uint32_t pulseLenRatio = 0; + uint32_t pulseLenRatioLock = 0; + int32_t userConfigDelay = 0; + uint32_t flags = 0; +}; + +struct UbxTimeMarkStruct { + enum { TIMEBASE_LOCAL = 0x00, + TIMEBASE_GNSS = 0x01, + TIMEBASE_UTC = 0x02, + TIMEBASE_OTHER = 0x03 }; + struct timespec rising = { 0, 0 }; + struct timespec falling = { 0, 0 }; + bool risingValid = false; + bool fallingValid = false; + uint32_t accuracy_ns = 0; + bool valid = false; + uint8_t timeBase = 0; + bool utcAvailable = false; + uint8_t flags = 0; + uint16_t evtCounter = 0; +}; + +struct GnssMonHwStruct { + GnssMonHwStruct() = default; + GnssMonHwStruct(quint16 a_noise, quint16 a_agc, quint8 a_antStatus, quint8 a_antPower, quint8 a_jamInd, quint8 a_flags) + : noise(a_noise) + , agc(a_agc) + , antStatus(a_antStatus) + , antPower(a_antPower) + , jamInd(a_jamInd) + , flags(a_flags) + { + } + quint16 noise = 0, agc = 0; + quint8 antStatus = 0, antPower = 0, jamInd = 0, flags = 0; +}; + +struct GnssMonHw2Struct { + GnssMonHw2Struct() = default; + GnssMonHw2Struct(qint8 a_ofsI, qint8 a_ofsQ, quint8 a_magI, quint8 a_magQ, quint8 a_cfgSrc) + : ofsI(a_ofsI) + , ofsQ(a_ofsQ) + , magI(a_magI) + , magQ(a_magQ) + , cfgSrc(a_cfgSrc) + { + } + qint8 ofsI = 0, ofsQ = 0; + quint8 magI = 0, magQ = 0; + quint8 cfgSrc = 0; +}; + +enum I2C_DEVICE_MODE { I2C_MODE_NONE = 0, + I2C_MODE_NORMAL = 0x01, + I2C_MODE_FORCE = 0x02, + I2C_MODE_UNREACHABLE = 0x04, + I2C_MODE_FAILED = 0x08, + I2C_MODE_LOCKED = 0x10 }; + +struct I2cDeviceEntry { + quint8 address; + QString name; + quint8 status; + quint32 nrBytesWritten; + quint32 nrBytesRead; + quint32 nrIoErrors; + quint32 lastTransactionTime; // in us +}; + +struct LogInfoStruct { + QString logFileName; + QString dataFileName; + quint8 status; + quint32 logFileSize; + quint32 dataFileSize; + qint32 logAge; +}; + +struct OledItem { + QString name; + QString displayString; +}; + +static const QList GNSS_ID_STRING = { " GPS", "SBAS", " GAL", "BEID", "IMES", "QZSS", "GLNS", " N/A" }; +static const QList FIX_TYPE_STRINGS = { "No Fix", "Dead Reck.", "2D-Fix", "3D-Fix", "GPS+Dead Reck.", "Time Fix" }; +static const QList GNSS_ORBIT_SRC_STRING = { "N/A", "Ephem", "Alm", "AOP", "AOP+", "Alt", "Alt", "Alt" }; +static const QList GNSS_ANT_STATUS_STRINGS = { "init", "unknown", "ok", "short", "open", "unknown", "unknown" }; +static const QList GNSS_HEALTH_STRINGS = { "N/A", "good", "bad", "bad+" }; +static const QMap I2C_MODE_STRINGMAP = { { 0x00, "None" }, + { 0x01, "Normal" }, + { 0x02, "System" }, + { 0x04, "Unreachable" }, + { 0x08, "Failed" }, + { 0x10, "Locked" } }; + +inline void GnssSatellite::PrintHeader(bool wIndex) +{ + if (wIndex) { + std::cout << " ----------------------------------------------------------------------------------" << std::endl; + std::cout << " Nr Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; + std::cout << " ----------------------------------------------------------------------------------" << std::endl; + } else { + std::cout << " -----------------------------------------------------------------" << std::endl; + std::cout << " Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; + std::cout << " -----------------------------------------------------------------" << std::endl; + } +} + +inline void GnssSatellite::Print(bool wHeader) const +{ + if (wHeader) { + std::cout << " ------------------------------------------------------------------------------" << std::endl; + std::cout << " Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; + std::cout << " ------------------------------------------------------------------------------" << std::endl; + } + std::cout << " " << std::dec << " " << GNSS_ID_STRING[(int)fGnssId].toStdString() << " " << std::setw(3) << (int)fSatId << " "; + std::cout << std::setw(3) << (int)fCnr << " " << std::setw(3) << (int)fElev << " " << std::setw(3) << (int)fAzim; + std::cout << " " << std::setw(6) << fPrRes << " " << fQuality << " " << std::string((fUsed) ? "Y" : "N"); + std::cout << " " << fHealth << " " << fOrbitSource << " " << (int)fSmoothed << " " << (int)fDiffCorr; + std::cout << std::endl; +} + +inline void GnssSatellite::Print(int index, bool wHeader) const +{ + if (wHeader) { + std::cout << " ----------------------------------------------------------------------------------" << std::endl; + std::cout << " Nr Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; + std::cout << " ----------------------------------------------------------------------------------" << std::endl; + } + std::cout << " " << std::dec << std::setw(2) << index + 1 << " " << GNSS_ID_STRING[(int)fGnssId].toStdString() << " " << std::setw(3) << (int)fSatId << " "; + std::cout << std::setw(3) << (int)fCnr << " " << std::setw(3) << (int)fElev << " " << std::setw(3) << (int)fAzim; + std::cout << " " << std::setw(6) << fPrRes << " " << fQuality << " " << std::string((fUsed) ? "Y" : "N"); + std::cout << " " << fHealth << " " << fOrbitSource << " " << (int)fSmoothed << " " << (int)fDiffCorr; + ; + std::cout << std::endl; +} + +inline QDataStream& operator<<(QDataStream& out, const CalibStruct& calib) +{ + out << QString::fromStdString(calib.name) << QString::fromStdString(calib.type) + << (quint16)calib.address << QString::fromStdString(calib.value); + return out; +} + +inline QDataStream& operator>>(QDataStream& in, CalibStruct& calib) +{ + QString s1, s2, s3; + quint16 u; + in >> s1 >> s2; + in >> u; + in >> s3; + calib.name = s1.toStdString(); + calib.type = s2.toStdString(); + calib.address = (uint16_t)u; + calib.value = s3.toStdString(); + return in; +} + +inline QDataStream& operator>>(QDataStream& in, GnssSatellite& sat) +{ + in >> sat.fGnssId >> sat.fSatId >> sat.fCnr >> sat.fElev >> sat.fAzim + >> sat.fPrRes >> sat.fQuality >> sat.fHealth >> sat.fOrbitSource + >> sat.fUsed >> sat.fDiffCorr >> sat.fSmoothed; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const GnssSatellite& sat) +{ + out << sat.fGnssId << sat.fSatId << sat.fCnr << sat.fElev << sat.fAzim + << sat.fPrRes << sat.fQuality << sat.fHealth << sat.fOrbitSource + << sat.fUsed << sat.fDiffCorr << sat.fSmoothed; + return out; +} + +inline QDataStream& operator>>(QDataStream& in, UbxTimePulseStruct& tp) +{ + in >> tp.tpIndex >> tp.version >> tp.antCableDelay >> tp.rfGroupDelay + >> tp.freqPeriod >> tp.freqPeriodLock >> tp.pulseLenRatio >> tp.pulseLenRatioLock + >> tp.userConfigDelay >> tp.flags; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const UbxTimePulseStruct& tp) +{ + out << tp.tpIndex << tp.version << tp.antCableDelay << tp.rfGroupDelay + << tp.freqPeriod << tp.freqPeriodLock << tp.pulseLenRatio << tp.pulseLenRatioLock + << tp.userConfigDelay << tp.flags; + return out; +} + +inline QDataStream& operator>>(QDataStream& in, Histogram& h) +{ + h.clear(); + QString name, unit; + in >> name >> h.fMin >> h.fMax >> h.fUnderflow >> h.fOverflow >> h.fNrBins; + h.setName(name.toStdString()); + for (int i = 0; i < h.fNrBins; i++) { + in >> h.fHistogramMap[i]; + } + in >> unit; + h.setUnit(unit.toStdString()); + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const Histogram& h) +{ + out << QString::fromStdString(h.fName) << h.fMin << h.fMax << h.fUnderflow << h.fOverflow << h.fNrBins; + for (int i = 0; i < h.fNrBins; i++) { + out << h.getBinContent(i); + } + out << QString::fromStdString(h.fUnit); + return out; +} + +inline QDataStream& operator>>(QDataStream& in, GnssMonHwStruct& hw) +{ + in >> hw.noise >> hw.agc >> hw.antStatus >> hw.antPower >> hw.jamInd >> hw.flags; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const GnssMonHwStruct& hw) +{ + out << hw.noise << hw.agc << hw.antStatus << hw.antPower << hw.jamInd << hw.flags; + return out; +} + +inline QDataStream& operator>>(QDataStream& in, GnssMonHw2Struct& hw2) +{ + in >> hw2.ofsI >> hw2.magI >> hw2.ofsQ >> hw2.magQ >> hw2.cfgSrc; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const GnssMonHw2Struct& hw2) +{ + out << hw2.ofsI << hw2.magI << hw2.ofsQ << hw2.magQ << hw2.cfgSrc; + return out; +} + +inline QDataStream& operator>>(QDataStream& in, LogInfoStruct& lis) +{ + in >> lis.logFileName >> lis.dataFileName >> lis.status >> lis.logFileSize + >> lis.dataFileSize >> lis.logAge; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const LogInfoStruct& lis) +{ + out << lis.logFileName << lis.dataFileName << lis.status << lis.logFileSize + << lis.dataFileSize << lis.logAge; + return out; +} + +inline QDataStream& operator>>(QDataStream& in, UbxTimeMarkStruct& tm) +{ + qint64 sec, nsec; + in >> sec >> nsec; + tm.rising.tv_sec = sec; + tm.rising.tv_nsec = nsec; + in >> sec >> nsec; + tm.falling.tv_sec = sec; + tm.falling.tv_nsec = nsec; + in >> tm.risingValid >> tm.fallingValid >> tm.accuracy_ns >> tm.valid + >> tm.timeBase >> tm.utcAvailable >> tm.flags >> tm.evtCounter; + return in; +} + +inline QDataStream& operator<<(QDataStream& out, const UbxTimeMarkStruct& tm) +{ + out << (qint64)tm.rising.tv_sec << (qint64)tm.rising.tv_nsec << (qint64)tm.falling.tv_sec << (qint64)tm.falling.tv_nsec + << tm.risingValid << tm.fallingValid << tm.accuracy_ns << tm.valid + << tm.timeBase << tm.utcAvailable << tm.flags << tm.evtCounter; + return out; +} + +class Property { +public: + Property() = default; + + template + Property(const T& val) + : name("") + , unit("") + { + typeId = qMetaTypeId(); + if (typeId == QMetaType::UnknownType) { + typeId = qRegisterMetaType(); + } + value = QVariant(val); + updated = true; + } + + template + Property(const QString& a_name, const T& val, const QString& a_unit = "") + : name(a_name) + , unit(a_unit) + { + typeId = qMetaTypeId(); + if (typeId == QMetaType::UnknownType) { + typeId = qRegisterMetaType(); + } + value = QVariant(val); + updated = true; + } + + Property(const Property& prop) = default; + Property& operator=(const Property& prop) + { + name = prop.name; + unit = prop.unit; + value = prop.value; + typeId = prop.typeId; + updated = prop.updated; + return *this; + } + + Property& operator=(const QVariant& val) + { + value = val; + //lastUpdate = std::chrono::system_clock::now(); + updated = true; + return *this; + } + + const QVariant& operator()() + { + updated = false; + return value; + } + + bool isUpdated() const { return updated; } + int type() const { return typeId; } + + QString name = ""; + QString unit = ""; + +private: + QVariant value; + bool updated = false; + int typeId = 0; +}; + + +#endif // MUONDETECTOR_STRUCTS_H diff --git a/source/library/include/tcpconnection.h b/library/include/tcpconnection.h similarity index 58% rename from source/library/include/tcpconnection.h rename to library/include/tcpconnection.h index 8ab42b4a..f03bfc9e 100644 --- a/source/library/include/tcpconnection.h +++ b/library/include/tcpconnection.h @@ -4,22 +4,21 @@ #include "muondetector_shared_global.h" #include "tcpmessage.h" -#include -#include -#include #include #include +#include +#include +#include #include -class MUONDETECTORSHARED TcpConnection : public QObject -{ +class MUONDETECTORSHARED TcpConnection : public QObject { Q_OBJECT public: TcpConnection(QString hostName, quint16 port, int verbose = 0, int timeout = 15000, - int pingInterval = 5000, QObject *parent = 0); + int pingInterval = 5000, QObject* parent = 0); TcpConnection(int socketDescriptor, int verbose = 0, int timeout = 15000, - int pingInterval = 5000, QObject *parent = 0); + int pingInterval = 5000, QObject* parent = 0); ~TcpConnection(); void delay(int millisecondsWait); const QString& getPeerAddress() const { return peerAddress; } @@ -29,17 +28,12 @@ class MUONDETECTORSHARED TcpConnection : public QObject uint32_t getNrBytesWritten() const { return bytesWritten; } time_t firstConnectionTime() const { return firstConnection; } - // void startTimePulser(); - signals: void madeConnection(QString remotePeerAddress, quint16 remotePeerPort, QString localAddress, quint16 localPort); void connectionTimeout(QString remotePeerAddress, quint16 remotePeerPort, QString localAddress, quint16 localPort, quint32 timeoutTime, quint32 connectionDuration); -// void connectionTimeout(QString remotePeerAddress, quint16 remotePeerPort, -// quint32 timeoutTime, quint32 connectionDuration); void error(int socketError, const QString message); void toConsole(QString data); - // void stopTimePulser(); void connected(); void receivedTcpMessage(TcpMessage tcpMessage); void finished(); @@ -50,33 +44,18 @@ public slots: void closeConnection(QString closedAddress); void closeThisConnection(); void onReadyRead(); - /* - void onTimePulse(); - bool sendFile(QString fileName = ""); - bool sendMessage(TcpMessage tcpMessage); - bool sendText(const quint16 someCode, QString someText); - bool sendCode(const quint16 someCode); - bool sendI2CProperties(I2cProperty i2cProperty, bool setProperties); - bool sendI2CPropertiesRequest(); - bool sendGpioRisingEdge(quint8 pin, quint32 tick); - bool sendUbxMsgRatesRequest(); - bool sendUbxMsgRates(QMap msgRateCfgs); - */ bool sendTcpMessage(TcpMessage tcpMessage); private: - // bool handleFileTransfer(QString fileName, QByteArray& block, quint16 nextCount); - bool writeBlock(const QByteArray &block); + bool writeBlock(const QByteArray& block); int timeout; int verbose; int pingInterval; int m_socketDescriptor; quint16 blockSize = 0; QString peerAddress, localAddress; - // quint16 fileCounter = -1; - // QFile *file = nullptr; - QDataStream *in = nullptr; - QTcpSocket *tcpSocket = nullptr; + QDataStream* in = nullptr; + QTcpSocket* tcpSocket = nullptr; QString hostName; quint16 port; quint16 peerPort; @@ -84,11 +63,6 @@ public slots: QPointer t; time_t lastConnection; time_t firstConnection; - uint32_t bytesRead=0, bytesWritten=0; -/* - static std::vector globalConnectionList; - static uint32_t globalNrBytesRead; - static uint32_t globalNrBytesWritten; -*/ + uint32_t bytesRead = 0, bytesWritten = 0; }; #endif // TCPCONNECTION_H diff --git a/source/library/include/tcpmessage.h b/library/include/tcpmessage.h similarity index 87% rename from source/library/include/tcpmessage.h rename to library/include/tcpmessage.h index be100ff9..ff94877a 100644 --- a/source/library/include/tcpmessage.h +++ b/library/include/tcpmessage.h @@ -13,13 +13,12 @@ enum class TCP_MSG_KEY : quint16; // at pos 0: length of message (quint16) -> length of QByteArray - length of this number (sizeof(quint16)) // at pos 1: tcpMsgID (quint16), shows what kind of message it is -class MUONDETECTORSHARED TcpMessage -{ +class MUONDETECTORSHARED TcpMessage { public: TcpMessage(quint16 tcpMsgID = 0); TcpMessage(TCP_MSG_KEY tcpMsgID); TcpMessage(QByteArray& rawdata); - TcpMessage(const TcpMessage &tcpMessage); + TcpMessage(const TcpMessage& tcpMessage); ~TcpMessage(); void setMsgID(quint16 tcpMsgID); @@ -28,7 +27,8 @@ class MUONDETECTORSHARED TcpMessage quint16 getMsgID() const; quint16 getByteCount() const; - QDataStream *dStream = nullptr; + QDataStream* dStream = nullptr; + private: QByteArray m_data {}; quint16 m_msgID {}; diff --git a/library/include/tcpmessage_keys.h b/library/include/tcpmessage_keys.h new file mode 100644 index 00000000..437e0a74 --- /dev/null +++ b/library/include/tcpmessage_keys.h @@ -0,0 +1,82 @@ +#ifndef TCPMESSAGE_KEYS_H +#define TCPMESSAGE_KEYS_H + +#include "muondetector_shared_global.h" + +// no specific reason but the codes are all prime numbers :) +enum class TCP_MSG_KEY : quint16 { MSG_PING = 2, + MSG_QUIT_CONNECTION = 3, + MSG_TIMEOUT = 5, + MSG_THRESHOLD = 7, + MSG_THRESHOLD_REQUEST = 11, + MSG_UBX_MSG_RATE_REQUEST = 13, + MSG_UBX_MSG_RATE = 17, + MSG_GPIO_EVENT = 19, + MSG_BIAS_VOLTAGE = 23, + MSG_BIAS_VOLTAGE_REQUEST = 29, + MSG_BIAS_SWITCH = 31, + MSG_BIAS_SWITCH_REQUEST = 37, + MSG_PCA_SWITCH = 41, + MSG_PCA_SWITCH_REQUEST = 43, + MSG_GPIO_RATE_REQUEST = 47, + MSG_GPIO_RATE = 53, + MSG_GPIO_RATE_CFG = 59, + MSG_GEO_POS = 61, + MSG_ADC_SAMPLE = 67, + MSG_ADC_SAMPLE_REQUEST = 71, + MSG_DAC_READBACK = 73, + MSG_DAC_REQUEST = 79, + MSG_GAIN_SWITCH = 83, + MSG_GAIN_SWITCH_REQUEST = 89, + MSG_PREAMP_SWITCH = 97, + MSG_PREAMP_SWITCH_REQUEST = 101, + MSG_TEMPERATURE = 103, + MSG_TEMPERATURE_REQUEST = 107, + MSG_DAC_EEPROM_SET = 109, + MSG_CALIB_SET = 127, + MSG_CALIB_REQUEST = 131, + MSG_I2C_STATS = 137, + MSG_I2C_STATS_REQUEST = 139, + MSG_GNSS_SATS = 149, + MSG_CALIB_SAVE = 151, + MSG_UBX_TIME_ACCURACY = 157, + MSG_I2C_SCAN_BUS = 163, + MSG_UBX_TXBUF = 167, + MSG_UBX_TXBUF_PEAK = 173, + MSG_UBX_MONHW = 179, + MSG_UBX_VERSION = 181, + MSG_UBX_FIXSTATUS = 191, + MSG_UBX_EVENTCOUNTER = 193, + MSG_UBX_RESET = 197, + MSG_UBX_CONFIG_DEFAULT = 199, + MSG_UBX_FREQ_ACCURACY = 211, + MSG_UBX_MONHW2 = 213, + MSG_UBX_GNSS_CONFIG = 221, + MSG_UBX_UPTIME = 223, + MSG_UBX_CFG_TP5 = 227, + MSG_GPIO_RATE_RESET = 229, + MSG_HISTOGRAM = 233, + MSG_UBX_CFG_SAVE = 239, + MSG_UBX_RXBUF = 241, + MSG_UBX_RXBUF_PEAK = 251, + MSG_EVENTTRIGGER = 257, + MSG_EVENTTRIGGER_REQUEST = 263, + MSG_SPI_STATS = 269, + MSG_SPI_STATS_REQUEST = 271, + MSG_HISTOGRAM_CLEAR = 277, + MSG_ADC_TRACE = 281, + MSG_ADC_MODE = 283, + MSG_ADC_MODE_REQUEST = 293, + MSG_LOG_INFO = 307, + MSG_FILE_DOWNLOAD = 311, + MSG_OLED_ENTRIES = 313, + MSG_RATE_SCAN = 317, + MSG_MQTT_STATUS = 331, + MSG_GPIO_INHIBIT = 337, + MSG_UBX_TIMEMARK = 349, + MSG_POLARITY_SWITCH = 353, + MSG_POLARITY_SWITCH_REQUEST = 359, + MSG_MQTT_INHIBIT = 367 +}; + +#endif // TCPMESSAGE_KEYS_H diff --git a/library/include/ublox_messages.h b/library/include/ublox_messages.h new file mode 100644 index 00000000..c8bf41df --- /dev/null +++ b/library/include/ublox_messages.h @@ -0,0 +1,118 @@ +#ifndef UBLOX_MESSAGES_H +#define UBLOX_MESSAGES_H + +#include "muondetector_shared_global.h" + +#define UBLOX_VERSION 7 +// not in this list are all msg of types: RXM, LOG, AID and INF + +// list of UBX message Cls/ID +#define UBX_ACK 0x0501 +#define UBX_NAK 0x0500 + +#define UBX_NAV_CLOCK 0x0122 +#define UBX_NAV_DGPS 0x0131 +#define UBX_NAV_AOPSTATUS 0x0160 +#define UBX_NAV_DOP 0x0104 +#define UBX_NAV_EOE 0x0161 // not supportet on U-Blox 7 +#define UBX_NAV_GEOFENCE 0x0139 // not supportet on U-Blox 7 +#define UBX_NAV_ODO 0x0109 // not supportet on U-Blox 7 +#define UBX_NAV_ORB 0x0134 // not supportet on U-Blox 7 +#define UBX_NAV_POSECEF 0x0101 +#define UBX_NAV_POSLLH 0x0102 +#define UBX_NAV_PVT 0x0107 +#define UBX_NAV_RESETODO 0x0110 // not supportet on U-Blox 7 +#define UBX_NAV_SAT 0x0135 // not supportet on U-Blox 7 +#define UBX_NAV_SBAS 0x0132 +#define UBX_NAV_SOL 0x0106 +#define UBX_NAV_STATUS 0x0103 +#define UBX_NAV_SVINFO 0x0130 +#define UBX_NAV_TIMEBDS 0x0124 // not supportet on U-Blox 7 +#define UBX_NAV_TIMEGAL 0x0125 // not supportet on U-Blox 7 +#define UBX_NAV_TIMEGLO 0x0123 // not supportet on U-Blox 7 +#define UBX_NAV_TIMEGPS 0x0120 +#define UBX_NAV_TIMELS 0x0126 // not supportet on U-Blox 7 +#define UBX_NAV_TIMEUTC 0x0121 +#define UBX_NAV_VELECEF 0x0111 +#define UBX_NAV_VELNED 0x0112 + +#define UBX_CFG_ANT 0x0613 +#define UBX_CFG_CFG 0x0609 +#define UBX_CFG_DAT 0x0606 +#define UBX_CFG_DOSC 0x0661 // not supportet on U-Blox 7 (only with time & frequency sync products) +#define UBX_CFG_DYNSEED 0x0685 // not supportet on U-Blox 7 +#define UBX_CFG_ESRC 0x0660 // not supportet on U-Blox 7 (only with time & frequency sync products) +#define UBX_CFG_FIXSEED 0x0684 // not supportet on U-Blox 7 +#define UBX_CFG_GEOFENCE 0x0669 // not supportet on U-Blox 7 +#define UBX_CFG_GNSS 0x063e +#define UBX_CFG_INF 0x0602 +#define UBX_CFG_ITFM 0x0639 +#define UBX_CFG_LOGFILTER 0x0647 +#define UBX_CFG_MSG 0x0601 +#define UBX_CFG_NAV5 0x0624 +#define UBX_CFG_NAVX5 0x0623 +#define UBX_CFG_NMEA 0x0617 +#define UBX_CFG_ODO 0x061e // not supportet on U-Blox 7 +#define UBX_CFG_PM2 0x063b +#define UBX_CFG_PMS 0x0686 // not supportet on U-Blox 7 +#define UBX_CFG_PRT 0x0600 +#define UBX_CFG_PWR 0x0657 // not supportet on U-Blox 7 +#define UBX_CFG_RATE 0x0608 +#define UBX_CFG_RINV 0x0634 +#define UBX_CFG_RST 0x0604 +#define UBX_CFG_RXM 0x0611 +#define UBX_CFG_SBAS 0x0616 +#define UBX_CFG_SMGR 0x0662 // not supportet on U-Blox 7 (only with time & frequency sync products) +#define UBX_CFG_TMODE2 0x063d // not supportet on U-Blox 7 (only for timing receivers) +#define UBX_CFG_TP5 0x0631 +#define UBX_CFG_TXSLOT 0x0653 // not supportet on U-Blox 7 (only with time & frequency sync products) +#define UBX_CFG_USB 0x061b + +#define UBX_TIM_TP 0x0d01 +#define UBX_TIM_TM2 0x0d03 +#define UBX_TIM_VRFY 0x0d06 + +#define UBX_MON_VER 0x0a04 +#define UBX_MON_GNSS 0x0a28 // not supportet on U-Blox 7 +#define UBX_MON_HW 0x0a09 +#define UBX_MON_HW2 0x0a0b +#define UBX_MON_IO 0x0a02 +#define UBX_MON_MSGPP 0x0a06 +#define UBX_MON_PATCH 0x0a27 // not supportet on U-Blox 7 +#define UBX_MON_RXBUF 0x0a07 +#define UBX_MON_RXR 0x0a21 +#define UBX_MON_SMGR 0x0a2e // not supportet on U-Blox 7 (only with time & frequency sync products) +#define UBX_MON_TXBUF 0x0a08 + +// list of NMEA message Cls/ID +#define UBX_NMEA_DTM 0xf00a +#define UBX_NMEA_GBQ 0xf044 +#define UBX_NMEA_GBS 0xf009 +#define UBX_NMEA_GGA 0xf000 +#define UBX_NMEA_GLL 0xf001 +#define UBX_NMEA_GLQ 0xf043 +#define UBX_NMEA_GNQ 0xf042 +#define UBX_NMEA_GNS 0xf00d +#define UBX_NMEA_GPQ 0xf040 +#define UBX_NMEA_GRS 0xf006 +#define UBX_NMEA_GSA 0xf002 +#define UBX_NMEA_GST 0xf007 +#define UBX_NMEA_GSV 0xf003 +#define UBX_NMEA_RMC 0xf004 +#define UBX_NMEA_TXT 0xf041 +#define UBX_NMEA_VLW 0xf00f +#define UBX_NMEA_VTG 0xf005 +#define UBX_NMEA_ZDA 0xf008 +#define UBX_NMEA_CONFIG 0xf141 +#define UBX_NMEA_POSITION 0xf100 +#define UBX_NMEA_RATE 0xf140 +#define UBX_NMEA_SVSTATUS 0xf103 +#define UBX_NMEA_TIME 0xf104 + +// proto is the shortcut for protocol and +// is defined as the correct bitmask for one +// protocol +#define PROTO_UBX 1 +#define PROTO_NMEA 0b10 +#define PROTO_RTCM3 0b100000 +#endif // UBLOX_MESSAGES_H diff --git a/library/include/ublox_structs.h b/library/include/ublox_structs.h new file mode 100644 index 00000000..628aaf4a --- /dev/null +++ b/library/include/ublox_structs.h @@ -0,0 +1,69 @@ +#ifndef UBLOX_STRUCTS_H +#define UBLOX_STRUCTS_H + +#include +#include +#include + +#include "muondetector_structs.h" + +struct GeodeticPos; +class GnssSatellite; + +struct UbxMessage { +public: + uint16_t msgID; + std::string data; +}; + +struct gpsTimestamp { + struct timespec rising_time; + struct timespec falling_time; + double accuracy_ns; + bool valid; + int channel; + bool rising; + bool falling; + int counter; +}; + +template +class gpsProperty { +public: + gpsProperty() + : value() + { + updated = false; + } + gpsProperty(const T& val) + { + value = val; + updated = true; + lastUpdate = std::chrono::system_clock::now(); + } + std::chrono::time_point lastUpdate; + std::chrono::duration updatePeriod; + std::chrono::duration updateAge() { return std::chrono::system_clock::now() - lastUpdate; } + bool updated; + gpsProperty& operator=(const T& val) + { + value = val; + lastUpdate = std::chrono::system_clock::now(); + updated = true; + return *this; + } + const T& operator()() + { + updated = false; + return value; + } + +private: + T value; +}; + +struct UbxDopStruct { + uint16_t gDOP = 0, pDOP = 0, tDOP = 0, vDOP = 0, hDOP = 0, nDOP = 0, eDOP = 0; +}; + +#endif // UBLOX_STRUCTS_H diff --git a/library/include/ubx_msg_key_name_map.h b/library/include/ubx_msg_key_name_map.h new file mode 100644 index 00000000..641f943d --- /dev/null +++ b/library/include/ubx_msg_key_name_map.h @@ -0,0 +1,100 @@ +#ifndef UBX_UBX_KEY_NAME_MAP_H +#define UBX_UBX_KEY_NAME_MAP_H + +#include "muondetector_shared_global.h" +#include "ublox_messages.h" + +#include +#include +#include + +const QMap ubxMsgKeyNameMap({ { UBX_ACK, "ACK-ACK" }, + { UBX_NAK, "ACK-NAK" }, + // NAV + { UBX_NAV_CLOCK, "NAV-CLOCK" }, + { UBX_NAV_DGPS, "NAV-DGPS" }, + { UBX_NAV_AOPSTATUS, "NAV-AOPSTATUS" }, + { UBX_NAV_DOP, "NAV-DOP" }, + { UBX_NAV_POSECEF, "NAV-POSECEF" }, + { UBX_NAV_POSLLH, "NAV-POSLLH" }, + { UBX_NAV_PVT, "NAV-PVT" }, + { UBX_NAV_SBAS, "NAV-SBAS" }, + { UBX_NAV_SOL, "NAV-SOL" }, + { UBX_NAV_STATUS, "NAV-STATUS" }, + { UBX_NAV_SVINFO, "NAV-SVINFO" }, + { UBX_NAV_TIMEGPS, "NAV-TIMEGPS" }, + { UBX_NAV_TIMEUTC, "NAV-TIMEUTC" }, + { UBX_NAV_VELECEF, "NAV-VELECEF" }, + { UBX_NAV_VELNED, "NAV-VELNED" }, + // CFG + { UBX_CFG_ANT, "CFG-ANT" }, + { UBX_CFG_CFG, "CFG-CFG" }, + { UBX_CFG_DAT, "CFG-DAT" }, + { UBX_CFG_GNSS, "CFG-GNSS" }, + { UBX_CFG_INF, "CFG-INF" }, + { UBX_CFG_ITFM, "CFG-ITFM" }, + { UBX_CFG_LOGFILTER, "CFG-LOGFILTER" }, + { UBX_CFG_MSG, "CFG-MSG" }, + { UBX_CFG_NAV5, "CFG-NAV5" }, + { UBX_CFG_NAVX5, "CFG-NAV5X" }, + { UBX_CFG_NMEA, "CFG-NMEA" }, + { UBX_CFG_PM2, "CFG-PM2" }, + { UBX_CFG_PRT, "CFG-PRT" }, + { UBX_CFG_RATE, "CFG-RATE" }, + { UBX_CFG_RINV, "CFG-RINV" }, + { UBX_CFG_RST, "CFG-RST" }, + { UBX_CFG_RXM, "CFG-RXM" }, + { UBX_CFG_SBAS, "CFG-SBAS" }, + { UBX_CFG_TP5, "CFG-TP5" }, + { UBX_CFG_USB, "CFG-USB" }, + // TIM + { UBX_TIM_TP, "TIM-TP" }, + { UBX_TIM_TM2, "TIM-TM2" }, + { UBX_TIM_VRFY, "TIM-VRFY" }, + // MON + { UBX_MON_VER, "MON-VER" }, + { UBX_MON_HW, "MON-HW" }, + { UBX_MON_HW2, "MON-HW2" }, + { UBX_MON_IO, "MON-IO" }, + { UBX_MON_MSGPP, "MON-MSGP" }, + { UBX_MON_RXBUF, "MON-RXBUF" }, + { UBX_MON_RXR, "MON-RXR" }, + { UBX_MON_TXBUF, "MON-TXBUF" }, + + // the messages only used in Ublox-8 + { UBX_NAV_EOE, "NAV-EOE" }, + { UBX_NAV_GEOFENCE, "NAV-GEOFENCE" }, + { UBX_NAV_ODO, "NAV-ODO" }, + { UBX_NAV_ORB, "NAV-ORB" }, + { UBX_NAV_RESETODO, "NAV-RESETODO" }, + { UBX_NAV_SAT, "NAV-SAT" }, + { UBX_NAV_TIMEBDS, "NAV-TIMEBDS" }, + { UBX_NAV_TIMEGAL, "NAV-TIMEGAL" }, + { UBX_NAV_TIMEGLO, "NAV-TIMEGLO" }, + { UBX_NAV_TIMELS, "NAV-TIMELS" }, + + // NMEA + { UBX_NMEA_DTM, "NMEA-DTM" }, + { UBX_NMEA_GBQ, "NMEA-GBQ" }, + { UBX_NMEA_GBS, "NMEA-GBS" }, + { UBX_NMEA_GGA, "NMEA-GGA" }, + { UBX_NMEA_GLL, "NMEA-GLL" }, + { UBX_NMEA_GLQ, "NMEA-GLQ" }, + { UBX_NMEA_GNQ, "NMEA-GNQ" }, + { UBX_NMEA_GNS, "NMEA-GNS" }, + { UBX_NMEA_GPQ, "NMEA-GPQ" }, + { UBX_NMEA_GRS, "NMEA-GRS" }, + { UBX_NMEA_GSA, "NMEA-GSA" }, + { UBX_NMEA_GST, "NMEA-GST" }, + { UBX_NMEA_GSV, "NMEA-GSV" }, + { UBX_NMEA_RMC, "NMEA-RMC" }, + { UBX_NMEA_TXT, "NMEA-TXT" }, + { UBX_NMEA_VLW, "NMEA-VLW" }, + { UBX_NMEA_VTG, "NMEA-VTG" }, + { UBX_NMEA_ZDA, "NMEA-ZDA" }, + { UBX_NMEA_CONFIG, "NMEA-CONFIG" }, + { UBX_NMEA_POSITION, "NMEA-POSITION" }, + { UBX_NMEA_RATE, "NMEA-RATE" }, + { UBX_NMEA_SVSTATUS, "NMEA-SVSTATUS" }, + { UBX_NMEA_TIME, "NMEA-TIME" } }); +#endif // UBX_UBX_KEY_NAME_MAP_H diff --git a/source/library/muondetector.conf b/library/muondetector.conf similarity index 100% rename from source/library/muondetector.conf rename to library/muondetector.conf diff --git a/library/src/config.cpp b/library/src/config.cpp new file mode 100644 index 00000000..97d610a7 --- /dev/null +++ b/library/src/config.cpp @@ -0,0 +1,10 @@ +#include "config.h" +#include + +namespace MuonPi::Version { +auto Version::string() const -> std::string +{ + return std::to_string(major) + "." + std::to_string(minor) + "." + std::to_string(patch) + ((std::strlen(additional) > 0) ? ("-" + std::string { additional }) : ("")) + ((std::strlen(hash) > 0) ? ("-" + std::string { hash }) : ("")); +} + +} diff --git a/library/src/histogram.cpp b/library/src/histogram.cpp new file mode 100644 index 00000000..558e3791 --- /dev/null +++ b/library/src/histogram.cpp @@ -0,0 +1,267 @@ +//#include +#include +#include +#include + +#include "histogram.h" + +Histogram::Histogram(const std::string& name, int nrBins, double min, double max) + : fName(name) + , fNrBins(nrBins) + , fMin(min) + , fMax(max) +{ +} + +Histogram::~Histogram() +{ + fHistogramMap.clear(); +} + +void Histogram::clear() +{ + fHistogramMap.clear(); + fUnderflow = fOverflow = 0.; +} + +void Histogram::setName(const std::string& name) +{ + fName = name; +} + +void Histogram::setUnit(const std::string& unit) +{ + fUnit = unit; +} + +void Histogram::setNrBins(int bins) +{ + fNrBins = bins; + clear(); +} + +int Histogram::getNrBins() const +{ + return fNrBins; +} + +void Histogram::setMin(double val) +{ + fMin = val; +} + +double Histogram::getMin() const +{ + return fMin; +} + +void Histogram::setMax(double val) +{ + fMax = val; +} + +double Histogram::getMax() const +{ + return fMax; +} + +double Histogram::getRange() const +{ + return fMax - fMin; +} + +double Histogram::getCenter() const +{ + return 0.5 * getRange() + fMin; +} + +double Histogram::getBinCenter(int bin) const +{ + return bin2Value(bin); +} + +int Histogram::getLowestOccupiedBin() const +{ + if (fHistogramMap.empty()) + return -1; + auto it = fHistogramMap.begin(); + while (it != fHistogramMap.end() && it->second < 1e-3) + ++it; + if (it == fHistogramMap.end()) + return -1; + return it->first; +} + +int Histogram::getHighestOccupiedBin() const +{ + if (fHistogramMap.empty()) + return -1; + auto it = --fHistogramMap.end(); + while (it != fHistogramMap.begin() && it->second < 1e-3) + --it; + if (it == fHistogramMap.begin()) + return 0; + return it->first; +} + +void Histogram::fill(double x, double mult) +{ + int bin = value2Bin(x); + if ( fAutoscale && getEntries() < 1e-6 ) { + // initial fill, so lets see if we should rescale to the first value + if ( bin < 0 || bin >= fNrBins ) { + rescale( x ); + fill( x, mult ); + return; + } + } + if (bin < 0) { + fUnderflow += mult; + } else if (bin >= fNrBins) { + fOverflow += mult; + } else + fHistogramMap[bin] += mult; +} + +void Histogram::setBinContent(int bin, double value) +{ + if (bin >= 0 && bin < fNrBins) + fHistogramMap[bin] = value; +} + +double Histogram::getBinContent(int bin) const +{ + if (bin >= 0 && bin < fNrBins) { + try { + auto it = fHistogramMap.find(bin); + if (it != fHistogramMap.end()) + return fHistogramMap.at(bin); + else + return double(); + } catch (...) { + return double(); + } + } else + return double(); +} + +double Histogram::getMean() +{ + double sum = 0., entries = 0.; + for (const auto& entry : fHistogramMap) { + entries += entry.second; + sum += bin2Value(entry.first) * entry.second; + } + if (entries > 0.) + return sum / entries; + else + return 0.; +} + +double Histogram::getRMS() +{ + double mean = getMean(); + double sum = 0., entries = 0.; + for (const auto& entry : fHistogramMap) { + entries += entry.second; + double dx = bin2Value(entry.first) - mean; + sum += dx * dx * entry.second; + } + if (entries > 1.) + return sqrt(sum / (entries - 1.)); + else + return 0.; +} + +double Histogram::getUnderflow() const +{ + return fUnderflow; +} + +double Histogram::getOverflow() const +{ + return fOverflow; +} + +double Histogram::getEntries() +{ + double sum = fUnderflow + fOverflow; + for (const auto& entry : fHistogramMap) { + sum += entry.second; + } + return sum; +} + +int Histogram::value2Bin(double value) const +{ + double range = fMax - fMin; + if (range <= 0.) + return -1; + int bin = (value - fMin) / range * (fNrBins - 1) + 0.5; + return bin; +} + +double Histogram::bin2Value(int bin) const +{ + double range = fMax - fMin; + if (range <= 0.) + return -1; + double value = range * bin / (fNrBins - 1) + fMin; + return value; +} + +void Histogram::rescale(double center, double width) +{ + setMin(center - width / 2.); + setMax(center + width / 2.); + clear(); +} + +void Histogram::rescale(double center) +{ + double width = getMax() - getMin(); + rescale(center, width); +} + +void Histogram::rescale() +{ + if ( !fAutoscale ) return; + + // Strategy: check if more than 1% of all entries in underflow/overflow + // set new center to old center, adjust range by 20% + // set center to newValue if histo empty or only underflow/overflow filled + // histo will not be filled with supplied value, it has to be done externally + double entries = getEntries(); + // do nothing if histo is empty + if ( entries < 3. ) { + return; + } + double ufl = getUnderflow(); + double ofl = getOverflow(); + entries -= ufl + ofl; + double range = getMax() - getMin(); + int lowest = getLowestOccupiedBin(); + int highest = getHighestOccupiedBin(); + double lowestEntry = getBinCenter(lowest); + double highestEntry = getBinCenter(highest); + if (ufl > 0. && ofl > 0. && (ufl + ofl) > 0.01 * entries) { + // range is too small, underflow and overflow have more than 1% of all entries + rescale( 0.5 * ( highestEntry-lowestEntry ) + lowestEntry, 1.2 * range ); + } else if ( ufl > 0.005 * entries ) { + setMin( getMax() - range * 1.2 ); + clear(); + } else if ( ofl > 0.005 * entries ) { + setMax( getMin() + range * 1.2 ); + clear(); + } else if ( ufl < 1e-3 && ofl < 1e-3 ) { + // check if range is too wide + if ( entries > 1000. && static_cast(highest-lowest)/fNrBins < 0.05 ) { + rescale( 0.5 * ( highestEntry-lowestEntry ) + lowestEntry, 0.8 * range ); + } + } +} + +void Histogram::setAutoscale( bool autoscale ) +{ + fAutoscale = autoscale; +} diff --git a/source/library/src/mqtthandler.cpp b/library/src/mqtthandler.cpp similarity index 95% rename from source/library/src/mqtthandler.cpp rename to library/src/mqtthandler.cpp index 3d81a9c6..5dbe9e03 100644 --- a/source/library/src/mqtthandler.cpp +++ b/library/src/mqtthandler.cpp @@ -61,7 +61,6 @@ void MqttHandler::callback_disconnected(int result) if (result != 0) { qWarning() << "Mqtt disconnected unexpectedly: " + QString::number(result); set_status(Status::Error); - m_tries = 1; emit request_timer_start(Config::MQTT::timeout * m_tries); } else { set_status(Status::Disconnected); @@ -76,6 +75,14 @@ void MqttHandler::callback_message(const mosquitto_message* message) void MqttHandler::set_status(Status status) { + if (status == Status::Error) { + m_tries++; + qWarning() << "Tried: "< s_max_tries) { + exit(0); + emit giving_up(); + } + } if (m_status != status) { if (status == Status::Connected) { emit mqttConnectionStatus(true); @@ -91,13 +98,10 @@ MqttHandler::MqttHandler(const QString& station_id, const int verbosity) , m_verbose { verbosity } { m_reconnect_timer.setInterval(Config::MQTT::timeout); - m_reconnect_timer.setSingleShot(true); connect(&m_reconnect_timer, &QTimer::timeout, this, [this](){mqttConnect();}); - connect(this, &MqttHandler::request_timer_stop, &m_reconnect_timer, &QTimer::stop); - connect(this, &MqttHandler::request_timer_restart, this, &MqttHandler::timer_restart); - connect(this, &MqttHandler::request_timer_start, this, &MqttHandler::timer_start); } + MqttHandler::~MqttHandler() { mqttDisconnect(); @@ -135,7 +139,6 @@ void MqttHandler::start(const QString& username, const QString& password){ void MqttHandler::mqttConnect(){ if (connected()) { - qDebug() << "Already connected to Mqtt."; return; } qDebug() << "Trying to connect to MQTT."; @@ -211,6 +214,7 @@ void MqttHandler::cleanup() { mosquitto_lib_cleanup(); } } + void MqttHandler::subscribe(const QString& topic) { if (!connected()) { diff --git a/source/library/src/tcpconnection.cpp b/library/src/tcpconnection.cpp similarity index 55% rename from source/library/src/tcpconnection.cpp rename to library/src/tcpconnection.cpp index 4b2f604c..9321bd80 100644 --- a/source/library/src/tcpconnection.cpp +++ b/library/src/tcpconnection.cpp @@ -1,22 +1,17 @@ #include "tcpconnection.h" #include "tcpmessage_keys.h" -#include -#include #include #include +#include +#include #if defined(Q_OS_UNIX) -#include #include +#include #endif -/* -std::vector TcpConnection::globalConnectionList; -uint32_t TcpConnection::globalNrBytesRead; -uint32_t TcpConnection::globalNrBytesWritten; -*/ TcpConnection::TcpConnection(QString newHostName, quint16 newPort, int newVerbose, int newTimeout, - int newPingInterval, QObject *parent) + int newPingInterval, QObject* parent) : QObject(parent) { verbose = newVerbose; @@ -24,29 +19,26 @@ TcpConnection::TcpConnection(QString newHostName, quint16 newPort, int newVerbos port = newPort; timeout = newTimeout; pingInterval = newPingInterval; - //qRegisterMetaType >("QVector"); } -TcpConnection::TcpConnection(int socketDescriptor, int newVerbose, int newTimeout, int newPingInterval, QObject *parent) +TcpConnection::TcpConnection(int socketDescriptor, int newVerbose, int newTimeout, int newPingInterval, QObject* parent) : QObject(parent) - , m_socketDescriptor(socketDescriptor)//, text(data) + , m_socketDescriptor(socketDescriptor) { pingInterval = newPingInterval; timeout = newTimeout; verbose = newVerbose; - //qRegisterMetaType >("QVector"); } TcpConnection::~TcpConnection() { - if (in!=nullptr){ delete in; in = nullptr; } - if (!t.isNull()){ + if (in != nullptr) { + delete in; + in = nullptr; + } + if (!t.isNull()) { t.clear(); } -/* - auto it = std::find(globalConnectionList.begin(), globalConnectionList.end(), this); - if (it != globalConnectionList.end()) globalConnectionList.erase(it); -*/ } void TcpConnection::makeConnection() @@ -63,7 +55,6 @@ void TcpConnection::makeConnection() in->setVersion(QDataStream::Qt_4_0); in->setDevice(tcpSocket); connect(tcpSocket, &QTcpSocket::readyRead, this, &TcpConnection::onReadyRead); - //connect(tcpSocket, &QTcpSocket::disconnected, this, &TcpConnection::disconnected); tcpSocket->connectToHost(hostName, port); firstConnection = time(NULL); lastConnection = firstConnection; @@ -72,26 +63,24 @@ void TcpConnection::makeConnection() this->thread()->quit(); return; } - //globalConnectionList.push_back(this); emit connected(); peerAddress = tcpSocket->peerAddress().toString(); - emit toConsole(QString("makeConnection: peer1 ")+peerAddress); - if(peerAddress!=""){ + emit toConsole(QString("makeConnection: peer1 ") + peerAddress); + if (peerAddress != "") { peerAddress = peerAddress.split(':').last(); } - emit toConsole(QString("makeConnection: peer2 ")+peerAddress); + emit toConsole(QString("makeConnection: peer2 ") + peerAddress); localAddress = tcpSocket->localAddress().toString(); - if(localAddress!=""){ + if (localAddress != "") { localAddress = localAddress.split(':').last(); } peerPort = tcpSocket->peerPort(); localPort = tcpSocket->localPort(); - bytesRead=bytesWritten=0; - //startTimePulser(); + bytesRead = bytesWritten = 0; } void TcpConnection::receiveConnection() -{ // setting up tcpSocket. +{ // setting up tcpSocket. // only done once #if defined(Q_OS_UNIX) if (verbose > 4) { @@ -105,20 +94,17 @@ void TcpConnection::receiveConnection() return; } peerAddress = tcpSocket->peerAddress().toString(); - //emit toConsole(QString("receiveConnection: peer1 ")+peerAddress); - if(peerAddress!=""){ + if (peerAddress != "") { peerAddress = peerAddress.split(':').last(); } - //emit toConsole(QString("receiveConnection: peer2 ")+peerAddress); localAddress = tcpSocket->localAddress().toString(); - if(localAddress!=""){ + if (localAddress != "") { localAddress = localAddress.split(':').last(); } peerPort = tcpSocket->peerPort(); localPort = tcpSocket->localPort(); lastConnection = time(NULL); - //connect(tcpSocket, &QTcpSocket::disconnected, this, &TcpConnection::onSocketDisconnected); in = new QDataStream(); in->setVersion(QDataStream::Qt_4_0); in->setDevice(tcpSocket); @@ -126,19 +112,20 @@ void TcpConnection::receiveConnection() firstConnection = time(NULL); lastConnection = firstConnection; emit madeConnection(peerAddress, peerPort, localAddress, localPort); - bytesRead=bytesWritten=0; - //startTimePulser(); + bytesRead = bytesWritten = 0; } -void TcpConnection::closeConnection(QString closedAddress) { - if (peerAddress!=""){ - if (peerAddress==closedAddress){ +void TcpConnection::closeConnection(QString closedAddress) +{ + if (peerAddress != "") { + if (peerAddress == closedAddress) { closeThisConnection(); } } } -void TcpConnection::closeThisConnection(){ +void TcpConnection::closeThisConnection() +{ TcpMessage quitMessage(TCP_MSG_KEY::MSG_QUIT_CONNECTION); *(quitMessage.dStream) << localAddress; sendTcpMessage(quitMessage); @@ -146,13 +133,14 @@ void TcpConnection::closeThisConnection(){ return; } -void TcpConnection::onReadyRead() { +void TcpConnection::onReadyRead() +{ // this function gets called when tcpSocket emits readyRead signal if (!in) { emit toConsole("input stream not yet initialized"); return; } - while(tcpSocket->bytesAvailable()!=0){ + while (tcpSocket->bytesAvailable() != 0) { if (blockSize == 0) { if (tcpSocket->bytesAvailable() < (int)(sizeof(quint16))) { return; @@ -162,117 +150,74 @@ void TcpConnection::onReadyRead() { if (tcpSocket->bytesAvailable() < blockSize) { return; } -// if (tcpSocket->bytesAvailable() > blockSize) { -// emit toConsole(QString(QString::number(tcpSocket->bytesAvailable() - blockSize) -// + " more Bytes available than expected by blockSize")); -// } - //qDebug() << "blockSize: " << blockSize; QByteArray block; char* data; - data = (char *) malloc (blockSize); - if (data==NULL){ + data = (char*)malloc(blockSize); + if (data == NULL) { qDebug() << "critical error: memory allocation of " << blockSize << " bytes failed. Memory full?"; exit(1); } - in->readRawData(data,blockSize); - QDataStream str(&block,QIODevice::ReadWrite); + in->readRawData(data, blockSize); + QDataStream str(&block, QIODevice::ReadWrite); str << blockSize; - str.writeRawData(data,blockSize); - bytesRead+=blockSize; - //globalNrBytesRead+=blockSize; - //block.setRawData(data,blockSize); // not sure if it works correctly + str.writeRawData(data, blockSize); + bytesRead += blockSize; blockSize = 0; - //*in >> block; - //qDebug() << block.size()-2 << "Bytes read: "; // -2 because "str << blockSize" makes - // uint16_t blockSize itself part of block - if (verbose > 4){ + if (verbose > 4) { qDebug() << block; } TcpMessage tcpMessage(block); emit receivedTcpMessage(tcpMessage); - // emit toConsole("something went wrong with the transmission code"); } } -bool TcpConnection::sendTcpMessage(TcpMessage tcpMessage) { +bool TcpConnection::sendTcpMessage(TcpMessage tcpMessage) +{ QByteArray block; block = tcpMessage.getData(); QDataStream stream(&block, QIODevice::ReadWrite); stream.device()->seek(0); stream << (quint16)(block.size() - (int)sizeof(quint16)); // size of payload - if (verbose > 4){ + if (verbose > 4) { qDebug() << block; } return writeBlock(block); } -bool TcpConnection::writeBlock(const QByteArray &block) { +bool TcpConnection::writeBlock(const QByteArray& block) +{ if (!tcpSocket) { emit toConsole("in client => tcpConnection:\ntcpSocket not instantiated"); return false; } tcpSocket->write(block); - bytesWritten+=block.size(); - //globalNrBytesWritten+=block.size(); + bytesWritten += block.size(); for (int i = 0; i < 3; i++) { if (tcpSocket->state() != QTcpSocket::UnconnectedState) { if (!tcpSocket->waitForBytesWritten(timeout)) { - //emit toConsole("wait for bytes written timeout"); - quint32 connectionDuration = (quint32)(time(NULL)-firstConnection); + quint32 connectionDuration = (quint32)(time(NULL) - firstConnection); quint32 timeoutTime = (quint32)time(NULL); - emit connectionTimeout(peerAddress,peerPort,localAddress,localPort,timeoutTime,connectionDuration); + emit connectionTimeout(peerAddress, peerPort, localAddress, localPort, timeoutTime, connectionDuration); this->deleteLater(); return false; } return true; - } - else { - //emit toConsole("client unconnected"); + } else { delay(100); } } - if (verbose > 1){ + if (verbose > 1) { emit toConsole("tcp unconnected state before wait for bytes written, closing connection"); } this->thread()->quit(); return false; } -/* -void TcpConnection::onTimePulse(){ - if (fabs(time(NULL)-lastConnection)>timeout/1000){ - // hier einfügen, was passiert, wenn host nicht auf ping antwortet - quint32 connectionDuration = (quint32)(time(NULL)-firstConnection); - quint32 timeoutTime = (quint32)time(NULL); - sendCode(timeoutSig); - emit connectionTimeout(peerAddress->toString(),peerPort,localAddress->toString(),localPort,timeoutTime,connectionDuration); - this->deleteLater(); - return; - } - if (tcpSocket){ - if (verbose>3){ - emit toConsole("sending ping"); - } - sendCode(ping); - } -} - -void TcpConnection::startTimePulser() -{ - t = new QTimer(this); - t->setInterval(pingInterval); - connect(this, &TcpConnection::stopTimePulser, t, &QTimer::stop); - connect(t, &QTimer::timeout, this, &TcpConnection::onTimePulse); - t->start(); -} -*/ void TcpConnection::delay(int millisecondsWait) { QEventLoop loop; QTimer delay; - //connect(this, &TcpConnection::posixTerminate, &loop, &QEventLoop::quit); - //connect(tcpSocket, &QTcpSocket::disconnected, &loop, &QEventLoop::quit); delay.connect(&delay, &QTimer::timeout, &loop, &QEventLoop::quit); delay.start(millisecondsWait); loop.exec(); diff --git a/source/library/src/tcpmessage.cpp b/library/src/tcpmessage.cpp similarity index 64% rename from source/library/src/tcpmessage.cpp rename to library/src/tcpmessage.cpp index e08cde40..1e221972 100644 --- a/source/library/src/tcpmessage.cpp +++ b/library/src/tcpmessage.cpp @@ -13,17 +13,9 @@ TcpMessage::TcpMessage(quint16 tcpMsgID) } TcpMessage::TcpMessage(QByteArray& rawdata) - : m_data {rawdata} + : m_data { rawdata } { - // quint64 pos = dStream->device()->pos(); dStream = new QDataStream(&m_data, QIODevice::ReadWrite); - // if (!dStream->device()->seek(0)){ - // qDebug() << "failed to seek position " << 0 << " in dStream"; - // } - // *dStream >> msgID; - // if(!dStream->device()->seek(pos)){ - // qDebug() << "failed to seek position " << pos << " in dStream"; - // } *dStream >> m_byteCount; *dStream >> m_msgID; } @@ -50,22 +42,27 @@ TcpMessage::TcpMessage(const TcpMessage& tcpMessage) m_byteCount = tcpMessage.getByteCount(); } -void TcpMessage::setData(QByteArray& rawData) { +void TcpMessage::setData(QByteArray& rawData) +{ m_data = rawData; } -void TcpMessage::setMsgID(quint16 tcpMsgID) { +void TcpMessage::setMsgID(quint16 tcpMsgID) +{ m_msgID = tcpMsgID; } -const QByteArray& TcpMessage::getData() const{ +const QByteArray& TcpMessage::getData() const +{ return m_data; } -quint16 TcpMessage::getMsgID() const{ +quint16 TcpMessage::getMsgID() const +{ return m_msgID; } -quint16 TcpMessage::getByteCount() const{ +quint16 TcpMessage::getByteCount() const +{ return m_byteCount; } diff --git a/source/CMakeLists.txt b/source/CMakeLists.txt deleted file mode 100644 index 4b41033e..00000000 --- a/source/CMakeLists.txt +++ /dev/null @@ -1,98 +0,0 @@ -cmake_minimum_required (VERSION 3.10) -project (muondetector LANGUAGES CXX C) - -string(TIMESTAMP PROJECT_DATE_STRING "%b %d, %Y") - -include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/version.cmake") - -option(MUONDETECTOR_BUILD_GUI "Build the gui for the muondetector" ON) -option(MUONDETECTOR_BUILD_DAEMON "Build the daemon for the muondetector" OFF) - -if ((${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv7l")) - set(MUONDETECTOR_BUILD_DAEMON ON) -endif () - -set(MUONDETECTOR_CONFIG_DIR "${CMAKE_CURRENT_SOURCE_DIR}/config") - -set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/lib") -set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/lib") -set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/bin") - -set(CMAKE_CXX_STANDARD 17) -set(CMAKE_CXX_STANDARD_REQUIRED ON) - - -set(CMAKE_BUILD_TYPE Release) - -add_compile_options( - -Wall - -O3 - ) -if (MSVC) - # Force to always compile with W4 - if(CMAKE_CXX_FLAGS MATCHES "/W[0-4]") - string(REGEX REPLACE "/W[0-4]" "/W4" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") - else() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4") - endif() -else() - -add_compile_options( - -Wextra - -Wshadow - -Wpedantic - ) - -endif() - -if (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv7l") -add_compile_options( - -mthumb - -mthumb-interwork - -march=armv7-a - ) -endif (${CMAKE_SYSTEM_PROCESSOR} STREQUAL "armv7l") - - -if (NOT WIN32) -set(CPACK_GENERATOR "DEB") -set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) -set(CPACK_DEBIAN_PACKAGE_HOMEPAGE "https://github.com/MuonPi/muondetector") -set(CPACK_DEBIAN_PACKAGE_MAINTAINER "MuonPi ") -set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT) -endif () -set(CPACK_RESOURCE_FILE_LICENSE "${MUONDETECTOR_CONFIG_DIR}/license") -set(CPACK_PACKAGE_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/packages") -set(CPACK_PACKAGE_VENDOR "MuonPi.org") -set(CPACK_PACKAGE_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") -set(CPACK_PACKAGE_VERSION_MAJOR "${PROJECT_VERSION_MAJOR}") -set(CPACK_PACKAGE_VERSION_MINOR "${PROJECT_VERSION_MINOR}") -set(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_VERSION_PATCH}") - - -set(CMAKE_AUTOUIC ON) -set(CMAKE_AUTOMOC ON) -set(CMAKE_AUTORCC ON) - - -if(NOT WIN32) # added to make program editable in qt-creator on windows - -set(Qt5_DIR "/usr/lib/x86_64-linux-gnu/cmake/Qt5/") - -endif () - - - -include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/library.cmake") - -if (MUONDETECTOR_BUILD_GUI) -include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/gui.cmake") -endif (MUONDETECTOR_BUILD_GUI) -if (MUONDETECTOR_BUILD_DAEMON) -include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/daemon.cmake") -endif (MUONDETECTOR_BUILD_DAEMON) - - -set(CPACK_DEB_COMPONENT_INSTALL ON) - -include(CPack) diff --git a/source/cmake/version.cmake b/source/cmake/version.cmake deleted file mode 100644 index bf571a2c..00000000 --- a/source/cmake/version.cmake +++ /dev/null @@ -1,3 +0,0 @@ -set(PROJECT_VERSION_MAJOR 2) -set(PROJECT_VERSION_MINOR 0) -set(PROJECT_VERSION_PATCH 1) diff --git a/source/daemon/include/geohash.h b/source/daemon/include/geohash.h deleted file mode 100644 index 8eb33c4c..00000000 --- a/source/daemon/include/geohash.h +++ /dev/null @@ -1,16 +0,0 @@ -#ifndef GEOHASH_H -#define GEOHASH_H - -#include -#include - - -class GeoHash : public QObject -{ - Q_OBJECT -public: - GeoHash()=delete; - static QString hashFromCoordinates(double lon, double lat, int precision=6); -}; - -#endif // GEOHASH_H diff --git a/source/daemon/include/gpio_mapping.h b/source/daemon/include/gpio_mapping.h deleted file mode 100644 index 432fb49f..00000000 --- a/source/daemon/include/gpio_mapping.h +++ /dev/null @@ -1,85 +0,0 @@ -#ifndef GPIO_MAPPING_H -#define GPIO_MAPPING_H -#include -#include "gpio_pin_definitions.h" - - -#define MAX_HW_VER 3 - - -// Mapping between signals of the MuonPi hardware interface and the actual GPIO pins of the RaspberryPi -// ATTENTION: -// All pins are numbered according to the BCM designation - -static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER+1] = { - { - /* Pin mapping, HW Version 0, proxy to be never used nor initializing something */ - } , - { - /* Pin mapping, HW Version 1 */ - { UBIAS_EN , 4 }, - { PREAMP_1 , 20 }, - { PREAMP_2 , 21 }, - { EVT_AND , 5 }, - { EVT_XOR , 6 }, - { GAIN_HL , 17 }, - { ADC_READY , 23 }, - { TIMEPULSE , 18 }, - { STATUS1 , 13 }, - { STATUS2 , 19 }, - { STATUS3 , 26 }, - { TDC_INTB, 24 }, - { TDC_STATUS, 25 }, - { EXT_TRIGGER, 16 } - } , - { - /* Pin mapping, HW Version 2 */ - { UBIAS_EN , 26 }, - { PREAMP_1 , 4 }, - { PREAMP_2 , 17 }, - { EVT_AND , 22 }, - { EVT_XOR , 27 }, - { GAIN_HL , 6 }, - { ADC_READY , 12 }, - { TIMEPULSE , 18 }, - { TIME_MEAS_OUT , 5 }, - { STATUS1 , 13 }, - { STATUS2 , 19 }, - { PREAMP_FAULT , 23 }, - { TDC_INTB, 20 }, - { TDC_STATUS, 21 }, - { EXT_TRIGGER, 16 } - } , - { - /* Pin mapping, HW Version 3 */ - { UBIAS_EN , 26 }, - { PREAMP_1 , 4 }, - { PREAMP_2 , 17 }, - { EVT_AND , 22 }, - { EVT_XOR , 27 }, - { GAIN_HL , 6 }, - { ADC_READY , 12 }, - { TIMEPULSE , 18 }, - { TIME_MEAS_OUT , 5 }, - { STATUS1 , 13 }, - { STATUS2 , 19 }, - { PREAMP_FAULT , 23 }, - { TDC_INTB, 20 }, - { TDC_STATUS, 21 }, - { EXT_TRIGGER, 16 }, - { IN_POL1, 24 }, - { IN_POL2, 25 } - } - }; - - -extern std::map GPIO_PINMAP; - -inline GPIO_SIGNAL bcmToGpioSignal(unsigned int bcmGpioNumber) { - std::map::const_iterator i = GPIO_PINMAP.cbegin(); - while (i != GPIO_PINMAP.cend() && i->second!=bcmGpioNumber) ++i; - if (i==GPIO_PINMAP.cend()) return UNDEFINED_SIGNAL; - return i->first; -} - -#endif //GPIO_MAPPING_H diff --git a/source/daemon/include/i2c/custom_i2cdetect.h b/source/daemon/include/i2c/custom_i2cdetect.h deleted file mode 100644 index e011357e..00000000 --- a/source/daemon/include/i2c/custom_i2cdetect.h +++ /dev/null @@ -1,39 +0,0 @@ -/* -custom_i2cdetect is directly copied from i2c-tools-3.1.2 i2cdetect.c and edited -it now contains "i2cdetect()" as a function which does the same as main() did before except a few changes. -Now it can be called by the main program and it's the only purpose of custom_i2cdetect right now. -*/ -#ifndef _CUSTOM_I2CDETECT_H -#define _CUSTOM_I2CDETECT_H - -#include "i2c/i2cbusses.h" -#include "i2c/addresses.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -#define MODE_AUTO 0 -#define I2C_BUS 1 - -int scan_i2c_bus(int file, /*int mode,*/ int first, int last, - bool outputAllAddresses, int expectedAddresses[]); -/* -struct func -{ - long value; - const char* name; -}; -static const struct func all_func[]; -*/ -//static void print_functionality(unsigned long funcs); -// int i2cdetect(); -// int i2cdetect(int expectedAddresses[]); -// c does not like overloading those functions -int i2cdetect(bool outputAllAddresses, int expectedAddresses[]); -#endif diff --git a/source/daemon/include/i2c/i2cbusses.h b/source/daemon/include/i2c/i2cbusses.h deleted file mode 100644 index 1a48e03f..00000000 --- a/source/daemon/include/i2c/i2cbusses.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - i2cbusses.h - Part of the i2c-tools package - - Copyright (C) 2004-2010 Jean Delvare - - This program is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, - MA 02110-1301 USA. - - original i2c-tools file! -*/ - -#ifndef _I2CBUSSES_H -#define _I2CBUSSES_H - -/* For strdup and snprintf */ -#define _BSD_SOURCE 1 - -#include -#include -#include /* for NAME_MAX */ -#include -#include -#include /* for strcasecmp() */ -#include -#include -#include -#include -#include -#include -#include -#include -#include "i2c/linux/i2c-dev.h" - -struct i2c_adap { - int nr; - char *name; - const char *funcs; - const char *algo; -}; - -struct i2c_adap *gather_i2c_busses(void); -void free_adapters(struct i2c_adap *adapters); - -int lookup_i2c_bus(const char *i2cbus_arg); -int parse_i2c_address(const char *address_arg); -int open_i2c_dev(int i2cbus, char *filename, size_t size, int quiet); -int set_slave_addr(int file, int address, int force); - -#define MISSING_FUNC_FMT "Error: Adapter does not have %s capability\n" - -#endif diff --git a/source/daemon/include/i2c/i2cdevices.h b/source/daemon/include/i2c/i2cdevices.h deleted file mode 100644 index e57cd423..00000000 --- a/source/daemon/include/i2c/i2cdevices.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef _I2CDEVICES_H_ -#define _I2CDEVICES_H_ -#include "i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h" -#include "i2c/i2cdevices/ads1015/ads1015.h" -#include "i2c/i2cdevices/ads1115/ads1115.h" -#include "i2c/i2cdevices/bme280/bme280.h" -#include "i2c/i2cdevices/bmp180/bmp180.h" -#include "i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h" -#include "i2c/i2cdevices/hmc5883/hmc5883.h" -#include "i2c/i2cdevices/lm75/lm75.h" -#include "i2c/i2cdevices/mcp4728/mcp4728.h" -#include "i2c/i2cdevices/pca9536/pca9536.h" -#include "i2c/i2cdevices/sht21/sht21.h" -#include "i2c/i2cdevices/sht31/sht31.h" -#include "i2c/i2cdevices/ubloxi2c/ubloxi2c.h" -#include "i2c/i2cdevices/x9119/x9119.h" -#include "i2c/i2cdevices/tca9546a/tca9546a.h" -#endif // !_I2CDEVICES_H_ diff --git a/source/daemon/include/i2c/i2cdevices/Adafruit_GFX.h b/source/daemon/include/i2c/i2cdevices/Adafruit_GFX.h deleted file mode 100644 index 459005a9..00000000 --- a/source/daemon/include/i2c/i2cdevices/Adafruit_GFX.h +++ /dev/null @@ -1,110 +0,0 @@ -/****************************************************************** - This is the core graphics library for all our displays, providing - basic graphics primitives (points, lines, circles, etc.). It needs - to be paired with a hardware-specific library for each display - device we carry (handling the lower-level functions). - - Adafruit invests time and resources providing this open - source code, please support Adafruit and open-source hardware - by purchasing products from Adafruit! - - Written by Limor Fried/Ladyada for Adafruit Industries. - BSD license, check license.txt for more information. - All text above must be included in any redistribution. - -02/18/2013 Charles-Henri Hallard (http://hallard.me) - Modified for compiling and use on Raspberry ArduiPi Board - LCD size and connection are now passed as arguments on - the command line (no more #define on compilation needed) - ArduiPi project documentation http://hallard.me/arduipi - - ******************************************************************/ - -#ifndef _ADAFRUIT_GFX_H -#define _ADAFRUIT_GFX_H - -#include -#include -#include - -#define swap(a, b) { int16_t t = a; a = b; b = t; } - -//class Adafruit_GFX : public Print { -class Adafruit_GFX { - public: - - Adafruit_GFX()=default; - // i have no idea why we have to formally call the constructor. kinda sux - void constructor(int16_t w, int16_t h); - - // this must be defined by the subclass - virtual void drawPixel(int16_t x, int16_t y, uint16_t color)=0; - virtual void invertDisplay(bool i); - - // the printf function - void printf( const char * format, ...); - void print( const char * string) ; - - - // these are 'generic' drawing functions, so we can share them! - virtual void drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, - uint16_t color); - virtual void drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color); - virtual void drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color); - virtual void drawRect(int16_t x, int16_t y, int16_t w, int16_t h, - uint16_t color); - virtual void fillRect(int16_t x, int16_t y, int16_t w, int16_t h, - uint16_t color); - - void drawVerticalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent) ; - void drawHorizontalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent) ; - - - virtual void fillScreen(uint16_t color); - - void drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color); - void drawCircleHelper(int16_t x0, int16_t y0, - int16_t r, uint8_t cornername, uint16_t color); - void fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color); - void fillCircleHelper(int16_t x0, int16_t y0, int16_t r, - uint8_t cornername, int16_t delta, uint16_t color); - - void drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, - int16_t x2, int16_t y2, uint16_t color); - void fillTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, - int16_t x2, int16_t y2, uint16_t color); - void drawRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h, - int16_t radius, uint16_t color); - void fillRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h, - int16_t radius, uint16_t color); - - void drawBitmap(int16_t x, int16_t y, - const uint8_t *bitmap, int16_t w, int16_t h, - uint16_t color); - void drawChar(int16_t x, int16_t y, unsigned char c, - uint16_t color, uint16_t bg, uint8_t size); - virtual size_t write(uint8_t); - - void setCursor(int16_t x, int16_t y); - void setTextColor(uint16_t c); - void setTextColor(uint16_t c, uint16_t bg); - void setTextSize(uint8_t s); - void setTextWrap(bool w); - - int16_t height(void); - int16_t width(void); - - void setRotation(uint8_t r); - uint8_t getRotation(void); - - protected: - int16_t WIDTH, HEIGHT; // this is the 'raw' display w/h - never changes - int16_t _width, _height; // dependent on rotation - int16_t cursor_x, cursor_y; - uint16_t textcolor, textbgcolor; - uint8_t textsize; - uint8_t rotation; - bool wrap; // If set, 'wrap' text at right edge of display -}; - -#endif diff --git a/source/daemon/include/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h b/source/daemon/include/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h deleted file mode 100644 index ebc6dda1..00000000 --- a/source/daemon/include/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h +++ /dev/null @@ -1,102 +0,0 @@ -#ifndef _ADAFRUIT_SSD1306_H_ -#define _ADAFRUIT_SSD1306_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -//class Adafruit_GFX; - -#include "i2c/i2cdevices/Adafruit_GFX.h" -// OLED defines -#define OLED_I2C_RESET RPI_V2_GPIO_P1_22 /* GPIO 25 pin 12 */ -// Oled supported display -#define OLED_ADAFRUIT_SPI_128x32 0 -#define OLED_ADAFRUIT_SPI_128x64 1 -#define OLED_ADAFRUIT_I2C_128x32 2 -#define OLED_ADAFRUIT_I2C_128x64 3 -#define OLED_SEEED_I2C_128x64 4 -#define OLED_SEEED_I2C_96x96 5 -#define OLED_LAST_OLED 6 /* always last type, used in code to end array */ - -/********************************************************************* -This is a library for our Monochrome OLEDs based on SSD1306 drivers - -Pick one up today in the adafruit shop! -------> http://www.adafruit.com/category/63_98 - -These displays use SPI to communicate, 4 or 5 pins are required to -interface - -Adafruit invests time and resources providing this open source code, -please support Adafruit and open-source hardware by purchasing -products from Adafruit! - -Written by Limor Fried/Ladyada for Adafruit Industries. -BSD license, check license.txt for more information -All text above, and the splash screen must be included in any redistribution - -02/18/2013 Charles-Henri Hallard (http://hallard.me) -Modified for compiling and use on Raspberry ArduiPi Board -LCD size and connection are now passed as arguments on -the command line (no more #define on compilation needed) -ArduiPi project documentation http://hallard.me/arduipi - -*********************************************************************/ -class Adafruit_SSD1306 : public i2cDevice, public Adafruit_GFX -{ -public: - enum { BLACK = 0, WHITE = 1 }; - - Adafruit_SSD1306() - : i2cDevice(0x3c) - { - fTitle = "SSD1306 OLED"; init(OLED_ADAFRUIT_I2C_128x64, -1); - } - Adafruit_SSD1306(const char* busAddress, uint8_t slaveAddress) - : i2cDevice(busAddress, slaveAddress) - { - fTitle = "SSD1306 OLED"; init(OLED_ADAFRUIT_I2C_128x64, -1); - } - Adafruit_SSD1306(uint8_t slaveAddress, uint8_t OLED_TYPE = OLED_ADAFRUIT_I2C_128x64, int8_t rst_pin = -1) - : i2cDevice(slaveAddress) - { - fTitle = "SSD1306 OLED"; init(OLED_TYPE, rst_pin); - } - - ~Adafruit_SSD1306() { close(); } - - // I2C Init - bool init(uint8_t OLED_TYPE, int8_t RST); - - void select_oled(uint8_t OLED_TYPE); - - void begin(void); - void close(void); - - void ssd1306_command(uint8_t c); - void ssd1306_command(uint8_t c0, uint8_t c1); - void ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2); - void ssd1306_data(uint8_t c); - - void clearDisplay(void); - void invertDisplay(bool inv); - void display(); - - void startscrollright(uint8_t start, uint8_t stop); - void startscrollleft(uint8_t start, uint8_t stop); - - void startscrolldiagright(uint8_t start, uint8_t stop); - void startscrolldiagleft(uint8_t start, uint8_t stop); - void stopscroll(void); - - void drawPixel(int16_t x, int16_t y, uint16_t color); - -private: - uint8_t * poledbuff = nullptr; // Pointer to OLED data buffer in memory - int8_t rst; - int16_t ssd1306_lcdwidth, ssd1306_lcdheight; - uint8_t vcc_type; - - void fastI2Cwrite(uint8_t c); - void fastI2Cwrite(char* tbuf, uint32_t len); -}; -#endif // !_ADAFRUIT_SSD1306_H_ diff --git a/source/daemon/include/i2c/i2cdevices/ads1015/ads1015.h b/source/daemon/include/i2c/i2cdevices/ads1015/ads1015.h deleted file mode 100644 index a33cd8ef..00000000 --- a/source/daemon/include/i2c/i2cdevices/ads1015/ads1015.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef _ADS1015_H_ -#define _ADS1015_H_ -#include "i2c/i2cdevices/ads1115/ads1115.h" - -/* ADS1015: 4(2) ch, 12 bit ADC */ - -class ADS1015 : public ADS1115 { -public: - using ADS1115::ADS1115; - // enum CFG_RATE { RATE128 = 0, RATE250, RATE490, RATE920, RATE1600, RATE2400, RATE3300 }; - -protected: - inline void init() { - ADS1115::init(); - fTitle = "ADS1015"; - } -}; - -#endif // !_ADS1015_H_ diff --git a/source/daemon/include/i2c/i2cdevices/ads1115/ads1115.h b/source/daemon/include/i2c/i2cdevices/ads1115/ads1115.h deleted file mode 100644 index 5fb3d931..00000000 --- a/source/daemon/include/i2c/i2cdevices/ads1115/ads1115.h +++ /dev/null @@ -1,69 +0,0 @@ -#ifndef _ADS1115_H_ -#define _ADS1115_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -// ADC ADS1x13/4/5 sampling readout delay -#define READ_WAIT_DELAY_INIT 10 - - -/* ADS1115: 4(2) ch, 16 bit ADC */ - -class ADS1115 : public i2cDevice { -public: - enum CFG_CHANNEL { CH0 = 0, CH1, CH2, CH3 }; - enum CFG_DIFF_CHANNEL { CH0_1 = 0, CH0_3, CH1_3, CH2_3 }; - // enum CFG_RATE { RATE8 = 0, RATE16, RATE32, RATE64, RATE128, RATE250, RATE475, RATE860 }; - enum CFG_PGA { PGA6V = 0, PGA4V = 1, PGA2V = 2, PGA1V = 3, PGA512MV = 4, PGA256MV = 5 }; - static const double PGAGAINS[6]; - - ADS1115() : i2cDevice("/dev/i2c-1", 0x48) { init(); } - ADS1115(uint8_t slaveAddress) : i2cDevice(slaveAddress) { init(); } - ADS1115(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { init(); } - ADS1115(const char* busAddress, uint8_t slaveAddress, CFG_PGA pga) : i2cDevice(busAddress, slaveAddress) - { - init(); - setPga(pga); - } - - void setPga(CFG_PGA pga) { fPga[0] = fPga[1] = fPga[2] = fPga[3] = pga; } - void setPga(unsigned int pga) { setPga((CFG_PGA)pga); } - void setPga(uint8_t channel, CFG_PGA pga) { if (channel>3) return; fPga[channel] = pga; } - void setPga(uint8_t channel, uint8_t pga) { setPga(channel, (CFG_PGA)pga); } - CFG_PGA getPga(int ch) const { return fPga[ch]; } - void setAGC(bool state) { fAGC = state; } - bool getAGC() const { return fAGC; } - void setRate(unsigned int rate) { fRate = rate & 0x07; } - unsigned int getRate() const { return fRate; } - bool setLowThreshold(int16_t thr); - bool setHighThreshold(int16_t thr); - int16_t readADC(unsigned int channel); - double readVoltage(unsigned int channel); - void readVoltage(unsigned int channel, double& voltage); - void readVoltage(unsigned int channel, int16_t& adc, double& voltage); - bool devicePresent(); - void setDiffMode(bool mode) { fDiffMode = mode; } - bool setDataReadyPinMode(); - unsigned int getReadWaitDelay() const { return fReadWaitDelay; } - double getLastConvTime() const { return fLastConvTime; } - -protected: - CFG_PGA fPga[4]; - unsigned int fRate; - double fLastConvTime; - unsigned int fLastADCValue; - double fLastVoltage; - unsigned int fReadWaitDelay; // conversion wait time in us - bool fAGC; // software agc which switches over to a better pga setting if voltage too low/high - bool fDiffMode = false; // measure differential input signals (true) or single ended (false=default) - - inline virtual void init() { - fPga[0] = fPga[1] = fPga[2] = fPga[3] = PGA4V; - fReadWaitDelay = READ_WAIT_DELAY_INIT; - fRate = 0x00; // RATE8 - fAGC = false; - fTitle = "ADS1115"; - } -}; - -#endif // !_ADS1115_H_ diff --git a/source/daemon/include/i2c/i2cdevices/bme280/bme280.h b/source/daemon/include/i2c/i2cdevices/bme280/bme280.h deleted file mode 100644 index 8692e13c..00000000 --- a/source/daemon/include/i2c/i2cdevices/bme280/bme280.h +++ /dev/null @@ -1,53 +0,0 @@ -#ifndef _BME280_H_ -#define _BME280_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* BME280 */ -// struct to store temperature, pressure and humidity data in different ways -struct TPH { - uint32_t adc_T; - uint32_t adc_P; - uint32_t adc_H; - double T, P, H; -}; -class BME280 : public i2cDevice { // t_max = 112.8 ms for all three measurements at max oversampling -public: - BME280() : i2cDevice(0x76) { init(); } - BME280(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { init(); } - BME280(uint8_t slaveAddress) : i2cDevice(slaveAddress) { init(); } - - bool init(); - bool status(); - bool measure(); - uint8_t readConfig(); - uint8_t read_CtrlMeasReg(); - bool writeConfig(uint8_t config); - bool write_CtrlMeasReg(uint8_t config); - bool setMode(uint8_t mode); // 3 bits: "1=sleep", "2=single shot", "3=interval" - bool setTSamplingMode(uint8_t mode); - bool setPSamplingMode(uint8_t mode); - bool setHSamplingMode(uint8_t mode); - bool setDefaultSettings(); - bool softReset(); - void readCalibParameters(); - inline bool isCalibValid() const { return fCalibrationValid; } - uint16_t getCalibParameter(unsigned int param) const; - int32_t readUT(); - int32_t readUP(); - int32_t readUH(); - TPH readTPCU(); - TPH getTPHValues(); - double getTemperature(int32_t adc_T); - double getPressure(signed int adc_P); - double getPressure(signed int adc_P, signed int t_fine); - double getHumidity(int32_t adc_H); - double getHumidity(int32_t adc_H, int32_t t_fine); -private: - int32_t fT_fine = 0; - unsigned int fLastConvTime; - bool fCalibrationValid; - uint16_t fCalibParameters[18]; // 18x 16-Bit words in 36 8-Bit registers -}; - -#endif // !_BME280_H_ diff --git a/source/daemon/include/i2c/i2cdevices/bmp180/bmp180.h b/source/daemon/include/i2c/i2cdevices/bmp180/bmp180.h deleted file mode 100644 index aeab93ef..00000000 --- a/source/daemon/include/i2c/i2cdevices/bmp180/bmp180.h +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef _BMP180_H_ -#define _BMP180_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* BMP180 */ - -class BMP180 : public i2cDevice { -public: - - BMP180() : i2cDevice(0x77) { fTitle = "BMP180"; } - BMP180(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "BMP180"; } - BMP180(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "BMP180"; } - - bool init(); - void readCalibParameters(); - inline bool isCalibValid() const { return fCalibrationValid; } - signed int getCalibParameter(unsigned int param) const; - unsigned int readUT(); - unsigned int readUP(uint8_t oss); - double getTemperature(); - double getPressure(uint8_t oss); - -private: - unsigned int fLastConvTime; - bool fCalibrationValid; - signed int fCalibParameters[11]; - -}; - -#endif // _I2CDEVICES_H_ \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h b/source/daemon/include/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h deleted file mode 100644 index ea207193..00000000 --- a/source/daemon/include/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef _EEPROM24AA02_H_ -#define _EEPROM24AA02_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* EEPROM24AA02 */ - -class EEPROM24AA02 : public i2cDevice { -public: - EEPROM24AA02() : i2cDevice(0x50) { fTitle = "24AA02"; } - EEPROM24AA02(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "24AA02"; } - EEPROM24AA02(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "24AA02"; } - - //bool devicePresent(); - uint8_t readByte(uint8_t addr); - bool readByte(uint8_t addr, uint8_t* value); - //the readBytes function is already defined in the base class - //int8_t readBytes(uint8_t regAddr, uint16_t length, uint8_t *data); - void writeByte(uint8_t addr, uint8_t data); - bool writeBytes(uint8_t addr, uint16_t length, uint8_t* data); -private: -}; -#endif //!_EEPROM24AA02_H \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/hmc5883/hmc5883.h b/source/daemon/include/i2c/i2cdevices/hmc5883/hmc5883.h deleted file mode 100644 index ff5ab648..00000000 --- a/source/daemon/include/i2c/i2cdevices/hmc5883/hmc5883.h +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef _HMC5883_H_ -#define _HMC5883_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* HMC5883 */ - -class HMC5883 : public i2cDevice { -public: - - // Resolution for the 8 gain settings in mG/LSB - static const double GAIN[8]; - HMC5883() : i2cDevice(0x1e) { fTitle = "HMC5883"; } - HMC5883(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "HMC5883"; } - HMC5883(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "HMC5883"; } - - bool init(); - // gain range 0..7 - void setGain(uint8_t gain); - uint8_t readGain(); - // uint8_t readGain2(); - bool getXYZRawValues(int &x, int &y, int &z); - bool getXYZMagneticFields(double &x, double &y, double &z); - bool readRDYBit(); - bool readLockBit(); - bool calibrate(int &x, int &y, int &z); - - -private: - unsigned int fLastConvTime; - bool fCalibrationValid; - unsigned int fGain; - signed int fCalibParameters[11]; -}; - -#endif // !_HMC5883_H_ \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/i2cdevice.h b/source/daemon/include/i2c/i2cdevices/i2cdevice.h deleted file mode 100644 index 01c800cc..00000000 --- a/source/daemon/include/i2c/i2cdevices/i2cdevice.h +++ /dev/null @@ -1,126 +0,0 @@ -#include -#include // open -#include -#include // ioctl -#include // uint8_t, etc -#include "i2c/linux/i2c-dev.h" // I2C bus definitions for linux like systems -#include // for gettimeofday() -#include -#include -#include - -#ifndef _I2CDEVICE_H_ -#define _I2CDEVICE_H_ - - -#define DEFAULT_DEBUG_LEVEL 0 - - -//We define a class named i2cDevices to outsource the hardware dependent program parts. We want to -//access components of integrated curcuits, like the ads1115 or other subdevices via i2c-bus. -//The main aim here is, that the user does not have to be concerned about the c like low level operations -//of I2C access -// First, we define an abstract base class with all low-level i2c acess functions implemented. -// For device specific implementations, classes can inherit this base class -// virtual methods should be reimplemented in the child classes to make sense there, e.g. devicePresent() -class i2cDevice { - -public: - - enum MODE { MODE_NONE=0, MODE_NORMAL=0x01, MODE_FORCE=0x02, MODE_UNREACHABLE=0x04, MODE_FAILED=0x08, MODE_LOCKED=0x10 }; - - //using I2C_DEVICE_MODE; - - i2cDevice(); - i2cDevice(const char* busAddress = "/dev/i2c-1"); - i2cDevice(uint8_t slaveAddress); - i2cDevice(const char* busAddress, uint8_t slaveAddress); - virtual ~i2cDevice(); - - void setAddress(uint8_t address); - uint8_t getAddress() const { return fAddress; } - static unsigned int getNrDevices() { return fNrDevices; } - unsigned int getNrBytesRead() const { return fNrBytesRead; } - unsigned int getNrBytesWritten() const { return fNrBytesWritten; } - unsigned int getNrIOErrors() const { return fIOErrors; } - static unsigned int getGlobalNrBytesRead() { return fGlobalNrBytesRead; } - static unsigned int getGlobalNrBytesWritten() { return fGlobalNrBytesWritten; } - static std::vector& getGlobalDeviceList() { return fGlobalDeviceList; } - virtual bool devicePresent(); - uint8_t getStatus() const { return fMode; } - void lock(bool locked=true) { if (locked) fMode |= MODE_LOCKED; else fMode &= ~MODE_LOCKED; } - - double getLastTimeInterval() const { return fLastTimeInterval; } - - void setDebugLevel(int level) { fDebugLevel = level; } - int getDebugLevel() const { return fDebugLevel; } - - void setTitle(const std::string& a_title) { fTitle = a_title; } - const std::string& getTitle() const { return fTitle; } - - // read nBytes bytes into buffer buf - // return value: - // the number of bytes actually read if successful - // -1 on error - int read(uint8_t* buf, int nBytes); - - // write nBytes bytes from buffer buf - // return value: - // the number of bytes actually written if successful - // -1 on error - int write(uint8_t* buf, int nBytes); - - // write nBytes bytes from buffer buf in register reg - // return value: - // the number of bytes actually written if successful - // -1 on error - // note: first byte of the write sequence is the register address, - // the following bytes from buf are then written in a sequence - int writeReg(uint8_t reg, uint8_t* buf, int nBytes); - - // read nBytes bytes into buffer buf from register reg - // return value: - // the number of bytes actually read if successful - // -1 on error - // note: first writes reg address and after a repeated start - // reads in a sequence of bytes - // not all devices support this procedure - // refer to the device's datasheet - int readReg(uint8_t reg, uint8_t* buf, int nBytes); - - int8_t readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data); - int8_t readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data); - bool readByte(uint8_t regAddr, uint8_t *data); - int16_t readBytes(uint8_t regAddr, uint16_t length, uint8_t *data); - bool writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data); - bool writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); - bool writeByte(uint8_t regAddr, uint8_t data); - bool writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data); - bool writeWords(uint8_t regAddr, uint16_t length, uint16_t* data); - bool writeWord(uint8_t regAddr, uint16_t data); - - void getCapabilities(); - - -protected: - int fHandle; - uint8_t fAddress; - static unsigned int fNrDevices; - unsigned long int fNrBytesWritten; - unsigned long int fNrBytesRead; - static unsigned long int fGlobalNrBytesRead; - static unsigned long int fGlobalNrBytesWritten; - double fLastTimeInterval; // the last time measurement's result is stored here - struct timeval fT1, fT2; - int fDebugLevel; - static std::vector fGlobalDeviceList; - std::string fTitle="I2C device"; - uint8_t fMode = MODE_NONE; - unsigned int fIOErrors=0; - - // fuctions for measuring time intervals - void startTimer(); - void stopTimer(); -}; - -#endif // _I2CDEVICE_H_ diff --git a/source/daemon/include/i2c/i2cdevices/lm75/lm75.h b/source/daemon/include/i2c/i2cdevices/lm75/lm75.h deleted file mode 100644 index 5d33c3d8..00000000 --- a/source/daemon/include/i2c/i2cdevices/lm75/lm75.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef _LM75_H_ -#define _LM75_H_ -#include "i2c/i2cdevices/i2cdevice.h" -class LM75 : public i2cDevice { -public: - LM75() : i2cDevice(0x4f) { fTitle = "LM75A"; } - LM75(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "LM75A"; } - LM75(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "LM75A"; } - bool devicePresent(); - int16_t readRaw(); - double getTemperature(); - double lastTemperatureValue() const { return fLastTemp; } - -private: - unsigned int fLastConvTime; - signed int fLastRawValue; - double fLastTemp; -}; -#endif // !_LM75_H_ diff --git a/source/daemon/include/i2c/i2cdevices/mcp4728/mcp4728.h b/source/daemon/include/i2c/i2cdevices/mcp4728/mcp4728.h deleted file mode 100644 index 53638bbc..00000000 --- a/source/daemon/include/i2c/i2cdevices/mcp4728/mcp4728.h +++ /dev/null @@ -1,46 +0,0 @@ -#ifndef _MCP4728_H_ -#define _MCP4728_H_ -#include "i2c/i2cdevices/i2cdevice.h" - -/* MCP4728 */ - -class MCP4728 : public i2cDevice { - // the DAC supports writing to input register but not sending latch bit to update the output register - // here we will always send the "UDAC" (latch) bit because we don't need this functionality - // MCP4728 listens to I2C Generall Call Commands - // reset, wake-up, software update, read address bits - // reset is "0x00 0x06" - // wake-up is "0x00 0x09" -public: - //enum CFG_CHANNEL {CH_A=0, CH_B, CH_C, CH_D}; - //enum POWER_DOWN {NORM=0, LOAD1, LOAD2, LOAD3}; // at Power Down mode the output is loaded with 1k, 100k, 500k - // to ground to power down the circuit - const static float VDD; // change, if device powered with different voltage - enum CFG_GAIN { GAIN1 = 0, GAIN2 = 1 }; - enum CFG_VREF { VREF_VDD = 0, VREF_2V = 1 }; - - // struct that characterizes one dac output channel - // setting the eeprom flag enables access to the eeprom registers instead of the dac output registers - struct DacChannel { - uint8_t pd = 0x00; - CFG_GAIN gain = GAIN1; - CFG_VREF vref = VREF_VDD; - bool eeprom = false; - uint16_t value = 0; - }; - - MCP4728() : i2cDevice(0x60) { fTitle = "MCP4728"; } - MCP4728(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "MCP4728"; } - MCP4728(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "MCP4728"; } - bool devicePresent(); - bool setVoltage(uint8_t channel, float voltage, bool toEEPROM = false); - bool setValue(uint8_t channel, uint16_t value, uint8_t gain = GAIN1, bool toEEPROM = false); - bool writeChannel(uint8_t channel, const DacChannel& channelData); - bool readChannel(uint8_t channel, DacChannel& channelData); - - static float code2voltage(const DacChannel& channelData); -private: - unsigned int fLastConvTime; -}; - -#endif //!_MCP4728_H_ diff --git a/source/daemon/include/i2c/i2cdevices/pca9536/pca9536.h b/source/daemon/include/i2c/i2cdevices/pca9536/pca9536.h deleted file mode 100644 index 5ab6624e..00000000 --- a/source/daemon/include/i2c/i2cdevices/pca9536/pca9536.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef _PCA9536_H_ -#define _PCA9536_H_ -#include "i2c/i2cdevices/i2cdevice.h" - -/* PCA9536 */ - -class PCA9536 : public i2cDevice { - // the device supports reading the incoming logic levels of the pins if set to input in the configuration register (will probably not use this feature) - // the device supports polarity inversion (by configuring the polarity inversino register) (will probably not use this feature) -public: - enum CFG_REG { INPUT_REG = 0x00, OUTPUT_REG = 0x01, POLARITY_INVERSION = 0x02, CONFIG_REG = 0x03 }; - enum CFG_PORT { C0 = 0, C1 = 2, C3 = 4, C4 = 8 }; - PCA9536() : i2cDevice(0x41) { fTitle = "PCA9536"; } - PCA9536(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "PCA9536"; } - PCA9536(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "PCA9536"; } - bool setOutputPorts(uint8_t portMask); - bool setOutputState(uint8_t portMask); - uint8_t getInputState(); - bool devicePresent(); -}; - -#endif // !_PCA9536_H_ diff --git a/source/daemon/include/i2c/i2cdevices/sht21/sht21.h b/source/daemon/include/i2c/i2cdevices/sht21/sht21.h deleted file mode 100644 index 19118594..00000000 --- a/source/daemon/include/i2c/i2cdevices/sht21/sht21.h +++ /dev/null @@ -1,27 +0,0 @@ -#ifndef _SHT21_H_ -#define _SHT21_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* SHT21 */ - -class SHT21 : public i2cDevice { -public: - SHT21() : i2cDevice(0x40) { fTitle = "SHT21"; } - SHT21(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "SHT21"; } - SHT21(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "SHT21"; } - - uint16_t readUT(); //read temperature; nothing gets passed - uint16_t readUH(); //read humidity; nothing gets passed - - bool softReset(); //reset, datasheet, page 9, Rückgabetyp in void geändert - uint8_t readResolutionSettings(); - void setResolutionSettings(uint8_t settingsByte); //Sets the resolution Bits for humidity and temperature - float getTemperature(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_temp() - float getHumidity(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_hum(); - -private: - bool checksumCorrect(uint8_t data[]); // expects 3 byte long data array; Source: https://www2.htw-dresden.de/~wiki_sn/index.php/SHT21 -}; - -#endif //!_SHT21_H_ \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/sht31/Makefile b/source/daemon/include/i2c/i2cdevices/sht31/Makefile deleted file mode 100644 index 599bcbb4..00000000 --- a/source/daemon/include/i2c/i2cdevices/sht31/Makefile +++ /dev/null @@ -1,19 +0,0 @@ -LFLAGS = -O -CPP = g++ -std=c++11 -CFLAGS = -c -O -OBJS = sht31.o i2cdevice.o sht31_test.o - -sht31_test : $(OBJS) - $(CPP) $(OBJS) $(LFLAGS) -o sht31_test - -sht31_test.o : sht31_test.cpp sht31.h ../i2cdevice.h - $(CPP) $(CFLAGS) sht31_test.cpp - -sht31.o : sht31.cpp sht31.h ../i2cdevice.h - $(CPP) $(CFLAGS) sht31.cpp - -i2cdevice.o : ../i2cdevice.cpp ../i2cdevice.h - $(CPP) $(CFLAGS) ../i2cdevice.cpp - -clean : - \rm -f *.o *~ $(OBJS) \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/ubloxi2c/ubloxi2c.h b/source/daemon/include/i2c/i2cdevices/ubloxi2c/ubloxi2c.h deleted file mode 100644 index e609d2b6..00000000 --- a/source/daemon/include/i2c/i2cdevices/ubloxi2c/ubloxi2c.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef _UBLOXI2C_H_ -#define _UBLOXI2C_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* Ublox GPS receiver, I2C interface */ - -class UbloxI2c : public i2cDevice { -public: - UbloxI2c() : i2cDevice(0x42) { fTitle = "UBLOX I2C"; } - UbloxI2c(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "UBLOX I2C"; } - UbloxI2c(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "UBLOX I2C"; } - bool devicePresent(); - std::string getData(); - bool getTxBufCount(uint16_t& nrBytes); - -private: -}; - -#endif // !_UBLOXI2C_H_ \ No newline at end of file diff --git a/source/daemon/include/i2c/i2cdevices/x9119/x9119.h b/source/daemon/include/i2c/i2cdevices/x9119/x9119.h deleted file mode 100644 index 841a14fa..00000000 --- a/source/daemon/include/i2c/i2cdevices/x9119/x9119.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef _X9119_H_ -#define _X9119_H_ - -#include "i2c/i2cdevices/i2cdevice.h" - -/* X9119 */ - -class X9119 : public i2cDevice { -public: - - X9119() : i2cDevice(0x28) { fTitle = "X9119"; } - X9119(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "X9119"; } - X9119(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "X9119"; } - - unsigned int readWiperReg(); - unsigned int readWiperReg2(); - unsigned int readWiperReg3(); - void writeWiperReg(unsigned int value); - unsigned int readDataReg(uint8_t reg); - void writeDataReg(uint8_t reg, unsigned int value); -private: - unsigned int fWiperReg; -}; - -#endif // !_X9119_H_ diff --git a/source/daemon/include/i2c/i2cdevices_old/i2cdevices.h b/source/daemon/include/i2c/i2cdevices_old/i2cdevices.h deleted file mode 100644 index 5749e4a7..00000000 --- a/source/daemon/include/i2c/i2cdevices_old/i2cdevices.h +++ /dev/null @@ -1,526 +0,0 @@ -#include -#include // open -#include -#include // ioctl -#include // uint8_t, etc -#include // I2C bus definitions for linux like systems -#include // for gettimeofday() -#include -#include - -#ifndef _I2CDEVICES_H_ -#define _I2CDEVICES_H_ - -// ADC ADS1x13/4/5 sampling readout delay -#define READ_WAIT_DELAY_INIT 10 - -// OLED defines -#define OLED_I2C_RESET RPI_V2_GPIO_P1_22 /* GPIO 25 pin 12 */ -// Oled supported display -#define OLED_ADAFRUIT_SPI_128x32 0 -#define OLED_ADAFRUIT_SPI_128x64 1 -#define OLED_ADAFRUIT_I2C_128x32 2 -#define OLED_ADAFRUIT_I2C_128x64 3 -#define OLED_SEEED_I2C_128x64 4 -#define OLED_SEEED_I2C_96x96 5 -#define OLED_LAST_OLED 6 /* always last type, used in code to end array */ - - -// struct to store temperature, pressure and humidity data in different ways -struct TPH { - uint32_t adc_T; - uint32_t adc_P; - uint32_t adc_H; - double T, P, H; -}; - -//We define a class named i2cDevices to outsource the hardware dependant programm parts. We want to -//access components of integrated curcuits, like the ads1115 or other subdevices via i2c-bus. -//The main aim here was, that the user does not have to be concerned about the c like low level operations -//of the coding. -class i2cDevice { - -public: - - enum MODE { MODE_NONE=0, MODE_NORMAL=0x01, MODE_FORCE=0x02, - MODE_UNREACHABLE=0x04, MODE_FAILED=0x08 }; - - i2cDevice(); - i2cDevice(const char* busAddress); - i2cDevice(uint8_t slaveAddress); - i2cDevice(const char* busAddress, uint8_t slaveAddress); - virtual ~i2cDevice(); - - void setAddress(uint8_t address); - uint8_t getAddress() const { return fAddress; } - static unsigned int getNrDevices() { return fNrDevices; } - unsigned int getNrBytesRead() { return fNrBytesRead; } - unsigned int getNrBytesWritten() { return fNrBytesWritten; } - static unsigned int getGlobalNrBytesRead() { return fGlobalNrBytesRead; } - static unsigned int getGlobalNrBytesWritten() { return fGlobalNrBytesWritten; } - static std::vector& getGlobalDeviceList() { return fGlobalDeviceList; } - virtual bool devicePresent(); - uint8_t getStatus() const { return fMode; } - - double getLastTimeInterval() { return fLastTimeInterval; } - - void setDebugLevel(int level) { fDebugLevel = level; } - int getDebugLevel() { return fDebugLevel; } - - void setTitle(const std::string& a_title) { fTitle = a_title; } - const std::string& getTitle() const { return fTitle; } - - // read nBytes bytes into buffer buf - // return value: - // the number of bytes actually read if successful - // -1 on error - int read(uint8_t* buf, int nBytes); - - // write nBytes bytes from buffer buf - // return value: - // the number of bytes actually written if successful - // -1 on error - int write(uint8_t* buf, int nBytes); - - // write nBytes bytes from buffer buf in register reg - // return value: - // the number of bytes actually written if successful - // -1 on error - // note: first byte of the write sequence is the register address, - // the following bytes from buf are then written in a sequence - int writeReg(uint8_t reg, uint8_t* buf, int nBytes); - - // read nBytes bytes into buffer buf from register reg - // return value: - // the number of bytes actually read if successful - // -1 on error - // note: first writes reg address and after a repeated start - // reads in a sequence of bytes - // not all devices support this procedure - // refer to the device's datasheet - int readReg(uint8_t reg, uint8_t* buf, int nBytes); - - int8_t readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data); - int8_t readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data); - bool readByte(uint8_t regAddr, uint8_t *data); - int16_t readBytes(uint8_t regAddr, uint16_t length, uint8_t *data); - bool writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data); - bool writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); - bool writeByte(uint8_t regAddr, uint8_t data); - bool writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data); - bool writeWords(uint8_t regAddr, uint16_t length, uint16_t* data); - bool writeWord(uint8_t regAddr, uint16_t data); - - void getCapabilities(); - - -protected: - int fHandle; - uint8_t fAddress; - static unsigned int fNrDevices; - unsigned long int fNrBytesWritten; - unsigned long int fNrBytesRead; - static unsigned long int fGlobalNrBytesRead; - static unsigned long int fGlobalNrBytesWritten; - double fLastTimeInterval; // the last time measurement's result is stored here - struct timeval fT1, fT2; - int fDebugLevel; - static std::vector fGlobalDeviceList; - std::string fTitle="I2C device"; - uint8_t fMode = MODE_NONE; - - // fuctions for measuring time intervals - void startTimer(); - void stopTimer(); -}; - - -/* ADS1115: 4(2) ch, 16 bit ADC */ -class ADS1115 : public i2cDevice { -public: - enum CFG_CHANNEL { CH0 = 0, CH1, CH2, CH3 }; - enum CFG_DIFF_CHANNEL { CH0_1 = 0, CH0_3, CH1_3, CH2_3 }; -// enum CFG_RATE { RATE8 = 0, RATE16, RATE32, RATE64, RATE128, RATE250, RATE475, RATE860 }; - enum CFG_PGA { PGA6V = 0, PGA4V = 1, PGA2V = 2, PGA1V = 3, PGA512MV = 4, PGA256MV = 5 }; - static const double PGAGAINS[6]; - - ADS1115() : i2cDevice("/dev/i2c-1", 0x48) { init(); } - ADS1115(uint8_t slaveAddress) : i2cDevice(slaveAddress) { init(); } - ADS1115(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { init(); } - ADS1115(const char* busAddress, uint8_t slaveAddress, CFG_PGA pga) : i2cDevice(busAddress, slaveAddress) - { - init(); - setPga(pga); - } - - void setPga(CFG_PGA pga) { fPga[0] = fPga[1] = fPga[2] = fPga[3] = pga; } - void setPga(unsigned int pga) { setPga((CFG_PGA)pga); } - void setPga(uint8_t channel, CFG_PGA pga) { if (channel>3) return; fPga[channel] = pga; } - void setPga(uint8_t channel, uint8_t pga) { setPga(channel, (CFG_PGA)pga); } - CFG_PGA getPga(int ch) const { return fPga[ch]; } - void setAGC(bool state) { fAGC = state; } - bool getAGC() const { return fAGC; } - void setRate(unsigned int rate) { fRate = rate & 0x07; } - unsigned int getRate() const { return fRate; } - bool setLowThreshold(int16_t thr); - bool setHighThreshold(int16_t thr); - int16_t readADC(unsigned int channel); - double readVoltage(unsigned int channel); - void readVoltage(unsigned int channel, double& voltage); - void readVoltage(unsigned int channel, int16_t& adc, double& voltage); - bool devicePresent(); - void setDiffMode(bool mode) { fDiffMode=mode; } - bool setDataReadyPinMode(); - unsigned int getReadWaitDelay() const { return fReadWaitDelay; } - double getLastConvTime() const { return fLastConvTime; } - -protected: - CFG_PGA fPga[4]; - unsigned int fRate; - double fLastConvTime; - unsigned int fLastADCValue; - double fLastVoltage; - unsigned int fReadWaitDelay; // conversion wait time in us - bool fAGC; // software agc which switches over to a better pga setting if voltage too low/high - bool fDiffMode=false; // measure differential input signals (true) or single ended (false=default) - - inline virtual void init() { - fPga[0] = fPga[1] = fPga[2] = fPga[3] = PGA4V; - fReadWaitDelay = READ_WAIT_DELAY_INIT; - fRate = 0x00; // RATE8 - fAGC = false; - fTitle = "ADS1115"; - } -}; - -/* ADS1015: 4(2) ch, 12 bit ADC */ -class ADS1015 : public ADS1115 { -public: - using ADS1115::ADS1115; -// enum CFG_RATE { RATE128 = 0, RATE250, RATE490, RATE920, RATE1600, RATE2400, RATE3300 }; - -protected: - inline void init() { - ADS1115::init(); - fTitle = "ADS1015"; - } -}; - - -class MCP4728 : public i2cDevice { - // the DAC supports writing to input register but not sending latch bit to update the output register - // here we will always send the "UDAC" (latch) bit because we don't need this functionality - // MCP4728 listens to I2C Generall Call Commands - // reset, wake-up, software update, read address bits - // reset is "0x00 0x06" - // wake-up is "0x00 0x09" -public: - //enum CFG_CHANNEL {CH_A=0, CH_B, CH_C, CH_D}; - //enum POWER_DOWN {NORM=0, LOAD1, LOAD2, LOAD3}; // at Power Down mode the output is loaded with 1k, 100k, 500k - // to ground to power down the circuit - const static float VDD; // change, if device powered with different voltage - enum CFG_GAIN { GAIN1 = 0, GAIN2 = 1 }; - enum CFG_VREF { VREF_VDD = 0, VREF_2V = 1 }; - - // struct that characterizes one dac output channel - // setting the eeprom flag enables access to the eeprom registers instead of the dac output registers - struct DacChannel { - uint8_t pd=0x00; - CFG_GAIN gain=GAIN1; - CFG_VREF vref=VREF_VDD; - bool eeprom = false; - uint16_t value = 0; - }; - - MCP4728() : i2cDevice(0x60) { fTitle = "MCP4728"; } - MCP4728(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "MCP4728"; } - MCP4728(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "MCP4728"; } - bool devicePresent(); - bool setVoltage(uint8_t channel, float voltage, bool toEEPROM = false); - bool setValue(uint8_t channel, uint16_t value, uint8_t gain = GAIN1, bool toEEPROM = false); - bool setChannel(uint8_t channel, const DacChannel& channelData); - bool readChannel(uint8_t channel, DacChannel& channelData); - - static float code2voltage(const DacChannel& channelData); -private: - unsigned int fLastConvTime; -}; - - -class PCA9536 : public i2cDevice { - // the device supports reading the incoming logic levels of the pins if set to input in the configuration register (will probably not use this feature) - // the device supports polarity inversion (by configuring the polarity inversino register) (will probably not use this feature) -public: - enum CFG_REG { INPUT_REG = 0x00, OUTPUT_REG=0x01, POLARITY_INVERSION=0x02, CONFIG_REG=0x03 }; - enum CFG_PORT { C0 = 0, C1 = 2, C3 = 4, C4 = 8 }; - PCA9536() : i2cDevice(0x41) { fTitle = "PCA9536"; } - PCA9536(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "PCA9536"; } - PCA9536(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "PCA9536"; } - bool setOutputPorts(uint8_t portMask); - bool setOutputState(uint8_t portMask); - uint8_t getInputState(); - bool devicePresent(); -}; - - -class LM75 : public i2cDevice { -public: - LM75() : i2cDevice(0x4f) { fTitle = "LM75A"; } - LM75(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "LM75A"; } - LM75(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "LM75A"; } - bool devicePresent(); - int16_t readRaw(); - double getTemperature(); - -private: - unsigned int fLastConvTime; - signed int fLastRawValue; - double fLastTemp; -}; - - - -class X9119 : public i2cDevice { -public: - - X9119() : i2cDevice(0x28) { fTitle = "X9119"; } - X9119(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "X9119"; } - X9119(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "X9119"; } - - unsigned int readWiperReg(); - unsigned int readWiperReg2(); - unsigned int readWiperReg3(); - void writeWiperReg(unsigned int value); - unsigned int readDataReg(uint8_t reg); - void writeDataReg(uint8_t reg, unsigned int value); -private: - unsigned int fWiperReg; -}; - - - -class EEPROM24AA02 : public i2cDevice { -public: - EEPROM24AA02() : i2cDevice(0x50) { fTitle = "24AA02"; } - EEPROM24AA02(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "24AA02"; } - EEPROM24AA02(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "24AA02"; } - - //bool devicePresent(); - uint8_t readByte(uint8_t addr); - bool readByte(uint8_t addr, uint8_t* value); - //the readBytes function is already defined in the base class - //int8_t readBytes(uint8_t regAddr, uint16_t length, uint8_t *data); - void writeByte(uint8_t addr, uint8_t data); - bool writeBytes(uint8_t addr, uint16_t length, uint8_t* data); -private: -}; - - -class SHT21 : public i2cDevice { -public: - SHT21() : i2cDevice(0x40) { fTitle = "SHT21"; } - SHT21(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "SHT21"; } - SHT21(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "SHT21"; } - - uint16_t readUT(); //read temperature; nothing gets passed - uint16_t readUH(); //read humidity; nothing gets passed - - bool softReset(); //reset, datasheet, page 9, Rückgabetyp in void geändert - uint8_t readResolutionSettings(); - void setResolutionSettings(uint8_t settingsByte); //Sets the resolution Bits for humidity and temperature - float getTemperature(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_temp() - float getHumidity(); // calculates the temperature with the formula in the datasheet. Gets the solution of read_hum(); - -private: - bool checksumCorrect(uint8_t data[]); // expects 3 byte long data array; Source: https://www2.htw-dresden.de/~wiki_sn/index.php/SHT21 -}; - - -class BMP180 : public i2cDevice { -public: - - BMP180() : i2cDevice(0x77) { fTitle = "BMP180"; } - BMP180(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "BMP180"; } - BMP180(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "BMP180"; } - - bool init(); - void readCalibParameters(); - inline bool isCalibValid() const { return fCalibrationValid; } - signed int getCalibParameter(unsigned int param) const; - unsigned int readUT(); - unsigned int readUP(uint8_t oss); - double getTemperature(); - double getPressure(uint8_t oss); - -private: - unsigned int fLastConvTime; - bool fCalibrationValid; - signed int fCalibParameters[11]; - -}; - - -class BME280 : public i2cDevice { // t_max = 112.8 ms for all three measurements at max oversampling -public: - BME280() : i2cDevice(0x76) { init(); } - BME280(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { init(); } - BME280(uint8_t slaveAddress) : i2cDevice(slaveAddress) { init(); } - - bool init(); - unsigned int status(); - void measure(); - unsigned int readConfig(); - unsigned int read_CtrlMeasReg(); - bool writeConfig(uint8_t config); - bool write_CtrlMeasReg(uint8_t config); - bool setMode(uint8_t mode); // 3 bits: "1=sleep", "2=single shot", "3=interval" - bool setTSamplingMode(uint8_t mode); - bool setPSamplingMode(uint8_t mode); - bool setHSamplingMode(uint8_t mode); - bool softReset(); - void readCalibParameters(); - inline bool isCalibValid() const { return fCalibrationValid; } - signed int getCalibParameter(unsigned int param) const; - unsigned int readUT(); - unsigned int readUP(); - unsigned int readUH(); - TPH readTPCU(); - TPH getTPHValues(); - double getTemperature(signed int adc_T); - double getPressure(signed int adc_P); - double getPressure(signed int adc_P, signed int t_fine); - double getHumidity(signed int adc_H); - double getHumidity(signed int adc_H, signed int t_fine); -private: - int32_t fT_fine = 0; - unsigned int fLastConvTime; - bool fCalibrationValid; - uint16_t fCalibParameters[18]; // 18x 16-Bit words in 36 8-Bit registers -}; - - -class HMC5883 : public i2cDevice { -public: - - // Resolution for the 8 gain settings in mG/LSB - static const double GAIN[8]; - HMC5883() : i2cDevice(0x1e) { fTitle = "HMC5883"; } - HMC5883(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "HMC5883"; } - HMC5883(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "HMC5883"; } - - bool init(); - // gain range 0..7 - void setGain(uint8_t gain); - uint8_t readGain(); - // uint8_t readGain2(); - bool getXYZRawValues(int &x, int &y, int &z); - bool getXYZMagneticFields(double &x, double &y, double &z); - bool readRDYBit(); - bool readLockBit(); - bool calibrate(int &x, int &y, int &z); - - -private: - unsigned int fLastConvTime; - bool fCalibrationValid; - unsigned int fGain; - signed int fCalibParameters[11]; -}; - - -/* Ublox GPS receiver, I2C interface */ -class UbloxI2c : public i2cDevice { -public: - UbloxI2c() : i2cDevice(0x42) { fTitle = "UBLOX I2C"; } - UbloxI2c(const char* busAddress, uint8_t slaveAddress) : i2cDevice(busAddress, slaveAddress) { fTitle = "UBLOX I2C"; } - UbloxI2c(uint8_t slaveAddress) : i2cDevice(slaveAddress) { fTitle = "UBLOX I2C"; } - bool devicePresent(); - std::string getData(); - bool getTxBufCount(uint16_t& nrBytes); - -private: -}; - - -//class Adafruit_GFX; -#include "./Adafruit_GFX.h" - -/********************************************************************* -This is a library for our Monochrome OLEDs based on SSD1306 drivers - - Pick one up today in the adafruit shop! - ------> http://www.adafruit.com/category/63_98 - -These displays use SPI to communicate, 4 or 5 pins are required to -interface - -Adafruit invests time and resources providing this open source code, -please support Adafruit and open-source hardware by purchasing -products from Adafruit! - -Written by Limor Fried/Ladyada for Adafruit Industries. -BSD license, check license.txt for more information -All text above, and the splash screen must be included in any redistribution - -02/18/2013 Charles-Henri Hallard (http://hallard.me) - Modified for compiling and use on Raspberry ArduiPi Board - LCD size and connection are now passed as arguments on - the command line (no more #define on compilation needed) - ArduiPi project documentation http://hallard.me/arduipi - -*********************************************************************/ -class Adafruit_SSD1306 : public i2cDevice, public Adafruit_GFX -{ -public: - enum { BLACK=0, WHITE=1 }; - - Adafruit_SSD1306() - : i2cDevice(0x3c) - { fTitle="SSD1306 OLED"; init(OLED_ADAFRUIT_I2C_128x64, -1); } - Adafruit_SSD1306(const char* busAddress, uint8_t slaveAddress) - : i2cDevice(busAddress, slaveAddress) - { fTitle="SSD1306 OLED"; init(OLED_ADAFRUIT_I2C_128x64, -1); } - Adafruit_SSD1306(uint8_t slaveAddress, uint8_t OLED_TYPE=OLED_ADAFRUIT_I2C_128x64, int8_t rst_pin=-1) - : i2cDevice(slaveAddress) - { fTitle="SSD1306 OLED"; init(OLED_TYPE, rst_pin); } - - ~Adafruit_SSD1306() { close(); } - - // I2C Init - bool init(uint8_t OLED_TYPE, int8_t RST); - - void select_oled(uint8_t OLED_TYPE); - - void begin(void); - void close(void); - - void ssd1306_command(uint8_t c); - void ssd1306_command(uint8_t c0, uint8_t c1); - void ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2); - void ssd1306_data(uint8_t c); - - void clearDisplay(void); - void invertDisplay(bool inv); - void display(); - - void startscrollright(uint8_t start, uint8_t stop); - void startscrollleft(uint8_t start, uint8_t stop); - - void startscrolldiagright(uint8_t start, uint8_t stop); - void startscrolldiagleft(uint8_t start, uint8_t stop); - void stopscroll(void); - - void drawPixel(int16_t x, int16_t y, uint16_t color); - -private: - uint8_t *poledbuff=nullptr; // Pointer to OLED data buffer in memory - int8_t rst; - int16_t ssd1306_lcdwidth, ssd1306_lcdheight; - uint8_t vcc_type; - - void fastI2Cwrite(uint8_t c); - void fastI2Cwrite(char* tbuf, uint32_t len); -}; - - -#endif // _I2CDEVICES_H_ diff --git a/source/daemon/include/i2c/linux/i2c-dev.h b/source/daemon/include/i2c/linux/i2c-dev.h deleted file mode 100644 index 81ddcb2e..00000000 --- a/source/daemon/include/i2c/linux/i2c-dev.h +++ /dev/null @@ -1,330 +0,0 @@ -/* - i2c-dev.h - i2c-bus driver, char device interface - - Copyright (C) 1995-97 Simon G. Vogl - Copyright (C) 1998-99 Frodo Looijaard - - This program is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, - MA 02110-1301 USA. -*/ - -#ifndef _LINUX_I2C_DEV_H -#define _LINUX_I2C_DEV_H - -#include -#include -#include - - -/* -- i2c.h -- */ - - -/* - * I2C Message - used for pure i2c transaction, also from /dev interface - */ -struct i2c_msg { - __u16 addr; /* slave address */ - unsigned short flags; -#define I2C_M_TEN 0x10 /* we have a ten bit chip address */ -#define I2C_M_RD 0x01 -#define I2C_M_NOSTART 0x4000 -#define I2C_M_REV_DIR_ADDR 0x2000 -#define I2C_M_IGNORE_NAK 0x1000 -#define I2C_M_NO_RD_ACK 0x0800 - short len; /* msg length */ - char *buf; /* pointer to msg data */ -}; - -/* To determine what functionality is present */ - -#define I2C_FUNC_I2C 0x00000001 -#define I2C_FUNC_10BIT_ADDR 0x00000002 -#define I2C_FUNC_PROTOCOL_MANGLING 0x00000004 /* I2C_M_{REV_DIR_ADDR,NOSTART,..} */ -#define I2C_FUNC_SMBUS_PEC 0x00000008 -#define I2C_FUNC_SMBUS_BLOCK_PROC_CALL 0x00008000 /* SMBus 2.0 */ -#define I2C_FUNC_SMBUS_QUICK 0x00010000 -#define I2C_FUNC_SMBUS_READ_BYTE 0x00020000 -#define I2C_FUNC_SMBUS_WRITE_BYTE 0x00040000 -#define I2C_FUNC_SMBUS_READ_BYTE_DATA 0x00080000 -#define I2C_FUNC_SMBUS_WRITE_BYTE_DATA 0x00100000 -#define I2C_FUNC_SMBUS_READ_WORD_DATA 0x00200000 -#define I2C_FUNC_SMBUS_WRITE_WORD_DATA 0x00400000 -#define I2C_FUNC_SMBUS_PROC_CALL 0x00800000 -#define I2C_FUNC_SMBUS_READ_BLOCK_DATA 0x01000000 -#define I2C_FUNC_SMBUS_WRITE_BLOCK_DATA 0x02000000 -#define I2C_FUNC_SMBUS_READ_I2C_BLOCK 0x04000000 /* I2C-like block xfer */ -#define I2C_FUNC_SMBUS_WRITE_I2C_BLOCK 0x08000000 /* w/ 1-byte reg. addr. */ - -#define I2C_FUNC_SMBUS_BYTE (I2C_FUNC_SMBUS_READ_BYTE | \ - I2C_FUNC_SMBUS_WRITE_BYTE) -#define I2C_FUNC_SMBUS_BYTE_DATA (I2C_FUNC_SMBUS_READ_BYTE_DATA | \ - I2C_FUNC_SMBUS_WRITE_BYTE_DATA) -#define I2C_FUNC_SMBUS_WORD_DATA (I2C_FUNC_SMBUS_READ_WORD_DATA | \ - I2C_FUNC_SMBUS_WRITE_WORD_DATA) -#define I2C_FUNC_SMBUS_BLOCK_DATA (I2C_FUNC_SMBUS_READ_BLOCK_DATA | \ - I2C_FUNC_SMBUS_WRITE_BLOCK_DATA) -#define I2C_FUNC_SMBUS_I2C_BLOCK (I2C_FUNC_SMBUS_READ_I2C_BLOCK | \ - I2C_FUNC_SMBUS_WRITE_I2C_BLOCK) - -/* Old name, for compatibility */ -#define I2C_FUNC_SMBUS_HWPEC_CALC I2C_FUNC_SMBUS_PEC - -/* - * Data for SMBus Messages - */ -#define I2C_SMBUS_BLOCK_MAX 32 /* As specified in SMBus standard */ -#define I2C_SMBUS_I2C_BLOCK_MAX 32 /* Not specified but we use same structure */ -union i2c_smbus_data { - __u8 byte; - __u16 word; - __u8 block[I2C_SMBUS_BLOCK_MAX + 2]; /* block[0] is used for length */ - /* and one more for PEC */ -}; - -/* smbus_access read or write markers */ -#define I2C_SMBUS_READ 1 -#define I2C_SMBUS_WRITE 0 - -/* SMBus transaction types (size parameter in the above functions) - Note: these no longer correspond to the (arbitrary) PIIX4 internal codes! */ -#define I2C_SMBUS_QUICK 0 -#define I2C_SMBUS_BYTE 1 -#define I2C_SMBUS_BYTE_DATA 2 -#define I2C_SMBUS_WORD_DATA 3 -#define I2C_SMBUS_PROC_CALL 4 -#define I2C_SMBUS_BLOCK_DATA 5 -#define I2C_SMBUS_I2C_BLOCK_BROKEN 6 -#define I2C_SMBUS_BLOCK_PROC_CALL 7 /* SMBus 2.0 */ -#define I2C_SMBUS_I2C_BLOCK_DATA 8 - - - /* /dev/i2c-X ioctl commands. The ioctl's parameter is always an - * unsigned long, except for: - * - I2C_FUNCS, takes pointer to an unsigned long - * - I2C_RDWR, takes pointer to struct i2c_rdwr_ioctl_data - * - I2C_SMBUS, takes pointer to struct i2c_smbus_ioctl_data - */ -#define I2C_RETRIES 0x0701 /* number of times a device address should - be polled when not acknowledging */ -#define I2C_TIMEOUT 0x0702 /* set timeout in units of 10 ms */ - - /* NOTE: Slave address is 7 or 10 bits, but 10-bit addresses - * are NOT supported! (due to code brokenness) - */ -#define I2C_SLAVE 0x0703 /* Use this slave address */ -#define I2C_SLAVE_FORCE 0x0706 /* Use this slave address, even if it - is already in use by a driver! */ -#define I2C_TENBIT 0x0704 /* 0 for 7 bit addrs, != 0 for 10 bit */ - -#define I2C_FUNCS 0x0705 /* Get the adapter functionality mask */ - -#define I2C_RDWR 0x0707 /* Combined R/W transfer (one STOP only) */ - -#define I2C_PEC 0x0708 /* != 0 to use PEC with SMBus */ -#define I2C_SMBUS 0x0720 /* SMBus transfer */ - - - /* This is the structure as used in the I2C_SMBUS ioctl call */ -struct i2c_smbus_ioctl_data { - __u8 read_write; - __u8 command; - __u32 size; - union i2c_smbus_data *data; -}; - -/* This is the structure as used in the I2C_RDWR ioctl call */ -struct i2c_rdwr_ioctl_data { - struct i2c_msg *msgs; /* pointers to i2c_msgs */ - __u32 nmsgs; /* number of i2c_msgs */ -}; - -#define I2C_RDRW_IOCTL_MAX_MSGS 42 - - -static inline __s32 i2c_smbus_access(int file, char read_write, __u8 command, - int size, union i2c_smbus_data *data) -{ - struct i2c_smbus_ioctl_data args; - - args.read_write = read_write; - args.command = command; - args.size = size; - args.data = data; - return ioctl(file, I2C_SMBUS, &args); -} - - -static inline __s32 i2c_smbus_write_quick(int file, __u8 value) -{ - return i2c_smbus_access(file, value, 0, I2C_SMBUS_QUICK, NULL); -} - -static inline __s32 i2c_smbus_read_byte(int file) -{ - union i2c_smbus_data data; - if (i2c_smbus_access(file, I2C_SMBUS_READ, 0, I2C_SMBUS_BYTE, &data)) - return -1; - else - return 0x0FF & data.byte; -} - -static inline __s32 i2c_smbus_write_byte(int file, __u8 value) -{ - return i2c_smbus_access(file, I2C_SMBUS_WRITE, value, - I2C_SMBUS_BYTE, NULL); -} - -static inline __s32 i2c_smbus_read_byte_data(int file, __u8 command) -{ - union i2c_smbus_data data; - if (i2c_smbus_access(file, I2C_SMBUS_READ, command, - I2C_SMBUS_BYTE_DATA, &data)) - return -1; - else - return 0x0FF & data.byte; -} - -static inline __s32 i2c_smbus_write_byte_data(int file, __u8 command, - __u8 value) -{ - union i2c_smbus_data data; - data.byte = value; - return i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_BYTE_DATA, &data); -} - -static inline __s32 i2c_smbus_read_word_data(int file, __u8 command) -{ - union i2c_smbus_data data; - if (i2c_smbus_access(file, I2C_SMBUS_READ, command, - I2C_SMBUS_WORD_DATA, &data)) - return -1; - else - return 0x0FFFF & data.word; -} - -static inline __s32 i2c_smbus_write_word_data(int file, __u8 command, - __u16 value) -{ - union i2c_smbus_data data; - data.word = value; - return i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_WORD_DATA, &data); -} - -static inline __s32 i2c_smbus_process_call(int file, __u8 command, __u16 value) -{ - union i2c_smbus_data data; - data.word = value; - if (i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_PROC_CALL, &data)) - return -1; - else - return 0x0FFFF & data.word; -} - - -/* Returns the number of read bytes */ -static inline __s32 i2c_smbus_read_block_data(int file, __u8 command, - __u8 *values) -{ - union i2c_smbus_data data; - int i; - if (i2c_smbus_access(file, I2C_SMBUS_READ, command, - I2C_SMBUS_BLOCK_DATA, &data)) - return -1; - else { - for (i = 1; i <= data.block[0]; i++) - values[i - 1] = data.block[i]; - return data.block[0]; - } -} - -static inline __s32 i2c_smbus_write_block_data(int file, __u8 command, - __u8 length, const __u8 *values) -{ - union i2c_smbus_data data; - int i; - if (length > 32) - length = 32; - for (i = 1; i <= length; i++) - data.block[i] = values[i - 1]; - data.block[0] = length; - return i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_BLOCK_DATA, &data); -} - -/* Returns the number of read bytes */ -/* Until kernel 2.6.22, the length is hardcoded to 32 bytes. If you - ask for less than 32 bytes, your code will only work with kernels - 2.6.23 and later. */ -static inline __s32 i2c_smbus_read_i2c_block_data(int file, __u8 command, - __u8 length, __u8 *values) -{ - union i2c_smbus_data data; - int i; - - if (length > 32) - length = 32; - data.block[0] = length; - if (i2c_smbus_access(file, I2C_SMBUS_READ, command, - length == 32 ? I2C_SMBUS_I2C_BLOCK_BROKEN : - I2C_SMBUS_I2C_BLOCK_DATA, &data)) - return -1; - else { - for (i = 1; i <= data.block[0]; i++) - values[i - 1] = data.block[i]; - return data.block[0]; - } -} - -static inline __s32 i2c_smbus_write_i2c_block_data(int file, __u8 command, - __u8 length, - const __u8 *values) -{ - union i2c_smbus_data data; - int i; - if (length > 32) - length = 32; - for (i = 1; i <= length; i++) - data.block[i] = values[i - 1]; - data.block[0] = length; - return i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_I2C_BLOCK_BROKEN, &data); -} - -/* Returns the number of read bytes */ -static inline __s32 i2c_smbus_block_process_call(int file, __u8 command, - __u8 length, __u8 *values) -{ - union i2c_smbus_data data; - int i; - if (length > 32) - length = 32; - for (i = 1; i <= length; i++) - data.block[i] = values[i - 1]; - data.block[0] = length; - if (i2c_smbus_access(file, I2C_SMBUS_WRITE, command, - I2C_SMBUS_BLOCK_PROC_CALL, &data)) - return -1; - else { - for (i = 1; i <= data.block[0]; i++) - values[i - 1] = data.block[i]; - return data.block[0]; - } -} - - -#endif /* _LINUX_I2C_DEV_H */ diff --git a/source/daemon/include/logengine.h b/source/daemon/include/logengine.h deleted file mode 100644 index 7e4a41d7..00000000 --- a/source/daemon/include/logengine.h +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef LOGENGINE_H -#define LOGENGINE_H -#include -#include -#include -#include -#include - -class LogEngine : public QObject -{ - Q_OBJECT - -public: - LogEngine(QObject *parent = nullptr); - ~LogEngine(); - -signals: - void sendLogString(const QString& str); - void logIntervalSignal(); - -public slots: - void onLogParameterReceived(const LogParameter& logpar); - void onLogInterval(); - void onOnceLogTrigger() { onceLogFlag=true; } - -private: - QMap > logData; - bool onceLogFlag=true; -}; - -#endif // LOGENGINE_H diff --git a/source/daemon/include/logparameter.h b/source/daemon/include/logparameter.h deleted file mode 100644 index 5282a1aa..00000000 --- a/source/daemon/include/logparameter.h +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef LOGPARAMETER_H -#define LOGPARAMETER_H -#include - -struct LogParameter{ -public: - - enum { LOG_NEVER=0, LOG_ONCE, LOG_EVERY, LOG_LATEST, LOG_AVERAGE, LOG_ON_CHANGE }; - - LogParameter()=default; - LogParameter(const QString& a_name, const QString& a_value, int a_logType = LOG_EVERY, bool updatedRecently=false) - : fName(a_name), fValue(a_value), updated(updatedRecently), fLogType(a_logType) - { } - - void setUpdatedRecently(bool updatedRecently) {updated = updatedRecently;} - void setName(const QString& a_name) {fName = a_name;} - void setValue(const QString& a_value) {fValue = a_value;} - - const QString& value() const {return fValue;} - const QString& name() const {return fName;} - bool updatedRecently() const {return updated;} - int logType() const { return fLogType; } - -private: - QString fName, fValue; - bool updated; - int fLogType = LOG_NEVER; -}; - -#endif // LOGPARAMETER_H diff --git a/source/daemon/include/time_from_rtc.h b/source/daemon/include/time_from_rtc.h deleted file mode 100644 index 82891939..00000000 --- a/source/daemon/include/time_from_rtc.h +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef TIME_FROM_RTC_H -#define TIME_FROM_RTC_H - -#include - -/* -static time_t t_from_rtc(struct tm *stm) { - bool rtc_on_utc = true; - - struct tm temp1, temp2; - long diff; - time_t t1, t2; - - temp1 = *stm; - temp1.tm_isdst = 0; - - t1 = mktime(&temp1); - if (rtc_on_utc) { - temp2 = *gmtime(&t1); - } - else { - temp2 = *localtime(&t1); - } - - temp2.tm_isdst = 0; - t2 = mktime(&temp2); - diff = t2 - t1; - - if (t1 - diff == -1) - //DEBUG_LOG(LOGF_RtcLinux, "Could not convert RTC time"); - printf("Could not convert RTC time"); - return t1 - diff; -} -*/ -#endif // TIME_FROM_RTC_H diff --git a/source/daemon/include/unixtime_from_gps.h b/source/daemon/include/unixtime_from_gps.h deleted file mode 100644 index c92a1784..00000000 --- a/source/daemon/include/unixtime_from_gps.h +++ /dev/null @@ -1,60 +0,0 @@ -#ifndef UNIXTIME_FROM_GPS_H -#define UNIXTIME_FROM_GPS_H - -#include -#include -#include - -static timespec unixtime_from_gps(int week_nr, long int s_of_week, long int ns /*,int leap_seconds*/) { - QDateTime gpsTimeStart(QDate(1980,1,6),QTime(0,0,0,0),Qt::UTC); - quint64 gpsOffsetToEpoch = gpsTimeStart.toMSecsSinceEpoch()/1000; - //qDebug() << "week: " << week_nr << " second: " << s_of_week << " ns: " << ns; - //qDebug() << "gpsOffsetToEpoch: "< -#include -#include -#include -//#include -#include "calibration.h" - -#define AS_U32(f) (*(uint32_t*)&(f)) -#define AS_U16(f) (*(uint16_t*)&(f)) -#define AS_TIME(u) (*(time_t*)&(u)) -#define AS_I8(f) (*(int8_t*)&(f)) -#define AS_I32(f) (*(int32_t*)&(f)) -#define AS_I16(f) (*(int16_t*)&(f)) -#define AS_FLOAT(u) (*(float*)&(u)) -#define AS_FLOAT_C(u) (*(const float*)&(u)) - -using namespace std; - -const CalibStruct ShowerDetectorCalib::InvalidCalibStruct = CalibStruct( "", "", 0, "" ); - - -void ShowerDetectorCalib::init() { - const uint16_t n=256; - for (int i=0; idevicePresent() && readFromEeprom(); - } -} - -void ShowerDetectorCalib::buildCalibList() { - fCalibList.clear(); - std::vector>::const_iterator it; - uint8_t addr=0x02; // calib range starts at 0x02 behind header - for (it=CALIBITEMS.begin(); it != CALIBITEMS.end(); it++) { - CalibStruct calibItem; - calibItem.name=std::get<0>(*it); - calibItem.type=std::get<1>(*it); - calibItem.address=addr; - addr+=getTypeSize(std::get<1>(*it)); - calibItem.value=std::get<2>(*it); - fCalibList.push_back(calibItem); - } -} - - - -uint8_t ShowerDetectorCalib::getTypeSize(const std::string& a_type) -{ - string str=a_type; - std::transform(a_type.begin(), a_type.end(), str.begin(), - [](unsigned char c){ return std::toupper(c); } - ); - //cout<<"type str = "<name<<", "<type<<", "<<(int)result->address<<", "<value<<")"<name<<", "<type<<", "<<(int)result->address<<", "<value<<")"<devicePresent()) return false; - const uint16_t n=256; - for (int i=0; ireadBytes(0,n,fEepBuffer)==n); - if (!success) { fEepromValid = false; return false; } - uint16_t eepheader = AS_U16(fEepBuffer[0]); - if (eepheader==CALIB_HEADER) fValid=true; - else { fValid=false; return true; } - - for (auto it=fCalibList.begin(); it!=fCalibList.end(); it++) { - uint8_t addr = it->address; - string str = it->type; - std::ostringstream ostr; - //cout<<"calibList entry: "<name<<" = "; - if (str=="UINT8") { - uint8_t val = fEepBuffer[it->address]; - it->value = std::to_string(val); - } else if (str=="UINT16") { - uint16_t val = AS_U16(fEepBuffer[it->address]); - it->value = std::to_string(val); - } else if (str=="UINT32") { - uint32_t val = AS_U32(fEepBuffer[it->address]); - it->value = std::to_string(val); - } else if (str=="FLOAT") { - uint32_t _x = AS_U32(fEepBuffer[it->address]); - if (fVerbose>5) cout<<"as U32="<<_x<<" "; - float val = AS_FLOAT_C(_x); - if (fVerbose>5) cout<<"as FLOAT="<name, AS_FLOAT((fEepBuffer[addr]))); - //float* val = reinterpret_cast(&fEepBuffer[it->address]); - //float val = 0.; - // use of std::to_string() is not recommended, since it messes with the locale's setting, e.g. the decimal separator - //it->value = std::to_string(val); - ostr << std::setprecision(7) << std::scientific << val; - it->value = ostr.str(); - } else if (str=="INT8") { - int8_t val = AS_I8(fEepBuffer[it->address]); - it->value = std::to_string(val); - } else if (str=="INT16") { - int16_t val = AS_I16(fEepBuffer[it->address]); - it->value = std::to_string(val); - } else if (str=="INT32") { - int32_t val = AS_I32(fEepBuffer[it->address]); - it->value = std::to_string(val); - } - else { - } - //cout<value<writeBytes(0, 256, fEepBuffer); - if (!success) { cerr<<"error: write to eeprom failed!"<1) cout<<"eep write took "<getLastTimeInterval()<<" ms"<address; - string str = it->type; - if (str=="UINT8") { - unsigned int val; - getValueFromString(it->value, val); - fEepBuffer[it->address]=(uint8_t)val; - } else if (str=="UINT16") { - unsigned int val; - getValueFromString(it->value, val); - AS_U16(fEepBuffer[it->address])=(uint16_t)val; - } else if (str=="UINT32") { - unsigned int val; - getValueFromString(it->value, val); - AS_U32(fEepBuffer[it->address])=(uint32_t)val; - } else if (str=="FLOAT") { - float val; - getValueFromString(it->value, val); - AS_FLOAT(fEepBuffer[it->address])=val; - } else if (str=="INT8") { - int val; - getValueFromString(it->value, val); - AS_I8(fEepBuffer[it->address])=(int8_t)val; - } else if (str=="INT16") { - int val; - getValueFromString(it->value, val); - AS_I16(fEepBuffer[it->address])=(int16_t)val; - } else if (str=="INT32") { - int val; - getValueFromString(it->value, val); - AS_I32(fEepBuffer[it->address])=(int32_t)val; - } - else { - } - } - -} - -void ShowerDetectorCalib::printBuffer() -{ -// bool retval=(eep->readBytes(0,n,buf)==n); - cout<<"*** Calibration buffer content ***"<name; - if (it->type=="FLOAT") { - float val; - getValueFromString(it->value,val); - cout<<" \t= "<value<<"'"<<" ("<type<<") @"<<(int)it->address<type<<") @"<<(int)it->address< -void ShowerDetectorCalib::setCalibItem(const std::string& name, float value) -{ - CalibStruct item; - item = getCalibItem(name); -// std::cout<<"*** ShowerDetectorCalib::setCalibItem(const std::string&, T) ***"<(item) != InvalidCalibStruct) { - if (item.name == name) { - std::ostringstream ostr; - ostr< - -std::ostream& operator<<(std::ostream& os, const QString& someQString) -{ - os << someQString.toStdString(); - return os; -} - -std::ostream& operator<<(std::ostream& os, const std::chrono::time_point& timestamp) -{ - // std::chrono::time_point timestamp = std::chrono::system_clock::now(); - std::chrono::microseconds mus = std::chrono::duration_cast(timestamp.time_since_epoch()); - std::chrono::seconds secs = std::chrono::duration_cast(mus); - std::chrono::microseconds subs = mus - secs; - - os << secs.count() << "." << std::setw(6) << std::setfill('0') << subs.count() << " " << std::setfill(' '); - return os; -} - -std::ostream& operator<<(std::ostream& os, const timespec& ts) -{ - // std::chrono::time_point timestamp = std::chrono::system_clock::now(); - os << ts.tv_sec << "." << std::setw(9) << std::setfill('0') << ts.tv_nsec << " " << std::setfill(' '); - return os; -} diff --git a/source/daemon/src/daemon.cpp b/source/daemon/src/daemon.cpp deleted file mode 100644 index ac0663b2..00000000 --- a/source/daemon/src/daemon.cpp +++ /dev/null @@ -1,2793 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -//#include -#include -#include -#include // std::setfill, std::setw -#include -#include -#include -#include -//#include -#include -//#include -#include -#include -#include - -// for i2cdetect: -extern "C" { -#include "i2c/custom_i2cdetect.h" -} - -#define DAC_BIAS 2 // channel of the dac where bias voltage is set -#define DAC_TH1 0 // channel of the dac where threshold 1 is set -#define DAC_TH2 1 // channel of the dac where threshold 2 is set - -#define DEGREE_CHARCODE 248 - -// REMEMBER: "emit" keyword is just syntactic sugar and not needed AT ALL ... learned it after 1 year *clap* *clap* - -using namespace std; - -static unsigned int HW_VERSION = 0; // default value is set in calibration.h - -int64_t msecdiff(timespec &ts, timespec &st){ - int64_t diff; - diff = (int64_t)ts.tv_sec - (int64_t)st.tv_sec; - diff *= 1000; - diff += ((int64_t)ts.tv_nsec-(int64_t)st.tv_nsec)/1000000; - return diff; -} - -static QVector allMsgCfgID({ - // UBX_CFG_ANT, UBX_CFG_CFG, UBX_CFG_DAT, UBX_CFG_DOSC, - // UBX_CFG_DYNSEED, UBX_CFG_ESRC, UBX_CFG_FIXSEED, UBX_CFG_GEOFENCE, - // UBX_CFG_GNSS, UBX_CFG_INF, UBX_CFG_ITFM, UBX_CFG_LOGFILTER, - // UBX_CFG_MSG, UBX_CFG_NAV5, UBX_CFG_NAVX5, UBX_CFG_NMEA, - // UBX_CFG_ODO, UBX_CFG_PM2, UBX_CFG_PMS, UBX_CFG_PRT, UBX_CFG_PWR, - // UBX_CFG_RATE, UBX_CFG_RINV, UBX_CFG_RST, UBX_CFG_RXM, UBX_CFG_SBAS, - // UBX_CFG_SMGR, UBX_CFG_TMODE2, UBX_CFG_TP5, UBX_CFG_TXSLOT, UBX_CFG_USB - UBX_TIM_TM2,UBX_TIM_TP, - UBX_NAV_CLOCK, UBX_NAV_DGPS, UBX_NAV_AOPSTATUS, UBX_NAV_DOP, - UBX_NAV_POSECEF, UBX_NAV_POSLLH, UBX_NAV_PVT, UBX_NAV_SBAS, UBX_NAV_SOL, - UBX_NAV_STATUS, UBX_NAV_SVINFO, UBX_NAV_TIMEGPS, UBX_NAV_TIMEUTC, UBX_NAV_VELECEF, - UBX_NAV_VELNED, /* UBX_NAV_SAT, */ - UBX_MON_HW, UBX_MON_HW2, UBX_MON_IO, UBX_MON_MSGPP, - UBX_MON_RXBUF, UBX_MON_RXR, UBX_MON_TXBUF - }); - - - -// signal handling stuff: put code to execute before shutdown down there -static int setup_unix_signal_handlers() -{ - struct sigaction hup, term, inte; - - hup.sa_handler = Daemon::hupSignalHandler; - sigemptyset(&hup.sa_mask); - hup.sa_flags = 0; - hup.sa_flags |= SA_RESTART; - - if (sigaction(SIGHUP, &hup, 0)) { - return 1; - } - - term.sa_handler = Daemon::termSignalHandler; - sigemptyset(&term.sa_mask); - term.sa_flags = 0; - term.sa_flags |= SA_RESTART; - - if (sigaction(SIGTERM, &term, 0)) { - return 2; - } - - inte.sa_handler = Daemon::intSignalHandler; - sigemptyset(&inte.sa_mask); - inte.sa_flags = 0; - inte.sa_flags |= SA_RESTART; - - if (sigaction(SIGINT, &inte, 0)) { - return 3; - } - return 0; -} -int Daemon::sighupFd[2]; -int Daemon::sigtermFd[2]; -int Daemon::sigintFd[2]; - -void Daemon::handleSigTerm() -{ - snTerm->setEnabled(false); - char tmp; - ::read(sigtermFd[1], &tmp, sizeof(tmp)); - - // do Qt stuff - if (verbose > 1) { - cout << "\nSIGTERM received" << endl; - } - - // save ublox config in built-in flash to provide latest orbit info of sats for next start-up - // and effectively reduce time-to-first-fix (TTFF) - emit UBXSaveCfg(); - - emit aboutToQuit(); - exit(0); - snTerm->setEnabled(true); -} - -void Daemon::handleSigHup() -{ - snHup->setEnabled(false); - char tmp; - ::read(sighupFd[1], &tmp, sizeof(tmp)); - - // do Qt stuff - if (verbose > 1) { - cout << "\nSIGHUP received" << endl; - } - - // save ublox config in built-in flash to provide latest orbit info of sats for next start-up - // and effectively reduce time-to-first-fix (TTFF) - emit UBXSaveCfg(); - - emit aboutToQuit(); - exit(0); - snHup->setEnabled(true); -} - -void Daemon::handleSigInt() -{ - snInt->setEnabled(false); - char tmp; - ::read(sigintFd[1], &tmp, sizeof(tmp)); - - // do Qt stuff - if (verbose > 1) { - cout << "\nSIGINT received" << endl; - } - if (showin || showout) { - qDebug() << allMsgCfgID.size(); - qDebug() << msgRateCfgs.size(); - for (QMap::iterator it = msgRateCfgs.begin(); it != msgRateCfgs.end(); it++) { - qDebug().nospace() << "0x" << hex << (uint8_t)(it.key() >> 8) << " 0x" << hex << (uint8_t)(it.key() & 0xff) << " " << dec << it.value(); - } - } - - // save ublox config in built-in flash to provide latest orbit info of sats for next start-up - // and effectively reduce time-to-first-fix (TTFF) - emit UBXSaveCfg(); - - emit aboutToQuit(); - exit(0); - snInt->setEnabled(true); -} - - -// begin of the Daemon class -Daemon::Daemon(QString username, QString password, QString new_gpsdevname, int new_verbose, quint8 new_pcaPortMask, - float *new_dacThresh, float new_biasVoltage, bool bias_ON, bool new_dumpRaw, int new_baudrate, - bool new_configGnss, unsigned int new_eventTrigger, QString new_peerAddress, quint16 new_peerPort, - QString new_daemonAddress, quint16 new_daemonPort, bool new_showout, bool new_showin, bool preamp1, bool preamp2, bool gain, QString station_ID, - bool new_polarity1, bool new_polarity2, QObject *parent) - : QTcpServer(parent) -{ - // first, we must set the locale to be independent of the number format of the system's locale. - // We rely on parsing floating point numbers with a decimal point (not a komma) which might fail if not setting the classic locale - // std::locale::global( std::locale( std::cout.getloc(), new punct_facet) ) ); - // std::locale mylocale( std::locale( std::cout.getloc(), new punct_facet) ); - std::locale::global(std::locale::classic()); - - qRegisterMetaType("TcpMessage"); - qRegisterMetaType("GeodeticPos"); - qRegisterMetaType("int32_t"); - qRegisterMetaType("uint32_t"); - qRegisterMetaType("uint16_t"); - qRegisterMetaType("uint8_t"); - qRegisterMetaType("int8_t"); - qRegisterMetaType("bool"); - qRegisterMetaType("CalibStruct"); - qRegisterMetaType>("std::vector"); - qRegisterMetaType>("std::vector"); - qRegisterMetaType>("std::chrono::duration"); - qRegisterMetaType("std::string"); - qRegisterMetaType("LogParameter"); - qRegisterMetaType("UbxTimePulseStruct"); - qRegisterMetaType("UbxDopStruct"); - qRegisterMetaType("timespec"); - qRegisterMetaType("GPIO_SIGNAL"); - qRegisterMetaType("GnssMonHwStruct"); - qRegisterMetaType("GnssMonHw2Struct"); - qRegisterMetaType("UbxTimeMarkStruct"); - qRegisterMetaType("I2cDeviceEntry"); - qRegisterMetaType("PigpiodHandler::EventEdge"); - // signal handling - setup_unix_signal_handlers(); - if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sighupFd)) { - qFatal("Couldn't create HUP socketpair"); - } - - if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sigtermFd)) { - qFatal("Couldn't create TERM socketpair"); - } - if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sigintFd)) { - qFatal("Couldn't createe INT socketpair"); - } - - snHup = new QSocketNotifier(sighupFd[1], QSocketNotifier::Read, this); - connect(snHup, SIGNAL(activated(int)), this, SLOT(handleSigHup())); - snTerm = new QSocketNotifier(sigtermFd[1], QSocketNotifier::Read, this); - connect(snTerm, SIGNAL(activated(int)), this, SLOT(handleSigTerm())); - snInt = new QSocketNotifier(sigintFd[1], QSocketNotifier::Read, this); - connect(snInt, SIGNAL(activated(int)), this, SLOT(handleSigInt())); - - // general - verbose = new_verbose; - if (verbose > 4) { - qDebug() << "daemon running in thread " << this->thread()->objectName(); - } - - if (verbose>3){ - qDebug()<<"QT version is "<3){ - this->thread()->setObjectName("muondetector-daemon"); - qInfo() << this->thread()->objectName() << " thread id (pid): " << syscall(SYS_gettid); - } - - // try to find out on which hardware version we are running - // for this to work, we have to initialize and read the eeprom first - // EEPROM 24AA02 type - eep = new EEPROM24AA02(); - calib = new ShowerDetectorCalib(eep); - if (eep->devicePresent()) { - calib->readFromEeprom(); - if (verbose>2) { - qInfo()<<"EEP device is present"; -// readEeprom(); -// calib->readFromEeprom(); - - // Caution, only for debugging. This code snippet writes a test sequence into the eeprom - if (1==0) { - uint8_t buf[256]; - for (int i=0; i<256; i++) buf[i]=i; - if (!eep->writeBytes(0, 256, buf)) cerr<<"error: write to eeprom failed!"<2) cout<<"eep write took "<getLastTimeInterval()<<" ms"<printCalibList(); - } - } - uint64_t id=calib->getSerialID(); - QString hwIdStr="0x"+QString::number(id,16); -// qInfo()<<"eep unique ID: 0x"<isValid()) { - - //} - } else { - qCritical()<<"eeprom device NOT present!"; - } - CalibStruct verStruct = calib->getCalibItem("VERSION"); - unsigned int version=0; - ShowerDetectorCalib::getValueFromString(verStruct.value,version); - if (version>0) { - HW_VERSION=version; - //if (verbose) - qInfo()<<"Found HW version"<1) { - // print out the current gpio pin mapping - // (function, gpio-pin, direction) - cout<<"GPIO pin mapping:"<first; - cout<second; - switch (GPIO_SIGNAL_MAP[signalId].direction) { - case DIR_IN: cout<<" (in)"; - break; - case DIR_OUT: cout<<" (out)"; - break; - case DIR_IO: cout<<" (i/o)"; - break; - default: cout<<" (undef)"; - } - cout<setObjectName("muondetector-daemon-mqtt"); - connect(this, &Daemon::aboutToQuit, mqttHandlerThread, &QThread::quit); - connect(mqttHandlerThread, &QThread::finished, mqttHandlerThread, &QThread::deleteLater); - - mqttHandler = new MuonPi::MqttHandler(station_ID, verbose-1); - mqttHandler->moveToThread(mqttHandlerThread); - connect(mqttHandler, &MuonPi::MqttHandler::mqttConnectionStatus, this, &Daemon::sendMqttStatus); - connect(fileHandlerThread, &QThread::finished, mqttHandler, &MuonPi::MqttHandler::deleteLater); - connect(this, &Daemon::requestMqttConnectionStatus, mqttHandler, &MuonPi::MqttHandler::onRequestConnectionStatus); - //connect(this, &Daemon::logParameter, mqttHandler, &MqttHandler::sendLog); - mqttHandlerThread->start(); - - - // create fileHandler - fileHandlerThread = new QThread(); - fileHandlerThread->setObjectName("muondetector-daemon-filehandler"); - connect(this, &Daemon::aboutToQuit, fileHandlerThread, &QThread::quit); - connect(fileHandlerThread, &QThread::finished, fileHandlerThread, &QThread::deleteLater); - - fileHandler = new FileHandler(username, password); - fileHandler->moveToThread(fileHandlerThread); - connect(this, &Daemon::aboutToQuit, fileHandler, &FileHandler::deleteLater); - //connect(this, &Daemon::logParameter, fileHandler, &FileHandler::onReceivedLogParameter); - connect(fileHandlerThread, &QThread::started, fileHandler, &FileHandler::start); - connect(fileHandlerThread, &QThread::finished, fileHandler, &FileHandler::deleteLater); - connect(fileHandler, &FileHandler::mqttConnect, mqttHandler, &MuonPi::MqttHandler::start); - fileHandlerThread->start(); - - // connect log signals to and from log engine and filehandler - connect(this, &Daemon::logParameter, &logEngine, &LogEngine::onLogParameterReceived); - connect(&logEngine, &LogEngine::sendLogString, mqttHandler, &MuonPi::MqttHandler::sendLog); - connect(&logEngine, &LogEngine::sendLogString, fileHandler, &FileHandler::writeToLogFile); - // connect to the regular log timer signal to log several non-regularly polled parameters - connect(&logEngine, &LogEngine::logIntervalSignal, this, &Daemon::onLogParameterPolled); - // connect the once-log flag reset slot of log engine with the logRotate signal of filehandler - connect(fileHandler, &FileHandler::logRotateSignal, &logEngine, &LogEngine::onOnceLogTrigger); - - // instantiate, detect and initialize all other i2c devices - // LM75A temp sensor - lm75 = new LM75(); - if (lm75->devicePresent()) { - if (verbose>2) { - qInfo()<<"LM75 device is present."; - qDebug()<<"temperature is "<getTemperature()<< DEGREE_CHARCODE <<"C"; - qDebug()<<"readout took"<getLastTimeInterval()<<"ms"; - } - } else { - qWarning()<<"LM75 device NOT present!"; - } - // 4ch, 16/14bit ADC ADS1115/1015 - adc = new ADS1115(); - if (adc->devicePresent()) { - adc->setPga(ADS1115::PGA4V); - //adc->setPga(0, ADS1115::PGA2V); -// adc->setRate(0x06); // ADS1115::RATE475 - adc->setRate(0x07); // ADS1115::RATE860 - adc->setAGC(false); - if (!adc->setDataReadyPinMode()) { - qWarning()<<"error: failed setting data ready pin mode (setting thresh regs)"; - } - - // set up sampling timer used for continuous sampling mode - samplingTimer.setInterval(MuonPi::Config::Hardware::trace_sampling_interval); - samplingTimer.setSingleShot(false); - samplingTimer.setTimerType(Qt::PreciseTimer); - connect(&samplingTimer, &QTimer::timeout, this, &Daemon::sampleAdc0TraceEvent); - - // set up peak sampling mode - setAdcSamplingMode(ADC_MODE_PEAK); - - if (verbose>2) { - qInfo()<<"ADS1115 device is present."; - bool ok=adc->setLowThreshold(0b00000000); - ok = ok && adc->setHighThreshold(0b10000000); - if (ok) qDebug()<<"successfully setting threshold registers"; - else qWarning()<<"error: failed setting threshold registers"; - qDebug()<<"single ended channels:"; - qDebug()<<"ch0: "<readADC(0)<<" ch1: "<readADC(1) - <<" ch2: "<readADC(2)<<" ch3: "<readADC(3); - adc->setDiffMode(true); - qDebug()<<"diff channels:"; - qDebug()<<"ch0-1: "<readADC(0)<<" ch0-3: "<readADC(1) - <<" ch1-3: "<readADC(2)<<" ch2-3: "<readADC(3); - adc->setDiffMode(false); - qDebug()<<"readout took "<getLastTimeInterval()<<" ms"; - } - } else { - adcSamplingMode = ADC_MODE_DISABLED; - qWarning()<<"ADS1115 device NOT present!"; - } - - // 4ch DAC MCP4728 - dac = new MCP4728(); - if (dac->devicePresent()) { - if (verbose>2) { - qInfo()<<"MCP4728 device is present."; - qDebug()<<"DAC registers / output voltages:"; - for (int i=0; i<4; i++) { - MCP4728::DacChannel dacChannel; - MCP4728::DacChannel eepromChannel; - eepromChannel.eeprom=true; - dac->readChannel(i, dacChannel); - dac->readChannel(i, eepromChannel); - qDebug()<<" ch"<getLastTimeInterval()<<" ms"; - } - } else { - qCritical("MCP4728 device NOT present!"); - // this error is critical, since the whole concept of counting muons is based on - // the function of the threshold discriminator - // we should quit here returning an error code (?) - //exit(-1); - } - float *tempThresh = new_dacThresh; - for (int i=std::min(DAC_TH1, DAC_TH2); i<=std::max(DAC_TH1, DAC_TH2); i++) { - if (tempThresh[i]<0. && dac->devicePresent()) { - MCP4728::DacChannel dacChannel; - MCP4728::DacChannel eepromChannel; - eepromChannel.eeprom=true; - dac->readChannel(i, dacChannel); - dac->readChannel(i, eepromChannel); - tempThresh[i]=MCP4728::code2voltage(dacChannel); - //tempThresh[i]=code2voltage(eepromChannel); - } - } - dacThresh.push_back(tempThresh[0]); - dacThresh.push_back(tempThresh[1]); - - - if (dac->devicePresent()) { - MCP4728::DacChannel eeprom_value; - eeprom_value.eeprom = true; - dac->readChannel(DAC_BIAS, eeprom_value); - if (eeprom_value.value == 0) { - setBiasVoltage(MuonPi::Config::Hardware::DAC::Voltage::bias); - setDacThresh(0, MuonPi::Config::Hardware::DAC::Voltage::threshold[0]); - setDacThresh(1, MuonPi::Config::Hardware::DAC::Voltage::threshold[1]); - } - } - - biasVoltage = new_biasVoltage; - if (biasVoltage<0. && dac->devicePresent()) { - MCP4728::DacChannel dacChannel; - MCP4728::DacChannel eepromChannel; - eepromChannel.eeprom=true; - dac->readChannel(DAC_BIAS, dacChannel); - dac->readChannel(DAC_BIAS, eepromChannel); - biasVoltage=MCP4728::code2voltage(dacChannel); - //tempThresh[i]=code2voltage(eepromChannel); - } - - // PCA9536 4 bit I/O I2C device used for selecting the UBX timing input - pca = new PCA9536(); - if (pca->devicePresent()) { - if (verbose>2) { - qInfo()<<"PCA9536 device is present."<getInputState(); - qDebug()<<"readout took "<getLastTimeInterval()<<" ms"; - } - pca->setOutputPorts(0b00000111); - setPcaChannel(new_pcaPortMask); - } else { - qCritical()<<"PCA9536 device NOT present!"; - } - - if (dac->devicePresent()) { - if (dacThresh[0] > 0) dac->setVoltage(DAC_TH1, dacThresh[0]); - if (dacThresh[1] > 0) dac->setVoltage(DAC_TH2, dacThresh[1]); - if (biasVoltage > 0) dac->setVoltage(DAC_BIAS, biasVoltage); - } - - -// removed initialization of ublox i2c interface since it doesn't work properly on RPi -// the Ublox i2c relies on clock stretching, which RPi is not supporting -// the ublox's i2c address is still occupied but locked, i.e. access is prohibited - ubloxI2c = new UbloxI2c(0x42); - ubloxI2c->lock(); - if (ubloxI2c->devicePresent()) { - if (verbose>2) { - qInfo()<<"ublox I2C device interface is present."; - uint16_t bufcnt = 0; - bool ok = ubloxI2c->getTxBufCount(bufcnt); - if (ok) qDebug()<<"bytes in TX buf: "<getTxBufCount(bufcnt); - //if (ok) cout<<"bytes in TX buf: "<getData(); - //cout<<"string length: "<getData(); - //ok = ubloxI2c->getTxBufCount(bufcnt); - //if (ok) cout<<"bytes in TX buf: "<devicePresent()) { - if (verbose>-1) { - qInfo()<<"I2C SSD1306-type OLED display found at address 0x3c"; - } - oled->begin(); - oled->clearDisplay(); - - // text display tests - oled->setTextSize(1); - oled->setTextColor(Adafruit_SSD1306::WHITE); - oled->setCursor(0,2); - oled->print("*Cosmic Shower Det.*\n"); - oled->print("V"); - oled->print(MuonPi::Version::software.string().c_str()); - oled->print("\n"); - //oled->print("V 1.2.0\n"); - // display.setTextColor(BLACK, WHITE); // 'inverted' text -/* - struct timespec tNow; - clock_gettime(CLOCK_REALTIME, &tNow); - - oled->printf("time:\n%ld.%06d\n", tNow.tv_sec, tNow.tv_nsec/1000L); - oled->printf(" %02d s", tNow.tv_sec%60); - oled->drawHorizontalBargraph(0,24,128,8,1, (tNow.tv_sec%60)*10/6); -*/ - // display.setTextSize(1); - // display.setTextColor(WHITE); - // display.printf("0x%8X\n", 0xDEADBEEF); - oled->display(); - usleep(500000L); - connect(&oledUpdateTimer, SIGNAL(timeout()), this, SLOT(updateOledDisplay())); - - oledUpdateTimer.start(MuonPi::Config::Hardware::OLED::update_interval); - } else { - //cout<<"I2C OLED display NOT present"<3) { - cout<<"Nr. of invoked I2C devices (plain count): "<getAddress()<<" "<getTitle(); - if (i2cDevice::getGlobalDeviceList()[i]->devicePresent()) cout<<" present"<getCapabilities(); - } - - // for ublox gnss module - gpsdevname = new_gpsdevname; - dumpRaw = new_dumpRaw; - baudrate = new_baudrate; - configGnss = new_configGnss; - showout = new_showout; - showin = new_showin; - - // for tcp connection with fileServer - peerPort = new_peerPort; - if (peerPort == 0) { - peerPort = 51508; - } - peerAddress = new_peerAddress; - if (peerAddress.isEmpty() || peerAddress == "local" || peerAddress == "localhost") { - peerAddress = QHostAddress(QHostAddress::LocalHost).toString(); - } - - if (new_daemonAddress.isEmpty()) { - // if not otherwise specified: listen on all available addresses - daemonAddress = QHostAddress(QHostAddress::Any); - if (verbose > 3) { - qDebug() << "daemon address: "<listen(daemonAddress, daemonPort)) { - qCritical() << tr("Unable to start the server: %1.\n").arg(this->errorString()); - } - else { - if (verbose > 3) { - qInfo() << tr("\nThe server is running on\n\nIP: %1\nport: %2\n") - .arg(daemonAddress.toString()).arg(serverPort()); - } - } - flush(cout); - - // set up histograms - setupHistos(); - - // connect to the pigpio daemon interface for gpio control - connectToPigpiod(); - - // set up the rate buffer for all GPIO signals - rateBuffer.clear(); - connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); - -// connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if ( histoMap.find("gpioEventInterval")!=histoMap.end() - && ( GPIO_PINMAP[eventTrigger] == gpio ) ) - { - //checkRescaleHisto(histoMap["gpioEventInterval"], 1e-6*nsecs); - histoMap["gpioEventInterval"].fill( 1e-6 * ns.count() ); - } - } ); - - connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) -// connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if ( histoMap.find("gpioEventIntervalShort")!=histoMap.end() ) - { - if ( nsecs/1000 <= histoMap["gpioEventIntervalShort"].getMax() ) { - histoMap["gpioEventIntervalShort"].fill( 1e-3 * nsecs ); - } - } - } ); - - // establish ublox gnss module connection - connectToGps(); - //delay(1000); - - // configure the ublox module with preset ubx messages, if required - if (configGnss) { - configGps(); - } - pollAllUbxMsgRate(); - - // set up cyclic timer monitoring following operational parameters: - // temp, vadc, vbias, ibias - parameterMonitorTimer.setInterval(MuonPi::Config::Hardware::monitor_interval); - parameterMonitorTimer.setSingleShot(false); - connect(¶meterMonitorTimer, &QTimer::timeout, this, &Daemon::aquireMonitoringParameters); - parameterMonitorTimer.start(); -} - - -Daemon::~Daemon() { - snHup.clear(); - snTerm.clear(); - snInt.clear(); - if (pca!=nullptr){ delete pca; pca = nullptr; } - if (dac!=nullptr){ delete dac; dac = nullptr; } - if (adc!=nullptr){ delete adc; adc = nullptr; } - if (eep!=nullptr){ delete eep; eep = nullptr; } - if (calib!=nullptr){ delete calib; calib = nullptr; } - if (ubloxI2c!=nullptr){ delete ubloxI2c; ubloxI2c = nullptr; } - if (oled!=nullptr){ delete oled; oled = nullptr; } - pigHandler.clear(); - unsigned long timeout = 2000; - if (!mqttHandlerThread->wait(timeout)){ - qWarning() << "Timeout waiting for thread "+mqttHandlerThread->objectName(); - } - if (!fileHandlerThread->wait(timeout)){ - qWarning() << "Timeout waiting for thread "+fileHandlerThread->objectName(); - } - if (!pigThread->wait(timeout)){ - qWarning() << "Timeout waiting for thread "+pigThread->objectName(); - } - if (!gpsThread->wait(timeout)){ - qWarning() << "Timeout waiting for thread "+gpsThread->objectName(); - } - if (!tcpThread->wait(timeout)){ - qWarning() << "Timeout waiting for thread "+tcpThread->objectName(); - } -} - -void Daemon::connectToPigpiod(){ -/* - const QVector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], - GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); -*/ - const std::vector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], - GPIO_PINMAP[TIMEPULSE] }); - pigHandler = new PigpiodHandler(gpio_pins); - //tdc7200 = new TDC7200(GPIO_PINMAP[TDC_INTB]); - pigThread = new QThread(); - pigThread->setObjectName("muondetector-daemon-pigpio"); - pigHandler->moveToThread(pigThread); - //tdc7200->moveToThread(pigThread); - connect(this, &Daemon::aboutToQuit, pigThread, &QThread::quit); - connect(pigThread, &QThread::finished, pigThread, &QThread::deleteLater); - - //pighandler <-> tdc -/* - connect(pigHandler, &PigpiodHandler::spiData, tdc7200, &TDC7200::onDataReceived); - connect(pigHandler, &PigpiodHandler::signal, tdc7200, &TDC7200::onDataAvailable); - connect(tdc7200, &TDC7200::readData, pigHandler, &PigpiodHandler::readSpi); - connect(tdc7200, &TDC7200::writeData, pigHandler, &PigpiodHandler::writeSpi); - - //tdc <-> thread & daemon - connect(tdc7200, &TDC7200::tdcEvent, this, [this](double usecs){ - if (histoMap.find("Time-to-Digital Time Diff")!=histoMap.end()) { - checkRescaleHisto(histoMap["Time-to-Digital Time Diff"],usecs); - histoMap["Time-to-Digital Time Diff"].fill(usecs); - } - }); - connect(tdc7200, &TDC7200::statusUpdated, this, [this](bool isPresent){ - spiDevicePresent = isPresent; - sendSpiStats(); - }); - connect(pigThread, &QThread::started, tdc7200, &TDC7200::initialise); - connect(pigThread, &QThread::finished, tdc7200, &TDC7200::deleteLater); -*/ - //pigHandler <-> thread & daemon - connect(this, &Daemon::aboutToQuit, pigHandler, &PigpiodHandler::stop); - connect(pigThread, &QThread::finished, pigHandler, &PigpiodHandler::deleteLater); - connect(this, &Daemon::GpioSetOutput, pigHandler, &PigpiodHandler::setPinOutput); - connect(this, &Daemon::GpioSetInput, pigHandler, &PigpiodHandler::setPinInput); -/// connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); -/// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); - connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); - connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); -// connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::onGpioPinEvent); -// connect(pigHandler, &PigpiodHandler::timePulseDiff, this, [this](qint32 usecs) - - struct timespec ts_res; - clock_getres(CLOCK_REALTIME, &ts_res); - if (verbose>3) { - qInfo()<<"the timing resolution of the system clock is "<toConsole("aboutToQuit called and signal emitted\n");}); - timespec_get(&lastRateInterval, TIME_UTC); - startOfProgram = lastRateInterval; - -// TODO: delete following block -/* - connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin){ -// connect(&rateBuffer, &RateBuffer::throttledSignal, this, [this](uint8_t gpio_pin){ - rateCounterIntervalActualisation(); - if (gpio_pin==GPIO_PINMAP[EVT_XOR]){ - xorCounts.back()++; - //xorCounts.pop_back(); - //value++; - //xorCounts.push_back(value); - } - if (gpio_pin==GPIO_PINMAP[EVT_AND]){ - //quint64 value = andCounts.back(); - andCounts.back()++; - //andCounts.pop_back(); - //value++; - //andCounts.push_back(value); - } - }); - */ - pigThread->start(); - rateBufferReminder.setInterval(rateBufferInterval); - rateBufferReminder.setSingleShot(false); - connect(&rateBufferReminder, &QTimer::timeout, this, &Daemon::onRateBufferReminder); - rateBufferReminder.start(); - emit GpioSetOutput(GPIO_PINMAP[UBIAS_EN]); - emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION==1)?(biasON?1:0):(biasON?0:1)); - emit GpioSetOutput(GPIO_PINMAP[PREAMP_1]); - emit GpioSetOutput(GPIO_PINMAP[PREAMP_2]); - emit GpioSetOutput(GPIO_PINMAP[GAIN_HL]); - emit GpioSetState(GPIO_PINMAP[PREAMP_1],preampStatus[0]); - emit GpioSetState(GPIO_PINMAP[PREAMP_2],preampStatus[1]); - emit GpioSetState(GPIO_PINMAP[GAIN_HL],gainSwitch); - emit GpioSetOutput(GPIO_PINMAP[STATUS1]); - emit GpioSetOutput(GPIO_PINMAP[STATUS2]); - emit GpioSetState(GPIO_PINMAP[STATUS1], 0); - emit GpioSetState(GPIO_PINMAP[STATUS2], 0); - emit GpioSetPullUp(GPIO_PINMAP[ADC_READY]); - emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], PigpiodHandler::EventEdge::RisingEdge); - auto it=GPIO_PINMAP.find(eventTrigger); - if (it != GPIO_PINMAP.end()) { -// pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); - emit GpioRegisterForCallback(GPIO_PINMAP[eventTrigger], PigpiodHandler::EventEdge::RisingEdge); - } -// connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); - - if (HW_VERSION>1) { - //emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); - emit GpioRegisterForCallback(GPIO_PINMAP[PREAMP_FAULT], PigpiodHandler::EventEdge::FallingEdge); - emit GpioSetPullUp(GPIO_PINMAP[PREAMP_FAULT]); - //emit GpioSetInput(GPIO_PINMAP[TDC_INTB]); - emit GpioRegisterForCallback(GPIO_PINMAP[TDC_INTB], PigpiodHandler::EventEdge::FallingEdge); - //emit GpioSetInput(GPIO_PINMAP[TIME_MEAS_OUT]); - emit GpioRegisterForCallback(GPIO_PINMAP[TIME_MEAS_OUT], PigpiodHandler::EventEdge::RisingEdge); - } - if (HW_VERSION>=3) { - emit GpioSetOutput(GPIO_PINMAP[IN_POL1]); - emit GpioSetOutput(GPIO_PINMAP[IN_POL2]); - emit GpioSetState(GPIO_PINMAP[IN_POL1],polarity1); - emit GpioSetState(GPIO_PINMAP[IN_POL2],polarity2); - } - -} - -void Daemon::connectToGps() { - // before connecting to gps we have to make sure all other programs are closed - // and serial echo is off - if (gpsdevname.isEmpty()) { - return; - } - QProcess prepareSerial; - QString command = "stty"; - QStringList args = { "-F", "/dev/ttyAMA0", "-echo", "-onlcr" }; - prepareSerial.start(command, args, QIODevice::ReadWrite); - prepareSerial.waitForFinished(); - - // here is where the magic threading happens look closely - qtGps = new QtSerialUblox(gpsdevname, gpsTimeout, baudrate, dumpRaw, verbose-1, showout, showin); - gpsThread = new QThread(); - gpsThread->setObjectName("muondetector-daemon-gnss"); - qtGps->moveToThread(gpsThread); - // connect all signals about quitting - connect(this, &Daemon::aboutToQuit, gpsThread, &QThread::quit); - connect(gpsThread, &QThread::finished, gpsThread, &QThread::deleteLater); - connect(gpsThread, &QThread::finished, qtGps, &QtSerialUblox::deleteLater); - // connect all signals not coming from Daemon to gps - connect(qtGps, &QtSerialUblox::toConsole, this, &Daemon::gpsToConsole); - connect(gpsThread, &QThread::started, qtGps, &QtSerialUblox::makeConnection); - connect(qtGps, &QtSerialUblox::gpsRestart, this, &Daemon::connectToGps); - // connect all command signals for ublox module here - connect(this, &Daemon::UBXSetCfgPrt, qtGps, &QtSerialUblox::UBXSetCfgPrt); - connect(this, &Daemon::UBXSetCfgMsgRate, qtGps, &QtSerialUblox::UBXSetCfgMsgRate); - connect(this, &Daemon::UBXSetCfgRate, qtGps, &QtSerialUblox::UBXSetCfgRate); - connect(this, &Daemon::sendPollUbxMsgRate, qtGps, &QtSerialUblox::pollMsgRate); - connect(this, &Daemon::sendPollUbxMsg, qtGps, &QtSerialUblox::pollMsg); - connect(this, &Daemon::sendUbxMsg, qtGps, &QtSerialUblox::enqueueMsg); - connect(qtGps, &QtSerialUblox::UBXReceivedAckNak, this, &Daemon::UBXReceivedAckNak); - connect(qtGps, &QtSerialUblox::UBXreceivedMsgRateCfg, this, &Daemon::UBXReceivedMsgRateCfg); - connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedGeodeticPos, this, &Daemon::onGpsPropertyUpdatedGeodeticPos); - connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedGnss, this, &Daemon::onGpsPropertyUpdatedGnss); - connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedUint32, this, &Daemon::gpsPropertyUpdatedUint32); - connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedInt32, this, &Daemon::gpsPropertyUpdatedInt32); - connect(qtGps, &QtSerialUblox::gpsPropertyUpdatedUint8, this, &Daemon::gpsPropertyUpdatedUint8); - connect(qtGps, &QtSerialUblox::gpsMonHW, this, &Daemon::onGpsMonHWUpdated); - connect(qtGps, &QtSerialUblox::gpsMonHW2, this, &Daemon::onGpsMonHW2Updated); - connect(qtGps, &QtSerialUblox::gpsVersion, this, &Daemon::UBXReceivedVersion); - connect(qtGps, &QtSerialUblox::UBXCfgError, this, &Daemon::toConsole); - connect(qtGps, &QtSerialUblox::UBXReceivedGnssConfig, this, &Daemon::onUBXReceivedGnssConfig); - connect(qtGps, &QtSerialUblox::UBXReceivedTP5, this, &Daemon::onUBXReceivedTP5); - connect(qtGps, &QtSerialUblox::UBXReceivedTxBuf, this, &Daemon::onUBXReceivedTxBuf); - connect(qtGps, &QtSerialUblox::UBXReceivedRxBuf, this, &Daemon::onUBXReceivedRxBuf); - connect(this, &Daemon::UBXSetDynModel, qtGps, &QtSerialUblox::setDynamicModel); - connect(this, &Daemon::resetUbxDevice, qtGps, &QtSerialUblox::UBXReset); - connect(this, &Daemon::setGnssConfig, qtGps, &QtSerialUblox::onSetGnssConfig); - connect(this, &Daemon::UBXSetCfgTP5, qtGps, &QtSerialUblox::UBXSetCfgTP5); - connect(this, &Daemon::UBXSetMinMaxSVs, qtGps, &QtSerialUblox::UBXSetMinMaxSVs); - connect(this, &Daemon::UBXSetMinCNO, qtGps, &QtSerialUblox::UBXSetMinCNO); - connect(this, &Daemon::UBXSetAopCfg, qtGps, &QtSerialUblox::UBXSetAopCfg); - connect(this, &Daemon::UBXSaveCfg, qtGps, &QtSerialUblox::UBXSaveCfg); - connect(qtGps, &QtSerialUblox::UBXReceivedTimeTM2, this, &Daemon::onUBXReceivedTimeTM2); - - connect(qtGps, &QtSerialUblox::UBXReceivedDops, this, [this](const UbxDopStruct& dops){ - currentDOP=dops; - emit logParameter(LogParameter("positionDOP", QString::number(dops.pDOP/100.), LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("timeDOP", QString::number(dops.tDOP/100.), LogParameter::LOG_AVERAGE)); - }); - - // connect fileHandler related stuff - if (fileHandler != nullptr){ - //connect(qtGps, &QtSerialUblox::timTM2, fileHandler, &FileHandler::writeToDataFile); - connect(this, &Daemon::eventMessage, fileHandler, &FileHandler::writeToDataFile); - //connect(qtGps, &QtSerialUblox::timTM2, mqttHandler, &MuonPi::MqttHandler::sendData); - connect(this, &Daemon::eventMessage, mqttHandler, &MuonPi::MqttHandler::sendData); - } - // after thread start there will be a signal emitted which starts the qtGps makeConnection function - gpsThread->start(); -} - -void Daemon::incomingConnection(qintptr socketDescriptor) { - if (verbose > 4) { - qDebug() << "incoming connection"; - } - tcpThread = new QThread(); - tcpThread->setObjectName("muondetector-daemon-tcp"); -// TcpConnection *tcpConnection = new TcpConnection(socketDescriptor, verbose); - tcpConnection = new TcpConnection(socketDescriptor, verbose); - tcpConnection->moveToThread(tcpThread); - // connect all signals about quitting - connect(this, &Daemon::aboutToQuit, tcpConnection, &TcpConnection::closeThisConnection); - connect(this, &Daemon::closeConnection, tcpConnection, &TcpConnection::closeConnection); - connect(tcpConnection, &TcpConnection::finished, tcpThread, &QThread::quit); - connect(tcpThread, &QThread::finished, tcpThread, &QThread::deleteLater); - connect(tcpThread, &QThread::finished, tcpConnection, &TcpConnection::deleteLater); - // connect all other signals - connect(tcpThread, &QThread::started, tcpConnection, &TcpConnection::receiveConnection); - connect(this, &Daemon::sendTcpMessage, tcpConnection, &TcpConnection::sendTcpMessage); - connect(tcpConnection, &TcpConnection::receivedTcpMessage, this, &Daemon::receivedTcpMessage); - connect(tcpConnection, &TcpConnection::toConsole, this, &Daemon::toConsole); -// connect(tcpConnection, &TcpConnection::madeConnection, this, [this](QString, quint16, QString , quint16) { emit sendPollUbxMsg(UBX_MON_VER); }); - connect(tcpConnection, &TcpConnection::madeConnection, this, &Daemon::onMadeConnection); - connect(tcpConnection, &TcpConnection::connectionTimeout, this, &Daemon::onStoppedConnection); - tcpThread->start(); - -/* - emit sendPollUbxMsg(UBX_MON_VER); - emit sendPollUbxMsg(UBX_CFG_GNSS); - emit sendPollUbxMsg(UBX_CFG_NAV5); - emit sendPollUbxMsg(UBX_CFG_TP5); - emit sendPollUbxMsg(UBX_CFG_NAVX5); - - sendBiasStatus(); - sendBiasVoltage(); - sendDacThresh(0); - sendDacThresh(1); - sendPcaChannel(); - sendEventTriggerSelection(); -*/ - - pollAllUbxMsgRate(); - emit requestMqttConnectionStatus(); -} - -// Histogram functions -void Daemon::setupHistos() { - Histogram hist=Histogram("geoHeight",200,0.,199.); - hist.setUnit("m"); - histoMap["geoHeight"]=hist; - hist=Histogram("geoLongitude",200,0.,0.003); - hist.setUnit("deg"); - histoMap["geoLongitude"]=hist; - hist=Histogram("geoLatitude",200,0.,0.003); - hist.setUnit("deg"); - histoMap["geoLatitude"]=hist; - hist=Histogram("weightedGeoHeight",200,0.,199.); - hist.setUnit("m"); - histoMap["weightedGeoHeight"]=hist; - hist=Histogram("pulseHeight",500,0.,3.8); - hist.setUnit("V"); - histoMap["pulseHeight"]=hist; - hist=Histogram("adcSampleTime",500,0.,49.9); - hist.setUnit("ms"); - histoMap["adcSampleTime"]=hist; - hist=Histogram("UbxEventLength",100,50.,149.); - hist.setUnit("ns"); - histoMap["UbxEventLength"]=hist; - hist=Histogram("gpioEventInterval",400,0.,2000.); - hist.setUnit("ms"); - histoMap["gpioEventInterval"]=hist; - hist=Histogram("gpioEventIntervalShort",50,0.,49.); - hist.setUnit("us"); - histoMap["gpioEventIntervalShort"]=hist; - hist=Histogram("UbxEventInterval",400,0.,2000.); - hist.setUnit("ms"); - histoMap["UbxEventInterval"]=hist; - hist=Histogram("TPTimeDiff",200,-999.,1000.); - hist.setUnit("us"); - histoMap["TPTimeDiff"]=hist; - hist=Histogram("Time-to-Digital Time Diff",400, 0., 1e6); - hist.setUnit("ns"); - histoMap["Time-to-Digital Time Diff"]=hist; - hist=Histogram("Bias Voltage", 500, 0., 1.); - hist.setUnit("V"); - histoMap["Bias Voltage"]=hist; - hist=Histogram("Bias Current", 200, 0., 50.); - hist.setUnit("uA"); - histoMap["Bias Current"]=hist; -} - -void Daemon::clearHisto(const QString& histoName){ - if (histoMap.find(histoName)!=histoMap.end()) { - histoMap[histoName].clear(); - emit sendHistogram(histoMap[histoName]); - } - return; -} - -void Daemon::rescaleHisto(Histogram& hist, double center, double width) { - hist.setMin(center-width/2.); - hist.setMax(center+width/2.); - hist.clear(); -} - -void Daemon::rescaleHisto(Histogram& hist, double center) { - double width=hist.getMax()-hist.getMin(); - rescaleHisto(hist, center, width); -} - -void Daemon::checkRescaleHisto(Histogram& hist, double newValue) { - // Strategy: check if more than 10% of all entries in underflow/overflow - // set new center to old mean - // set center to newValue if histo empty or only underflow/overflow filled - // histo will not be filled with supplied value, it has to be done externally - double entries=hist.getEntries(); - // do nothing if histo is empty - if (entries<3.) { - return; - rescaleHisto(hist, newValue); - } - double ufl=hist.getUnderflow(); - double ofl=hist.getOverflow(); - entries-=ufl+ofl; - double range=hist.getMax()-hist.getMin(); - if (ufl>0. && ofl>0. && (ufl+ofl)>0.02*entries) { - // range is too small, underflow and overflow have more than 2% of all entries - rescaleHisto(hist, hist.getMean(), 1.2*range); - } else if (ufl>0.02*entries) { -// if (entries<1.) rescaleHisto(hist, hist.getMin()-(hist.getMax()-hist.getMin())/2.); - if (entries<1.) rescaleHisto(hist, newValue); - else rescaleHisto(hist, hist.getMean(), 1.2*range); - } else if (ofl>0.02*entries) { -// if (entries<1.) rescaleHisto(hist, hist.getMax()+(hist.getMax()-hist.getMin())/2.); - if (entries<1.) rescaleHisto(hist, newValue); - else rescaleHisto(hist, hist.getMean(), 1.2*range); - } else if (ufl<1e-3 && ofl<1e-3) { - // check if range is too wide - if (entries>100) { - int lowest = hist.getLowestOccupiedBin(); - int highest = hist.getHighestOccupiedBin(); - if ((float)lowest/hist.getNrBins()>0.45 && (float)(hist.getNrBins()-highest)/hist.getNrBins()>0.45) rescaleHisto(hist, hist.getMean(), 0.75*range); - } - } -} - -// ALL FUNCTIONS ABOUT TCPMESSAGE SENDING AND RECEIVING -void Daemon::receivedTcpMessage(TcpMessage tcpMessage) { -// quint16 msgID = tcpMessage.getMsgID(); - TCP_MSG_KEY msgID = static_cast(tcpMessage.getMsgID()); - if (msgID == TCP_MSG_KEY::MSG_THRESHOLD) { - uint8_t channel; - float threshold; - *(tcpMessage.dStream) >> channel >> threshold; - if (threshold<0.001) { - if (verbose>2) qWarning()<<"setting DAC "<> voltage; - setBiasVoltage(voltage); - if (histoMap.find("pulseHeight")!=histoMap.end()) histoMap["pulseHeight"].clear(); - sendBiasVoltage(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST){ - sendBiasVoltage(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_BIAS_SWITCH){ - bool status; - *(tcpMessage.dStream) >> status; - setBiasStatus(status); - //pulseHeightHisto.clear(); - sendBiasStatus(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_BIAS_VOLTAGE_REQUEST){ - sendBiasStatus(); - } - if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH){ - quint8 channel; - bool status; - *(tcpMessage.dStream) >> channel >> status; - if (channel==0) { - preampStatus[0]=status; - emit GpioSetState(GPIO_PINMAP[PREAMP_1], status); - emit logParameter(LogParameter("preampSwitch1", QString::number((int)preampStatus[0]), LogParameter::LOG_EVERY)); - //pulseHeightHisto.clear(); - } else if (channel==1) { - preampStatus[1]=status; - emit GpioSetState(GPIO_PINMAP[PREAMP_2], status); - emit logParameter(LogParameter("preampSwitch2", QString::number((int)preampStatus[1]), LogParameter::LOG_EVERY)); - } - sendPreampStatus(0); - sendPreampStatus(1); - return; - } - if (msgID == TCP_MSG_KEY::MSG_PREAMP_SWITCH_REQUEST){ - sendPreampStatus(0); - sendPreampStatus(1); - } - if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH){ - bool pol1,pol2; - *(tcpMessage.dStream) >> pol1 >> pol2; - if (HW_VERSION>=3 && pol1 != polarity1) { - polarity1=pol1; - emit GpioSetState(GPIO_PINMAP[IN_POL1], polarity1); - emit logParameter(LogParameter("polaritySwitch1", QString::number((int)polarity1), LogParameter::LOG_EVERY)); - } - if (HW_VERSION>=3 && pol2 != polarity2) { - polarity2=pol2; - emit GpioSetState(GPIO_PINMAP[IN_POL2], polarity2); - emit logParameter(LogParameter("polaritySwitch2", QString::number((int)polarity2), LogParameter::LOG_EVERY)); - } - sendPolarityStatus(); - } - if (msgID == TCP_MSG_KEY::MSG_POLARITY_SWITCH_REQUEST){ - sendPolarityStatus(); - } - if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH){ - bool status; - *(tcpMessage.dStream) >> status; - gainSwitch=status; - emit GpioSetState(GPIO_PINMAP[GAIN_HL], status); - if (histoMap.find("pulseHeight")!=histoMap.end()) histoMap["pulseHeight"].clear(); - //pulseHeightHisto.clear(); - emit logParameter(LogParameter("gainSwitch", QString::number((int)gainSwitch), LogParameter::LOG_EVERY)); - sendGainSwitchStatus(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_GAIN_SWITCH_REQUEST){ - sendGainSwitchStatus(); - } - if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE_REQUEST) { -// if (msgID == ubxMsgRateRequest) { - sendUbxMsgRates(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_UBX_RESET) { - uint32_t resetFlags = QtSerialUblox::RESET_WARM | QtSerialUblox::RESET_SW; - emit resetUbxDevice(resetFlags); - pollAllUbxMsgRate(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_UBX_CONFIG_DEFAULT) { - configGps(); - pollAllUbxMsgRate(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_UBX_MSG_RATE){ - QMap ubxMsgRates; - *(tcpMessage.dStream) >> ubxMsgRates; - setUbxMsgRates(ubxMsgRates); - } - if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH){ - quint8 portMask; - *(tcpMessage.dStream) >> portMask; - setPcaChannel((uint8_t)portMask); - sendPcaChannel(); -// ubxTimeLengthHisto.clear(); - if (histoMap.find("UbxEventLength")!=histoMap.end()) histoMap["UbxEventLength"].clear(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_PCA_SWITCH_REQUEST){ - sendPcaChannel(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER){ - unsigned int signal; - *(tcpMessage.dStream) >> signal; - setEventTriggerSelection((GPIO_SIGNAL)signal); - usleep(1000); - sendEventTriggerSelection(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_EVENTTRIGGER_REQUEST){ - sendEventTriggerSelection(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE_REQUEST){ - quint8 whichRate; - quint16 number; - *(tcpMessage.dStream) >> number >> whichRate; - sendGpioRates(number, whichRate); - } - if (msgID == TCP_MSG_KEY::MSG_GPIO_RATE_RESET){ - clearRates(); - return; - } - if (msgID == TCP_MSG_KEY::MSG_DAC_REQUEST){ - quint8 channel; - *(tcpMessage.dStream) >> channel; - MCP4728::DacChannel channelData; - if (!dac->devicePresent()) return; - dac->readChannel(channel, channelData); - float voltage = MCP4728::code2voltage(channelData); - sendDacReadbackValue(channel, voltage); - } - if (msgID == TCP_MSG_KEY::MSG_ADC_SAMPLE_REQUEST){ - quint8 channel; - *(tcpMessage.dStream) >> channel; - sampleAdcEvent(channel); - } - if (msgID == TCP_MSG_KEY::MSG_TEMPERATURE_REQUEST){ - getTemperature(); - } - if (msgID == TCP_MSG_KEY::MSG_I2C_STATS_REQUEST){ - sendI2cStats(); - } - if (msgID == TCP_MSG_KEY::MSG_I2C_SCAN_BUS){ - scanI2cBus(); - sendI2cStats(); - } - if (msgID == TCP_MSG_KEY::MSG_SPI_STATS_REQUEST){ - sendSpiStats(); - } - if (msgID == TCP_MSG_KEY::MSG_CALIB_REQUEST){ - sendCalib(); - } - if (msgID == TCP_MSG_KEY::MSG_CALIB_SAVE){ - if (calib!=nullptr) calib->writeToEeprom(); - sendCalib(); - } - if (msgID == TCP_MSG_KEY::MSG_CALIB_SET){ - std::vector calibs; - quint8 nrEntries=0; - *(tcpMessage.dStream) >> nrEntries; - for (int i=0; i> item; - calibs.push_back(item); - } - receivedCalibItems(calibs); - } - if (msgID == TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG){ - std::vector configs; - int nrEntries=0; - *(tcpMessage.dStream) >> nrEntries; - for (int i=0; i> config.gnssId >> config.resTrkCh >> config.maxTrkCh >> config.flags; - configs.push_back(config); - } - emit setGnssConfig(configs); - usleep(150000L); - emit sendPollUbxMsg(UBX_CFG_GNSS); - } - if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_TP5){ - UbxTimePulseStruct tp; - *(tcpMessage.dStream) >> tp; - emit UBXSetCfgTP5(tp); - emit sendPollUbxMsg(UBX_CFG_TP5); - return; - } - if (msgID == TCP_MSG_KEY::MSG_UBX_CFG_SAVE){ - emit UBXSaveCfg(); - emit sendPollUbxMsg(UBX_CFG_TP5); - emit sendPollUbxMsg(UBX_CFG_GNSS); - return; - } - if (msgID == TCP_MSG_KEY::MSG_QUIT_CONNECTION){ - QString closeAddress; - *(tcpMessage.dStream) >> closeAddress; - emit closeConnection(closeAddress); - } - if (msgID == TCP_MSG_KEY::MSG_DAC_EEPROM_SET){ - saveDacValuesToEeprom(); - } - if (msgID == TCP_MSG_KEY::MSG_HISTOGRAM_CLEAR){ - QString histoName; - *(tcpMessage.dStream) >> histoName; - clearHisto(histoName); - } - if (msgID == TCP_MSG_KEY::MSG_ADC_MODE_REQUEST){ - TcpMessage answer(TCP_MSG_KEY::MSG_ADC_MODE); - *(answer.dStream) << (quint8)adcSamplingMode; - emit sendTcpMessage(answer); - - } - if (msgID == TCP_MSG_KEY::MSG_ADC_MODE){ - quint8 mode=0; - *(tcpMessage.dStream) >> mode; - setAdcSamplingMode(mode); - TcpMessage answer(TCP_MSG_KEY::MSG_ADC_MODE); - *(answer.dStream) << (quint8)adcSamplingMode; - emit sendTcpMessage(answer); - } - if (msgID == TCP_MSG_KEY::MSG_LOG_INFO){ - sendLogInfo(); - } - if (msgID == TCP_MSG_KEY::MSG_RATE_SCAN) { - quint8 channel=0; - *(tcpMessage.dStream) >> channel; - startRateScan(channel); - } - if (msgID == TCP_MSG_KEY::MSG_GPIO_INHIBIT) { - bool inhibit=true; - *(tcpMessage.dStream) >> inhibit; - if (pigHandler!=nullptr) pigHandler->setInhibited(inhibit); - } -} - -void Daemon::setAdcSamplingMode(quint8 mode) { - if (mode>ADC_MODE_TRACE) return; - adcSamplingMode=mode; - if (mode==ADC_MODE_TRACE) samplingTimer.start(); - else samplingTimer.stop(); -} - -void Daemon::scanI2cBus() { - for (uint8_t addr=1; addr<0x7f; addr++) - { - bool alreadyThere = false; - for (uint8_t i=0; igetAddress()) { - alreadyThere=true; - break; - } - } - if (alreadyThere) continue; - i2cDevice* dev = new i2cDevice(addr); - if (!dev->devicePresent()) delete dev; - } -} - -void Daemon::sendLogInfo(){ - LogInfoStruct lis; - lis.logFileName=fileHandler->logFileInfo().absoluteFilePath(); - lis.dataFileName=fileHandler->dataFileInfo().absoluteFilePath(); - lis.logFileSize=fileHandler->logFileInfo().size(); - lis.dataFileSize=fileHandler->dataFileInfo().size(); - lis.status=(quint8)(fileHandler->dataFileInfo().exists() && fileHandler->logFileInfo().exists()); -// following code works only from Qt 5.10 onwards -/* - QDateTime now = QDateTime::currentDateTime(); - qint64 difftime=-now.secsTo(fileHandler->dataFileInfo().fileTime(QFileDevice::FileMetadataChangeTime)); - lis.logAge=(qint32)difftime; -*/ - lis.logAge=(qint32)fileHandler->currentLogAge(); - TcpMessage answer(TCP_MSG_KEY::MSG_LOG_INFO); - *(answer.dStream) << lis; - emit sendTcpMessage(answer); -} - -void Daemon::sendI2cStats() { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_I2C_STATS); - quint8 nrDevices=i2cDevice::getGlobalDeviceList().size(); - quint32 bytesRead = i2cDevice::getGlobalNrBytesRead(); - quint32 bytesWritten = i2cDevice::getGlobalNrBytesWritten(); - *(tcpMessage.dStream) << nrDevices << bytesRead << bytesWritten; - - for (uint8_t i=0; igetAddress(); - QString title = QString::fromStdString(i2cDevice::getGlobalDeviceList()[i]->getTitle()); - i2cDevice::getGlobalDeviceList()[i]->devicePresent(); - uint8_t status = i2cDevice::getGlobalDeviceList()[i]->getStatus(); - *(tcpMessage.dStream) << addr << title << status; - } - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendSpiStats() { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_SPI_STATS); - *(tcpMessage.dStream) << spiDevicePresent; - emit sendTcpMessage(spiDevicePresent); -} - -void Daemon::sendCalib() { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_CALIB_SET); - bool valid=calib->isValid(); - bool eepValid=calib->isEepromValid(); - quint16 nrPars = calib->getCalibList().size(); - quint64 id = calib->getSerialID(); - *(tcpMessage.dStream) << valid << eepValid << id << nrPars; - for (int i=0; igetCalibItem(i); - } - emit sendTcpMessage(tcpMessage); -} - -void Daemon::receivedCalibItems(const std::vector& newCalibs) { - for (unsigned int i=0; isetCalibItem(newCalibs[i].name, newCalibs[i]); - } -} - - -void Daemon::onGpsPropertyUpdatedGeodeticPos(const GeodeticPos& pos){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GEO_POS); - (*tcpMessage.dStream) << pos.iTOW << pos.lon << pos.lat - << pos.height << pos.hMSL << pos.hAcc - << pos.vAcc; - emit sendTcpMessage(tcpMessage); - - QString geohash=GeoHash::hashFromCoordinates(1e-7*pos.lon, 1e-7*pos.lat, 10); - - emit logParameter(LogParameter("geoLongitude", QString::number(1e-7*pos.lon,'f',7)+" deg", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("geoLatitude", QString::number(1e-7*pos.lat,'f',7)+" deg", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("geoHash", geohash+" ", LogParameter::LOG_LATEST)); - emit logParameter(LogParameter("geoHeightMSL", QString::number(1e-3*pos.hMSL,'f',2)+" m", LogParameter::LOG_AVERAGE)); - if (histoMap.find("geoHeight")!=histoMap.end()) - emit logParameter(LogParameter("meanGeoHeightMSL", QString::number(histoMap["geoHeight"].getMean(),'f',2)+" m", LogParameter::LOG_LATEST)); - emit logParameter(LogParameter("geoHorAccuracy", QString::number(1e-3*pos.hAcc,'f',2)+" m", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("geoVertAccuracy", QString::number(1e-3*pos.vAcc,'f',2)+" m", LogParameter::LOG_AVERAGE)); - - if (1e-3*pos.vAcc<100.) { - QString name="geoHeight"; - if (histoMap.find(name)!=histoMap.end()) { - checkRescaleHisto(histoMap[name], 1e-3*pos.hMSL); - histoMap[name].fill(1e-3*pos.hMSL /*, heightWeight */); - if (currentDOP.vDOP>0) { - name="weightedGeoHeight"; - double heightWeight=100./currentDOP.vDOP; - checkRescaleHisto(histoMap[name], 1e-3*pos.hMSL); - histoMap[name].fill(1e-3*pos.hMSL , heightWeight ); - } - } - } - if (1e-3*pos.hAcc<100.) { - QString name="geoLongitude"; - checkRescaleHisto(histoMap[name], 1e-7*pos.lon); - histoMap[name].fill(1e-7*pos.lon /*, heightWeight */); - name="geoLatitude"; - checkRescaleHisto(histoMap[name], 1e-7*pos.lat); - histoMap[name].fill(1e-7*pos.lat /*, heightWeight */); - } -} - -void Daemon::sendHistogram(const Histogram& hist){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_HISTOGRAM); - (*tcpMessage.dStream) << hist; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendUbxMsgRates() { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_MSG_RATE); - *(tcpMessage.dStream) << msgRateCfgs; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendDacThresh(uint8_t channel) { - if (channel > 1){ return; } - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_THRESHOLD); - *(tcpMessage.dStream) << (quint8)channel << dacThresh[(int)channel]; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) { - if (channel > 3){ return; } - - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_DAC_READBACK); - *(tcpMessage.dStream) << (quint8)channel << voltage; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { - // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) - { return item.second == gpio; } - ); - if (result != GPIO_PINMAP.end()) { - if ( result->first == TIMEPULSE) { - auto usecs = std::chrono::duration_cast(event_time.time_since_epoch()).count(); - usecs = usecs % 1000000LL; - if ( usecs > 500000L ) { - usecs -= 1000000LL; - } - if (histoMap.find("TPTimeDiff") != histoMap.end()) { - checkRescaleHisto(histoMap["TPTimeDiff"], usecs); - histoMap["TPTimeDiff"].fill((double)usecs); - } - if (verbose>2) qDebug()<<"TP time diff:"<first == EVT_XOR || result->first == EVT_AND ) { - rateCounterIntervalActualisation(); - if ( result->first == EVT_XOR ) { - xorCounts.back()++; - } else if ( result->first == EVT_AND ) { - andCounts.back()++; - } - } - if ( result->first == eventTrigger ) { - /* - auto nsecs = rateBuffer.lastInterval(gpio).count(); - if ( nsecs > 0 ) { - emit eventInterval( rateBuffer.lastInterval(gpio).count() ); - } - */ - emit sampleAdc0Event(); - } - - if ( result->first == TIME_MEAS_OUT ) { - auto start_gpio = GPIO_PINMAP.find(eventTrigger); - if ( start_gpio != GPIO_PINMAP.end() ) { - long long nsecs { 0 }; - if ( result->first != eventTrigger ) { - nsecs = rateBuffer.lastInterval( gpio, start_gpio->second ).count(); - if ( nsecs < 0 ) nsecs = rateBuffer.lastInterval( start_gpio->second, gpio ).count(); - } else { - nsecs = rateBuffer.lastInterval( gpio ).count(); - } - if ( nsecs > 0 ) { - //emit eventInterval( nsecs ); - if ( nsecs < 100000L ) { - emit eventInterval( nsecs ); - std::cout<<"trigger interval="<& item) - { return item.second==gpio; } - ); - if (result!=GPIO_PINMAP.end()) { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); - *(tcpMessage.dStream) << (GPIO_SIGNAL)result->first; - emit sendTcpMessage(tcpMessage); - } -} - -void Daemon::sendBiasVoltage(){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_VOLTAGE); - *(tcpMessage.dStream) << biasVoltage; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendBiasStatus(){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_BIAS_SWITCH); - *(tcpMessage.dStream) << biasON; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendGainSwitchStatus(){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GAIN_SWITCH); - *(tcpMessage.dStream) << gainSwitch; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendPreampStatus(uint8_t channel) { - if (channel > 1){ return; } - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PREAMP_SWITCH); - *(tcpMessage.dStream) << (quint8)channel << preampStatus [channel]; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendPolarityStatus() { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_POLARITY_SWITCH); - *(tcpMessage.dStream) << polarity1 << polarity2; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendPcaChannel(){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_PCA_SWITCH); - *(tcpMessage.dStream) << (quint8)pcaPortMask; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendEventTriggerSelection(){ - if (pigHandler==nullptr) return; - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_EVENTTRIGGER); - *(tcpMessage.dStream) << eventTrigger; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sendMqttStatus(bool connected){ - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_MQTT_STATUS); - *(tcpMessage.dStream) << connected; - if (connected != mqttConnectionStatus) { - if (connected) { - qInfo()<<"MQTT (re)connected"; - emit GpioSetState(GPIO_PINMAP[STATUS1],1); - } - else { - qWarning()<<"MQTT connection lost"; - emit GpioSetState(GPIO_PINMAP[STATUS1],0); - } - } - mqttConnectionStatus=connected; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::rateCounterIntervalActualisation(){ - if (xorCounts.isEmpty()){ - xorCounts.push_back(0); - } - if (andCounts.isEmpty()){ - andCounts.push_back(0); - } - timespec now; - timespec_get(&now, TIME_UTC); - int64_t diff = msecdiff(now,lastRateInterval); - while(diff>1000){ - xorCounts.push_back(0); - andCounts.push_back(0); - while ((quint32)xorCounts.size()>(rateBufferTime)){ - xorCounts.pop_front(); - } - while ((quint32)andCounts.size()>(rateBufferTime)){ - andCounts.pop_front(); - } - lastRateInterval.tv_sec += 1; - diff = msecdiff(now,lastRateInterval); - } -} - -void Daemon::clearRates(){ - xorCounts.clear(); - xorCounts.push_back(0); - andCounts.clear(); - andCounts.push_back(0); - xorRatePoints.clear(); - andRatePoints.clear(); -} - -qreal Daemon::getRateFromCounts(quint8 which_rate){ - rateCounterIntervalActualisation(); - QList *counts; - if (which_rate==XOR_RATE){ - counts = &xorCounts; - }else if( which_rate == AND_RATE){ - counts = &andCounts; - }else{ - return -1.0; - } - quint64 sum = 0; - for (auto count : *counts){ - sum += count; - } - timespec now; - timespec_get(&now, TIME_UTC); - qreal timeInterval = ((qreal)(1000*(counts->size()-1)))+(qreal)msecdiff(now,lastRateInterval); // in ms - qreal rate = sum/timeInterval*1000; - return (rate); -} - -void Daemon::onRateBufferReminder(){ - qreal secsSinceStart = 0.001*(qreal)msecdiff(lastRateInterval,startOfProgram); - qreal xorRate = getRateFromCounts(XOR_RATE); - qreal andRate = getRateFromCounts(AND_RATE); - QPointF xorPoint(secsSinceStart, xorRate); - QPointF andPoint(secsSinceStart, andRate); - xorRatePoints.append(xorPoint); - andRatePoints.append(andPoint); - emit logParameter(LogParameter("rateXOR", QString::number(xorRate)+" Hz", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("rateAND", QString::number(andRate)+" Hz", LogParameter::LOG_AVERAGE)); - while ((quint32)xorRatePoints.size()>rateMaxShowInterval/rateBufferInterval){ - xorRatePoints.pop_front(); - } - while ((quint32)andRatePoints.size()>rateMaxShowInterval/rateBufferInterval){ - andRatePoints.pop_front(); - } -} - -void Daemon::sendGpioRates(int number, quint8 whichRate){ - if (pigHandler==nullptr){ - return; - } - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_RATE); - QVector *ratePoints; - if (whichRate==XOR_RATE){ - ratePoints = &xorRatePoints; - }else if(whichRate==AND_RATE){ - ratePoints = &andRatePoints; - }else{ - return; - } - QVector someRates; - if (number >= ratePoints->size() || number == 0){ - number = ratePoints->size()-1; - } - if (!ratePoints->isEmpty()){ - for (int i = 0; iat(ratePoints->size()-1-i)); - } - } - *(tcpMessage.dStream) << whichRate << someRates; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::sampleAdc0Event(){ - const uint8_t channel=0; - if (adc==nullptr || adcSamplingMode==ADC_MODE_DISABLED){ - return; - } - if (adc->getStatus() & i2cDevice::MODE_UNREACHABLE) return; - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_SAMPLE); - float value = adc->readVoltage(channel); - *(tcpMessage.dStream) << (quint8)channel << value; - emit sendTcpMessage(tcpMessage); - QString name="pulseHeight"; - histoMap[name].fill(value); - emit logParameter(LogParameter("adcSamplingTime", QString::number(adc->getLastConvTime())+" ms", LogParameter::LOG_AVERAGE)); - name="adcSampleTime"; - checkRescaleHisto(histoMap[name], adc->getLastConvTime()); - histoMap[name].fill(adc->getLastConvTime()); - currentAdcSampleIndex=0; -} - -void Daemon::sampleAdc0TraceEvent(){ - const uint8_t channel=0; - if (adc==nullptr || adcSamplingMode==ADC_MODE_DISABLED){ - return; - } - if (adc->getStatus() & i2cDevice::MODE_UNREACHABLE) return; - float value = adc->readVoltage(channel); - adcSamplesBuffer.push_back(value); - if (adcSamplesBuffer.size() > MuonPi::Config::Hardware::ADC::buffer_size/*ADC_SAMPLEBUFFER_SIZE*/) adcSamplesBuffer.pop_front(); - if (currentAdcSampleIndex>=0) { - currentAdcSampleIndex++; - if (currentAdcSampleIndex >= (MuonPi::Config::Hardware::ADC::buffer_size - MuonPi::Config::Hardware::ADC::pretrigger)/*ADC_SAMPLEBUFFER_SIZE-ADC_PRETRIGGER*/) { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_TRACE); - *(tcpMessage.dStream) << (quint16) adcSamplesBuffer.size(); - for (int i=0; igetLastConvTime())+" ms", LogParameter::LOG_AVERAGE)); - checkRescaleHisto(histoMap["adcSampleTime"], adc->getLastConvTime()); - histoMap["adcSampleTime"].fill(adc->getLastConvTime()); -} - -void Daemon::sampleAdcEvent(uint8_t channel){ - if (adc==nullptr || adcSamplingMode==ADC_MODE_DISABLED){ - return; - } - if (adc->getStatus() & i2cDevice::MODE_UNREACHABLE) return; - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_ADC_SAMPLE); - float value = adc->readVoltage(channel); - *(tcpMessage.dStream) << (quint8)channel << value; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::getTemperature(){ - if (lm75==nullptr){ - return; - } - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_TEMPERATURE); - if (lm75->getStatus() & i2cDevice::MODE_UNREACHABLE) return; - float value = lm75->getTemperature(); - *(tcpMessage.dStream) << value; - emit sendTcpMessage(tcpMessage); -} - -void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) { - if (pigHandler==nullptr) return; - auto it=GPIO_PINMAP.find(signal); - if (it==GPIO_PINMAP.end()) { - return; - } - - if ( verbose > 0 ){ - qInfo() << "changed event selection to signal" << GPIO_SIGNAL_MAP[signal].name; - } - emit GpioRegisterForCallback( it->second, PigpiodHandler::EventEdge::RisingEdge ); - eventTrigger = signal; - emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); -} - -// ALL FUNCTIONS ABOUT SETTINGS FOR THE I2C-DEVICES (DAC, ADC, PCA...) -void Daemon::setPcaChannel(uint8_t channel) { - if (!pca || !pca->devicePresent()) { - return; - } - if (channel > ((HW_VERSION==1)?3:7)) { - qWarning() << "invalid PCA channel selection: ch" <<(int)channel<<"...ignoring"; - return; - } - if (verbose > 0){ - qInfo() << "changed pcaPortMask to " << channel; - } - pcaPortMask = channel; - pca->setOutputState(channel); - emit logParameter(LogParameter("ubxInputSwitch", "0x"+QString::number(pcaPortMask,16), LogParameter::LOG_EVERY)); - //sendPcaChannel(); -} - -void Daemon::setBiasVoltage(float voltage) { - biasVoltage = voltage; - if (verbose > 0){ - qInfo() << "change biasVoltage to " << voltage; - } - if (dac && dac->devicePresent()) { - dac->setVoltage(DAC_BIAS, voltage); - emit logParameter(LogParameter("biasDAC", QString::number(voltage)+" V", LogParameter::LOG_EVERY)); - } - clearRates(); - //sendBiasVoltage(); -} - -void Daemon::setBiasStatus(bool status){ - biasON = status; - if (verbose > 0){ - qInfo() << "change biasStatus to " << status; - } - //emit GpioSetState(UBIAS_EN, status); - - if (status) { - emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION==1)?1:0); - } - else { - emit GpioSetState(GPIO_PINMAP[UBIAS_EN], (HW_VERSION==1)?0:1); - } - emit logParameter(LogParameter("biasSwitch", QString::number(status), LogParameter::LOG_EVERY)); - clearRates(); - //sendBiasStatus(); -} - -void Daemon::setDacThresh(uint8_t channel, float threshold) { - if (threshold < 0 || channel > 3) { return; } - if (channel==2 || channel==3) { - if (dac->devicePresent()) { - dac->setVoltage(channel, threshold); - } - return; - } - if (threshold > 4.095){ - threshold = 4.095; - } - if (verbose > 0){ - qInfo() << "change dacThresh " << channel << " to " << threshold; - } - dacThresh[channel] = threshold; - clearRates(); - if (dac->devicePresent()) { - dac->setVoltage(channel, threshold); - emit logParameter(LogParameter("thresh"+QString::number(channel+1), QString::number(dacThresh[channel])+" V", LogParameter::LOG_EVERY)); - } - //sendDacThresh(channel); -} - -void Daemon::saveDacValuesToEeprom(){ - for (int i=0; i<4; i++) { - MCP4728::DacChannel dacChannel; - dac->readChannel(i, dacChannel); - dacChannel.eeprom=true; - dac->writeChannel(i, dacChannel); - } -} - -bool Daemon::readEeprom() -{ - if (eep==nullptr) return false; - if (eep->devicePresent()) { - if (verbose>2) cout<<"eep device is present."<readBytes(0,n,buf)==n); - cout<<"*** EEPROM content ***"<& ubxMsgRates){ - for (QMap::iterator it = ubxMsgRates.begin(); it != ubxMsgRates.end(); it++) { - emit UBXSetCfgMsgRate(it.key(),1,it.value()); - emit sendPollUbxMsgRate(it.key()); - waitingForAppliedMsgRate++; - } -} - -// ALL FUNCTIONS ABOUT UBLOX GPS MODULE -void Daemon::configGps() { - // set up ubx as only outPortProtocol - //emit UBXSetCfgPrt(1,1); // enables on UART port (1) only the UBX protocol - emit UBXSetCfgPrt(1, PROTO_UBX); - - // set dynamic model: Stationary - emit UBXSetDynModel(2); - - emit UBXSetAopCfg(true); - - emit sendPollUbxMsg(UBX_MON_VER); - - // deactivate all NMEA messages: (port 6 means ALL ports) - // not needed because of deactivation of all NMEA messages with "UBXSetCfgPrt" -// msgRateCfgs.insert(UBX_NMEA_DTM,0); -// // msgRateCfgs.insert(UBX_NMEA_GBQ,0); -// msgRateCfgs.insert(UBX_NMEA_GBS,0); -// msgRateCfgs.insert(UBX_NMEA_GGA,0); -// msgRateCfgs.insert(UBX_NMEA_GLL,0); -// // msgRateCfgs.insert(UBX_NMEA_GLQ,0); -// // msgRateCfgs.insert(UBX_NMEA_GNQ,0); -// msgRateCfgs.insert(UBX_NMEA_GNS,0); -// // msgRateCfgs.insert(UBX_NMEA_GPQ,0); -// msgRateCfgs.insert(UBX_NMEA_GRS,0); -// msgRateCfgs.insert(UBX_NMEA_GSA,0); -// msgRateCfgs.insert(UBX_NMEA_GST,0); -// msgRateCfgs.insert(UBX_NMEA_GSV,0); -// msgRateCfgs.insert(UBX_NMEA_RMC,0); -// // msgRateCfgs.insert(UBX_NMEA_TXT,0); -// msgRateCfgs.insert(UBX_NMEA_VLW,0); -// msgRateCfgs.insert(UBX_NMEA_VTG,0); -// msgRateCfgs.insert(UBX_NMEA_ZDA,0); -// msgRateCfgs.insert(UBX_NMEA_POSITION,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_DTM,6,0); -// // has no output msg UBX_NMEA_GBQ -// emit UBXSetCfgMsgRate(UBX_NMEA_GBS,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_GGA,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_GLL,6,0); -// // has no output msg UBX_NMEA_GLQ -// // has no output msg UBX_NMEA_GNQ -// emit UBXSetCfgMsgRate(UBX_NMEA_GNS,6,0); -// // has no output msg UBX_NMEA_GPQ -// emit UBXSetCfgMsgRate(UBX_NMEA_GRS,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_GSA,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_GST,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_GSV,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_RMC,6,0); -// // is not configured through UBX_CFG_MSG but through UBX-CFG-INF!!! (UBX_NMEA_TXT) -// //emit UBXSetCfgMsgRate(UBX_NMEA_VLW,6,0); don't know why this does not work, probably not supported anymore -// emit UBXSetCfgMsgRate(UBX_NMEA_VTG,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_ZDA,6,0); -// emit UBXSetCfgMsgRate(UBX_NMEA_POSITION,6,0); - - // set protocol configuration for ports - // msgRateCfgs: -1 means unknown, 0 means off, some positive value means update time - int measrate = 10; - // msgRateCfgs.insert(UBX_CFG_RATE, measrate); - // msgRateCfgs.insert(UBX_TIM_TM2, 1); - // msgRateCfgs.insert(UBX_TIM_TP, 51); - // msgRateCfgs.insert(UBX_NAV_TIMEUTC, 20); - // msgRateCfgs.insert(UBX_MON_HW, 47); - // msgRateCfgs.insert(UBX_NAV_SAT, 59); - // msgRateCfgs.insert(UBX_NAV_TIMEGPS, 61); - // msgRateCfgs.insert(UBX_NAV_SOL, 67); - // msgRateCfgs.insert(UBX_NAV_STATUS, 71); - // msgRateCfgs.insert(UBX_NAV_CLOCK, 89); - // msgRateCfgs.insert(UBX_MON_TXBUF, 97); - // msgRateCfgs.insert(UBX_NAV_SBAS, 255); - // msgRateCfgs.insert(UBX_NAV_DOP, 101); - // msgRateCfgs.insert(UBX_NAV_SVINFO, 49); - emit UBXSetCfgRate(1000/measrate, 1); // UBX_RATE - - //emit sendPollUbxMsg(UBX_MON_VER); - emit UBXSetCfgMsgRate(UBX_TIM_TM2, 1, 1); // TIM-TM2 - emit UBXSetCfgMsgRate(UBX_TIM_TP, 1, 0); // TIM-TP - emit UBXSetCfgMsgRate(UBX_NAV_TIMEUTC, 1, 131); // NAV-TIMEUTC - emit UBXSetCfgMsgRate(UBX_MON_HW, 1, 47); // MON-HW - emit UBXSetCfgMsgRate(UBX_MON_HW2, 1, 49); // MON-HW - emit UBXSetCfgMsgRate(UBX_NAV_POSLLH, 1, 127); // MON-POSLLH - // probably also configured with UBX-CFG-INFO... - emit UBXSetCfgMsgRate(UBX_NAV_TIMEGPS, 1, 0); // NAV-TIMEGPS - emit UBXSetCfgMsgRate(UBX_NAV_SOL, 1, 0); // NAV-SOL - emit UBXSetCfgMsgRate(UBX_NAV_STATUS, 1, 71); // NAV-STATUS - emit UBXSetCfgMsgRate(UBX_NAV_CLOCK, 1, 189); // NAV-CLOCK - emit UBXSetCfgMsgRate(UBX_MON_RXBUF, 1, 53); // MON-TXBUF - emit UBXSetCfgMsgRate(UBX_MON_TXBUF, 1, 51); // MON-TXBUF - emit UBXSetCfgMsgRate(UBX_NAV_SBAS, 1, 0); // NAV-SBAS - emit UBXSetCfgMsgRate(UBX_NAV_DOP, 1, 254); // NAV-DOP - // this poll is for checking the port cfg (which protocols are enabled etc.) - emit sendPollUbxMsg(UBX_CFG_PRT); - emit sendPollUbxMsg(UBX_MON_VER); - emit sendPollUbxMsg(UBX_MON_VER); - emit sendPollUbxMsg(UBX_MON_VER); - emit sendPollUbxMsg(UBX_CFG_GNSS); - //emit UBXSetMinCNO(5); - emit sendPollUbxMsg(UBX_CFG_NAVX5); - emit sendPollUbxMsg(UBX_CFG_ANT); - emit sendPollUbxMsg(UBX_CFG_TP5); - - configGpsForVersion(); -} - -void Daemon::configGpsForVersion() { - if (QtSerialUblox::getProtVersion()<=0.1) return; - if (QtSerialUblox::getProtVersion()>15.0) { - if (std::find(allMsgCfgID.begin(), allMsgCfgID.end(), UBX_NAV_SAT)==allMsgCfgID.end()) { - allMsgCfgID.push_back(UBX_NAV_SAT); - } - emit UBXSetCfgMsgRate(UBX_NAV_SAT, 1, 69); // NAV-SAT - emit UBXSetCfgMsgRate(UBX_NAV_SVINFO, 1, 0); - } else emit UBXSetCfgMsgRate(UBX_NAV_SVINFO, 1, 69); // NAV-SVINFO - //cout<<"prot Version: "<& sats, - std::chrono::duration lastUpdated) { - vector visibleSats = sats; - std::sort(visibleSats.begin(), visibleSats.end(), GnssSatellite::sortByCnr); - while (visibleSats.size() > 0 && visibleSats.back().getCnr() == 0) visibleSats.pop_back(); - - if (verbose > 3) { - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(lastUpdated) - << "Nr of satellites: " << visibleSats.size() <<" (out of "<< sats.size() << endl; - // read nrSats property without evaluation to prevent separate display of this property - // in the common message poll below - GnssSatellite::PrintHeader(true); - for (unsigned int i = 0; i < sats.size(); i++) { - sats[i].Print(i, false); - } - } - int N=sats.size(); - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GNSS_SATS); - (*tcpMessage.dStream) << N; - for (int i=0; i(visibleSats.size()) }; - - propertyMap["nrSats"]=Property("nrSats",N); - propertyMap["visSats"]=Property("visSats",visibleSats.size()); - - int usedSats=0, maxCnr=0; - if (visibleSats.size()) { - for (auto sat : visibleSats){ - if (sat.fUsed) usedSats++; - if (sat.fCnr>maxCnr) maxCnr=sat.fCnr; - } - } - propertyMap["usedSats"]=Property("usedSats",usedSats); - propertyMap["maxCNR"]=Property("maxCNR",maxCnr); - //qDebug()<< "propertyMap.size()="<& gnssConfigs) { - if (verbose > 3) { - // put some verbose output here - } - int N=gnssConfigs.size(); - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_GNSS_CONFIG); - (*tcpMessage.dStream) << (int)numTrkCh << N; - for (int i=0; i 3) { - // put some verbose output here - } - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_CFG_TP5); - (*tcpMessage.dStream) << tp; - emit sendTcpMessage(tcpMessage); - // check here if UTC is selected as time source - // this should probably be implemented somewhere else, maybe at ublox init - // however, for the timestamping to work correctly, setting the time grid to UTC is mandatory! - int timeGrid = (tp.flags & UbxTimePulseStruct::GRID_UTC_GPS)>>7; - if (timeGrid != 0 && forceUtcSetCounter++ < 3) { - UbxTimePulseStruct newTp = tp; - newTp.flags &= ~((uint32_t)UbxTimePulseStruct::GRID_UTC_GPS); - emit UBXSetCfgTP5(newTp); - qDebug() << "forced time grid to UTC"; - emit sendPollUbxMsg(UBX_CFG_TP5); - } -} - -void Daemon::onUBXReceivedTxBuf(uint8_t txUsage, uint8_t txPeakUsage) { - TcpMessage* tcpMessage; - if (verbose>3) { - qDebug() << "TX buf usage: " << (int)txUsage << " %"; - qDebug() << "TX buf peak usage: " << (int)txPeakUsage << " %"; - } - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_TXBUF); - *(tcpMessage->dStream) << (quint8)txUsage << (quint8)txPeakUsage; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("TXBufUsage", QString::number(txUsage)+" %", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("maxTXBufUsage", QString::number(txPeakUsage)+" %", LogParameter::LOG_LATEST)); -} - -void Daemon::onUBXReceivedRxBuf(uint8_t rxUsage, uint8_t rxPeakUsage) { - TcpMessage* tcpMessage; - if (verbose>3) { - qDebug() << "RX buf usage: " << (int)rxUsage << " %"; - qDebug() << "RX buf peak usage: " << (int)rxPeakUsage << " %"; - } - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_RXBUF); - *(tcpMessage->dStream) << (quint8)rxUsage << (quint8)rxPeakUsage; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("RXBufUsage", QString::number(rxUsage)+" %", LogParameter::LOG_AVERAGE)); - emit logParameter(LogParameter("maxRXBufUsage", QString::number(rxPeakUsage)+" %", LogParameter::LOG_LATEST)); -} - -void Daemon::gpsPropertyUpdatedUint8(uint8_t data, std::chrono::duration updateAge, - char propertyName) { - TcpMessage* tcpMessage; - switch (propertyName) { - case 's': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "Nr of available satellites: " << (int)data << endl; - break; - case 'e': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "quant error: " << (int)data << " ps" << endl; - break; - /* - case 'b': - if (verbose>2) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "TX buf usage: " << (int)data << " %" << endl; - tcpMessage = new TcpMessage(gpsTxBufSig); - *(tcpMessage->dStream) << (quint8)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("TXBufUsage", QString::number(data)+" %", LogParameter::LOG_LATEST)); - break; - case 'p': - if (verbose>2) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "TX buf peak usage: " << (int)data << " %" << endl; - tcpMessage = new TcpMessage(gpsTxBufPeakSig); - *(tcpMessage->dStream) << (quint8)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("maxTXBufUsage", QString::number(data)+" %", LogParameter::LOG_LATEST)); - break; - */ - case 'f': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "Fix value: " << (int)data << endl; - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_FIXSTATUS); - *(tcpMessage->dStream) << (quint8)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("fixStatus", QString::number(data), LogParameter::LOG_LATEST)); - emit logParameter(LogParameter("fixStatusString", FIX_TYPE_STRINGS[data], LogParameter::LOG_LATEST)); - fixStatus=QVariant(data); - propertyMap["fixStatus"]=Property("fixStatus",FIX_TYPE_STRINGS[data]); - break; - default: - break; - } -} - -void Daemon::gpsPropertyUpdatedUint32(uint32_t data, chrono::duration updateAge, - char propertyName) { - TcpMessage* tcpMessage; - switch (propertyName) { - case 'a': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "time accuracy: " << data << " ns" << endl; - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_TIME_ACCURACY); - *(tcpMessage->dStream) << (quint32)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("timeAccuracy", QString::number(data)+" ns", LogParameter::LOG_AVERAGE)); - break; - case 'f': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "frequency accuracy: " << data << " ps/s" << endl; - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_FREQ_ACCURACY); - *(tcpMessage->dStream) << (quint32)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("freqAccuracy", QString::number(data)+" ps/s", LogParameter::LOG_AVERAGE)); - break; - case 'u': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "Ublox uptime: " << data << " s" << endl; - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_UPTIME); - *(tcpMessage->dStream) << (quint32)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - emit logParameter(LogParameter("ubloxUptime", QString::number(data)+" s", LogParameter::LOG_LATEST)); - break; - case 'c': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "rising edge counter: " << data << endl; - propertyMap["events"]=Property("events",(quint16)data); - tcpMessage = new TcpMessage(TCP_MSG_KEY::MSG_UBX_EVENTCOUNTER); - *(tcpMessage->dStream) << (quint32)data; - emit sendTcpMessage(*tcpMessage); - delete tcpMessage; - break; - default: - break; - } -} - -void Daemon::gpsPropertyUpdatedInt32(int32_t data, std::chrono::duration updateAge, - char propertyName) { - switch (propertyName) { - case 'd': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "clock drift: " << data << " ns/s" << endl; - logParameter(LogParameter("clockDrift", QString::number(data)+" ns/s", LogParameter::LOG_AVERAGE)); - propertyMap["clkDrift"]=Property("clkDrift",(qint32)data); - break; - case 'b': - if (verbose>3) - cout << std::chrono::system_clock::now() - - std::chrono::duration_cast(updateAge) - << "clock bias: " << data << " ns" << endl; - emit logParameter(LogParameter("clockBias", QString::number(data)+" ns", LogParameter::LOG_AVERAGE)); - propertyMap["clkBias"]=Property("clkBias",(qint32)data); - break; - default: - break; - } -} - - -void Daemon::UBXReceivedVersion(const QString& swString, const QString& hwString, const QString& protString) -{ - static bool initialVersionInfo = true; - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_UBX_VERSION); - (*tcpMessage.dStream) << swString << hwString << protString; - emit sendTcpMessage(tcpMessage); - logParameter(LogParameter("UBX_SW_Version", swString, LogParameter::LOG_ONCE)); - logParameter(LogParameter("UBX_HW_Version", hwString, LogParameter::LOG_ONCE)); - logParameter(LogParameter("UBX_Prot_Version", protString, LogParameter::LOG_ONCE)); - if (initialVersionInfo) { - configGpsForVersion(); - qInfo()<<"Ublox version: "<3) cout << "established connection with " << remotePeerAddress << ":" << remotePeerPort << endl; - - emit sendPollUbxMsg(UBX_MON_VER); - emit sendPollUbxMsg(UBX_CFG_GNSS); - emit sendPollUbxMsg(UBX_CFG_NAV5); - emit sendPollUbxMsg(UBX_CFG_TP5); - emit sendPollUbxMsg(UBX_CFG_NAVX5); - - sendBiasStatus(); - sendBiasVoltage(); - sendDacThresh(0); - sendDacThresh(1); - sendPcaChannel(); - sendEventTriggerSelection(); -} - -void Daemon::onStoppedConnection(QString remotePeerAddress, quint16 remotePeerPort, QString /*localAddress*/, quint16 /*localPort*/, - quint32 timeoutTime, quint32 connectionDuration) { - if (verbose>3) { - qDebug() << "stopped connection with " << remotePeerAddress << ":" << remotePeerPort << endl; - qDebug() << "connection timeout at " << timeoutTime << " connection lasted " << connectionDuration << "s" << endl; - } -} - -void Daemon::displayError(QString message) -{ - qDebug() << "Daemon: " << message; -} - -void Daemon::displaySocketError(int socketError, QString message) -{ - switch (socketError) { - case QAbstractSocket::HostNotFoundError: - qCritical() << tr("The host was not found. Please check the host and port settings."); - break; - case QAbstractSocket::ConnectionRefusedError: - qCritical() << tr("The connection was refused by the peer. " - "Make sure the server is running, " - "and check that the host name and port " - "settings are correct."); - break; - default: - qCritical() << tr("The following error occurred: %1.").arg(message); - } - flush(cout); -} - -void Daemon::delay(int millisecondsWait) -{ - QEventLoop loop; - QTimer t; - t.connect(&t, &QTimer::timeout, &loop, &QEventLoop::quit); - t.start(millisecondsWait); - loop.exec(); -} - -void Daemon::printTimestamp() -{ - std::chrono::time_point timestamp = std::chrono::system_clock::now(); - std::chrono::microseconds mus = std::chrono::duration_cast(timestamp.time_since_epoch()); - std::chrono::seconds secs = std::chrono::duration_cast(mus); - std::chrono::microseconds subs = mus - secs; - - - // t1 = std::chrono::system_clock::now(); - // t2 = std::chrono::duration_cast(t1); - //double subs=timestamp-(long int)timestamp; - cout << secs.count() << "." << setw(6) << setfill('0') << subs.count() << " " << setfill(' '); -} - -// some signal handling stuff -void Daemon::hupSignalHandler(int) -{ - char a = 1; - ::write(sighupFd[0], &a, sizeof(a)); -} - -void Daemon::termSignalHandler(int) -{ - char a = 1; - ::write(sigtermFd[0], &a, sizeof(a)); -} -void Daemon::intSignalHandler(int) { - char a = 1; - ::write(sigintFd[0], &a, sizeof(a)); -} - -void Daemon::aquireMonitoringParameters() -{ - if (lm75 && lm75->devicePresent()) emit logParameter(LogParameter("temperature", QString::number(lm75->getTemperature())+" degC", LogParameter::LOG_AVERAGE)); - - double v1=0.,v2=0.; - if (adc && (!(adc->getStatus() & i2cDevice::MODE_UNREACHABLE)) && (adc->getStatus() & (i2cDevice::MODE_NORMAL | i2cDevice::MODE_FORCE))) { - v1=adc->readVoltage(2); - v2=adc->readVoltage(3); - if (calib && calib->getCalibItem("VDIV").name=="VDIV") { - CalibStruct vdivItem=calib->getCalibItem("VDIV"); - std::istringstream istr(vdivItem.value); - double vdiv; - istr >> vdiv; - vdiv/=100.; - logParameter(LogParameter("calib_vdiv", QString::number(vdiv), LogParameter::LOG_ONCE)); -// istr=std::istringstream(calib->getCalibItem("RSENSE").value); - istr.clear(); - istr.str(calib->getCalibItem("RSENSE").value); - double rsense; - istr >> rsense; - if (verbose>2){ - qDebug()<<"rsense:"<getCalibItem("RSENSE").value)<<" ("<getCalibItem("CALIB_FLAGS"); - int calFlags=0; -// istr=std::istringstream(flagItem.value); - - istr.clear(); - istr.str(flagItem.value); - istr >> calFlags; - if (verbose>2){ - qDebug()<<"cal flags:"<getCalibItem("COEFF2").value); - istr >> ioffs; - logParameter(LogParameter("calib_coeff2", QString::number(ioffs), LogParameter::LOG_ONCE)); - istr.clear(); - istr.str(calib->getCalibItem("COEFF3").value); - istr >> islope; - logParameter(LogParameter("calib_coeff3", QString::number(islope), LogParameter::LOG_ONCE)); - icorr = ubias*islope+ioffs; - } - double ibias = usense/rsense-icorr; - checkRescaleHisto(histoMap["Bias Current"], ibias); - histoMap["Bias Current"].fill(ibias); - logParameter(LogParameter("ibias", QString::number(ibias)+" uA", LogParameter::LOG_AVERAGE)); - - } else { - logParameter(LogParameter("vadc3", QString::number(v1)+" V", LogParameter::LOG_AVERAGE)); - logParameter(LogParameter("vadc4", QString::number(v2)+" V", LogParameter::LOG_AVERAGE)); - } - } -} - -void Daemon::onLogParameterPolled(){ - // connect to the regular log timer signal to log several non-regularly polled parameters - /* - double xorRate = 0.0; - if (!xorRatePoints.isEmpty()){ - xorRate = xorRatePoints.back().y(); - } - logParameter(LogParameter("rateXOR", QString::number(xorRate)+" Hz")); - double andRate = 0.0; - if (!andRatePoints.isEmpty()){ - andRate = andRatePoints.back().y(); - } - logParameter(LogParameter("rateAND", QString::number(andRate)+" Hz")); - */ - emit logParameter(LogParameter("biasSwitch", QString::number(biasON), LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("preampSwitch1", QString::number((int)preampStatus[0]), LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("preampSwitch2", QString::number((int)preampStatus[1]), LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("gainSwitch", QString::number((int)gainSwitch), LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("polaritySwitch1", QString::number((int)polarity1), LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("polaritySwitch2", QString::number((int)polarity2), LogParameter::LOG_ON_CHANGE)); -// if (lm75 && lm75->devicePresent()) emit logParameter(LogParameter("temperature", QString::number(lm75->getTemperature())+" degC", LogParameter::LOG_AVERAGE)); - - if (dac && dac->devicePresent()) { - emit logParameter(LogParameter("thresh1", QString::number(dacThresh[0])+" V", LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("thresh2", QString::number(dacThresh[1])+" V", LogParameter::LOG_ON_CHANGE)); - emit logParameter(LogParameter("biasDAC", QString::number(biasVoltage)+" V", LogParameter::LOG_ON_CHANGE)); - } - - if (pca && pca->devicePresent()) emit logParameter(LogParameter("ubxInputSwitch", "0x"+QString::number(pcaPortMask,16), LogParameter::LOG_ON_CHANGE)); - if (pigHandler!=nullptr) emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)eventTrigger,16), LogParameter::LOG_ON_CHANGE)); - //logBiasValues(); - if (adc && !(adc->getStatus() & i2cDevice::MODE_UNREACHABLE)) { -/* - emit logParameter(LogParameter("adcSamplingTime", QString::number(adc->getLastConvTime())+" ms", LogParameter::LOG_ON_CHANGE)); - checkRescaleHisto(adcSampleTimeHisto, adc->getLastConvTime()); - adcSampleTimeHisto.fill(adc->getLastConvTime()); -*/ -// sendHistogram(histoMap["adcSampleTime"]); -// sendHistogram(histoMap["pulseHeight"]); - } -/* - sendHistogram(ubxTimeLengthHisto); - sendHistogram(eventIntervalHisto); - sendHistogram(eventIntervalShortHisto); - sendHistogram(ubxTimeIntervalHisto); - sendHistogram(tpTimeDiffHisto); - sendHistogram(tdc7200Histo); -*/ - - for (const auto &hist : histoMap) { - sendHistogram(hist); - } - - sendLogInfo(); - if (verbose>2) - { - qDebug() << "current data file: " << fileHandler->dataFileInfo().absoluteFilePath(); - qDebug() << " file size: " << fileHandler->dataFileInfo().size()/(1024*1024) << "MiB"; - } - -// Since Linux 2.3.23 (i386) and Linux 2.3.48 (all architectures) the -// structure is: -// -// struct sysinfo { -// long uptime; /* Seconds since boot */ -// unsigned long loads[3]; /* 1, 5, and 15 minute load averages */ -// unsigned long totalram; /* Total usable main memory size */ -// unsigned long freeram; /* Available memory size */ -// unsigned long sharedram; /* Amount of shared memory */ -// unsigned long bufferram; /* Memory used by buffers */ -// unsigned long totalswap; /* Total swap space size */ -// unsigned long freeswap; /* Swap space still available */ -// unsigned short procs; /* Number of current processes */ -// unsigned long totalhigh; /* Total high memory size */ -// unsigned long freehigh; /* Available high memory size */ -// unsigned int mem_unit; /* Memory unit size in bytes */ -// char _f[20-2*sizeof(long)-sizeof(int)]; -// /* Padding to 64 bytes */ -// }; -// -// In the above structure, sizes of the memory and swap fields are given -// as multiples of mem_unit bytes. - - struct sysinfo info; - memset(&info, 0, sizeof info); - int err=sysinfo(&info); - if (!err) { - double f_load = 1.0 / (1 << SI_LOAD_SHIFT); - if (verbose>2) { - qDebug()<<"*** Sysinfo Stats ***"; - qDebug()<<"nr of cpus : "< 2 ) { - qDebug() << "GPIO Rate Summary:"; - for (auto signalIt=GPIO_PINMAP.begin(); signalIt!=GPIO_PINMAP.end(); signalIt++) { - const GPIO_SIGNAL signalId=signalIt->first; - if (GPIO_SIGNAL_MAP[signalId].direction == DIR_IN ) { - qDebug()<second - <<"rate:"<second )<<"Hz" - <<"deadtime"<second ).count()<<"us"; - } - } - } - -// updateOledDisplay(); -} - -/* -void Daemon::onUBXReceivedTimeTM2(timespec rising, timespec falling, uint32_t accEst, bool valid, uint8_t timeBase, bool utcAvailable) -{ - long double dts=(falling.tv_sec-rising.tv_sec)*1e9; - dts+=(falling.tv_nsec-rising.tv_nsec); - if (dts>0.) { - checkRescaleHisto(histoMap["UbxEventLength"], dts); - histoMap["UbxEventLength"].fill(dts); - } - long double interval=(rising.tv_sec-lastTimestamp.tv_sec)*1e9; - interval+=(rising.tv_nsec-lastTimestamp.tv_nsec); - histoMap["UbxEventInterval"].fill(1e-6*interval); - lastTimestamp=rising; -} -*/ - -void Daemon::onUBXReceivedTimeTM2(const UbxTimeMarkStruct& tm) { - if (!tm.risingValid && !tm.fallingValid) { - qDebug()<<"Daemon::onUBXReceivedTimeTM2(const UbxTimeMarkStruct&): detected invalid time mark message; no rising or falling edge data"; - return; - } - static UbxTimeMarkStruct lastTimeMark { }; - //static int64_t lastPulseLength = 0; - - long double dts=(tm.falling.tv_sec-tm.rising.tv_sec)*1.0e9L; - dts+=(tm.falling.tv_nsec-tm.rising.tv_nsec); - if ((dts > 0.0L) && tm.fallingValid) { - checkRescaleHisto(histoMap["UbxEventLength"], static_cast(dts)); - histoMap["UbxEventLength"].fill(static_cast(dts)); - } - long double interval=(tm.rising.tv_sec-lastTimeMark.rising.tv_sec)*1.0e9L; - interval+=(tm.rising.tv_nsec-lastTimeMark.rising.tv_nsec); - histoMap["UbxEventInterval"].fill(static_cast(1.0e-6L * interval)); - uint16_t diffCount=tm.evtCounter-lastTimeMark.evtCounter; - emit timeMarkIntervalCountUpdate(diffCount, static_cast(interval * 1.0e-9L)); - lastTimeMark=tm; - - // output is: rising falling timeAcc valid timeBase utcAvailable - std::stringstream tempStream; - tempStream << tm.rising << tm.falling << tm.accuracy_ns << " " << tm.evtCounter << " " - << static_cast(tm.valid) << " " << static_cast(tm.timeBase) << " " - << static_cast(tm.utcAvailable); - emit eventMessage(QString::fromStdString(tempStream.str())); - - if (!tm.risingValid || !tm.fallingValid) { - qDebug() << "detected timemark message with reconstructed edge time ("<devicePresent()) return; - oled->clearDisplay(); - oled->setCursor(0,2); - oled->print("*Cosmic Shower Det.*\n"); -// oled->printf("rate (XOR) %4.2f 1/s\n", getRateFromCounts(XOR_RATE)); -// oled->printf("rate (AND) %4.2f 1/s\n", getRateFromCounts(AND_RATE)); - oled->printf("Rates %4.1f %4.1f /s\n", getRateFromCounts(AND_RATE), getRateFromCounts(XOR_RATE)); -// oled->printf("temp %4.2f %cC\n", lm75->lastTemperatureValue(), DEGREE_CHARCODE); - oled->printf("temp %4.2f %cC\n", lm75->getTemperature(), DEGREE_CHARCODE); - oled->printf("%d(%d) Sats ", nrVisibleSats().toInt(), nrSats().toInt(), DEGREE_CHARCODE); - oled->printf("%s\n", FIX_TYPE_STRINGS[fixStatus().toInt()].toStdString().c_str()); - oled->display(); -} -/* -void Daemon::startRateScan(uint8_t channel) { - if (!dac->devicePresent()) return; - // save all the settings which will be altered during the scan - RateScanInfo *scanInfo = new RateScanInfo; - scanInfo->origPcaMask = pcaPortMask; - scanInfo->origEventTrigger = eventTrigger; - setPcaChannel((channel==0)?MUX_DISC1:MUX_DISC2); - setEventTriggerSelection(EXT_TRIGGER); - pigHandler->setInhibited(true); - - quint16 counterStart=propertyMap["events"]().toUInt(); - scanInfo->lastEvtCounter=counterStart; - scanInfo->minThr=0.002; - scanInfo->maxThr=0.1; - scanInfo->currentThr=scanInfo->minThr; - scanInfo->thrIncrement=0.0005; - scanInfo->thrChannel=channel; - scanInfo->nrLoops=(RATE_SCAN_ITERATIONS>0)?RATE_SCAN_ITERATIONS:1; - scanInfo->currentLoop=0; - dac->setVoltage(channel, scanInfo->currentThr); -// usleep(10000UL); - QTimer::singleShot(RATE_SCAN_TIME_INTERVAL_MS, [this,scanInfo](){ - this->doRateScanIteration(scanInfo); - } ); -} -*/ - -void Daemon::startRateScan(uint8_t channel) { - if (!dac->devicePresent() || channel>1) return; - // save all the settings which will be altered during the scan -/* - RateScan *scan = new RateScan; - scan->origPcaMask = pcaPortMask; - scan->origEventTrigger = eventTrigger; - scan->origScanPar=dacThresh[channel]; - setPcaChannel((channel==0)?MUX_DISC1:MUX_DISC2); - setEventTriggerSelection(EXT_TRIGGER); - pigHandler->setInhibited(true); - - quint16 counterStart=propertyMap["events"]().toUInt(); - scan->lastEvtCounter=counterStart; - scan->minScanPar=0.002; - scan->maxScanPar=0.1; - scan->currentScanPar=scan->minScanPar; - scan->scanParIncrement=0.0005; - scanInfo->nrLoops=(RATE_SCAN_ITERATIONS>0)?RATE_SCAN_ITERATIONS:1; - scanInfo->currentLoop=0; - dac->setVoltage(channel, scan->currentScanPar); -// usleep(10000UL); - QTimer::singleShot(RATE_SCAN_TIME_INTERVAL_MS, [this,scanInfo](){ - this->doRateScanIteration(scanInfo); - } ); -*/ -} - -void Daemon::doRateScanIteration(RateScanInfo* info) { - uint currCounter = propertyMap["events"]().toUInt(); - uint diffCount = currCounter-info->lastEvtCounter; - info->lastEvtCounter = static_cast(currCounter); - - float thr=info->currentThr+info->thrIncrement; - double rate = diffCount * 1000.0 / MuonPi::Config::Hardware::RateScan::interval/*RATE_SCAN_TIME_INTERVAL_MS*/; -// qDebug() << "thr"<<(int)info->thrChannel<<"="<currentThr<<": "<currentThr<<" "<maxThr) { - // initiate next scan step - dac->setVoltage(info->thrChannel, thr); -// usleep(10000UL); - info->currentThr=thr; - QTimer::singleShot(MuonPi::Config::Hardware::RateScan::interval/*RATE_SCAN_TIME_INTERVAL_MS*/, [this,info](){ - this->doRateScanIteration(info); - } ); - } else { - // scan is done, restore the original settings now - setDacThresh(0, dacThresh[0]); - setDacThresh(1, dacThresh[1]); - setPcaChannel(info->origPcaMask); - setEventTriggerSelection(info->origEventTrigger); - pigHandler->setInhibited(false); - delete info; - } -} - diff --git a/source/daemon/src/dtoa.c b/source/daemon/src/dtoa.c deleted file mode 100644 index afe7553a..00000000 --- a/source/daemon/src/dtoa.c +++ /dev/null @@ -1,6204 +0,0 @@ -#define IEEE_8087 -/**************************************************************** - * - * The author of this software is David M. Gay. - * - * Copyright (c) 1991, 2000, 2001 by Lucent Technologies. - * - * Permission to use, copy, modify, and distribute this software for any - * purpose without fee is hereby granted, provided that this entire notice - * is included in all copies of any software which is or includes a copy - * or modification of this software and in all copies of the supporting - * documentation for such software. - * - * THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED - * WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR LUCENT MAKES ANY - * REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY - * OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE. - * - ***************************************************************/ - -/* Please send bug reports to David M. Gay (dmg at acm dot org, - * with " at " changed at "@" and " dot " changed to "."). */ - -/* On a machine with IEEE extended-precision registers, it is - * necessary to specify double-precision (53-bit) rounding precision - * before invoking strtod or dtoa. If the machine uses (the equivalent - * of) Intel 80x87 arithmetic, the call - * _control87(PC_53, MCW_PC); - * does this with many compilers. Whether this or another call is - * appropriate depends on the compiler; for this to work, it may be - * necessary to #include "float.h" or another system-dependent header - * file. - */ - -/* strtod for IEEE-, VAX-, and IBM-arithmetic machines. - * (Note that IEEE arithmetic is disabled by gcc's -ffast-math flag.) - * - * This strtod returns a nearest machine number to the input decimal - * string (or sets errno to ERANGE). With IEEE arithmetic, ties are - * broken by the IEEE round-even rule. Otherwise ties are broken by - * biased rounding (add half and chop). - * - * Inspired loosely by William D. Clinger's paper "How to Read Floating - * Point Numbers Accurately" [Proc. ACM SIGPLAN '90, pp. 92-101]. - * - * Modifications: - * - * 1. We only require IEEE, IBM, or VAX double-precision - * arithmetic (not IEEE double-extended). - * 2. We get by with floating-point arithmetic in a case that - * Clinger missed -- when we're computing d * 10^n - * for a small integer d and the integer n is not too - * much larger than 22 (the maximum integer k for which - * we can represent 10^k exactly), we may be able to - * compute (d*10^k) * 10^(e-k) with just one roundoff. - * 3. Rather than a bit-at-a-time adjustment of the binary - * result in the hard case, we use floating-point - * arithmetic to determine the adjustment to within - * one bit; only in really hard cases do we need to - * compute a second residual. - * 4. Because of 3., we don't need a large table of powers of 10 - * for ten-to-e (just some small tables, e.g. of 10^k - * for 0 <= k <= 22). - */ - -/* - * #define IEEE_8087 for IEEE-arithmetic machines where the least - * significant byte has the lowest address. - * #define IEEE_MC68k for IEEE-arithmetic machines where the most - * significant byte has the lowest address. - * #define Long int on machines with 32-bit ints and 64-bit longs. - * #define IBM for IBM mainframe-style floating-point arithmetic. - * #define VAX for VAX-style floating-point arithmetic (D_floating). - * #define No_leftright to omit left-right logic in fast floating-point - * computation of dtoa. This will cause dtoa modes 4 and 5 to be - * treated the same as modes 2 and 3 for some inputs. - * #define Honor_FLT_ROUNDS if FLT_ROUNDS can assume the values 2 or 3 - * and strtod and dtoa should round accordingly. Unless Trust_FLT_ROUNDS - * is also #defined, fegetround() will be queried for the rounding mode. - * Note that both FLT_ROUNDS and fegetround() are specified by the C99 - * standard (and are specified to be consistent, with fesetround() - * affecting the value of FLT_ROUNDS), but that some (Linux) systems - * do not work correctly in this regard, so using fegetround() is more - * portable than using FLT_ROUNDS directly. - * #define Check_FLT_ROUNDS if FLT_ROUNDS can assume the values 2 or 3 - * and Honor_FLT_ROUNDS is not #defined. - * #define RND_PRODQUOT to use rnd_prod and rnd_quot (assembly routines - * that use extended-precision instructions to compute rounded - * products and quotients) with IBM. - * #define ROUND_BIASED for IEEE-format with biased rounding and arithmetic - * that rounds toward +Infinity. - * #define ROUND_BIASED_without_Round_Up for IEEE-format with biased - * rounding when the underlying floating-point arithmetic uses - * unbiased rounding. This prevent using ordinary floating-point - * arithmetic when the result could be computed with one rounding error. - * #define Inaccurate_Divide for IEEE-format with correctly rounded - * products but inaccurate quotients, e.g., for Intel i860. - * #define NO_LONG_LONG on machines that do not have a "long long" - * integer type (of >= 64 bits). On such machines, you can - * #define Just_16 to store 16 bits per 32-bit Long when doing - * high-precision integer arithmetic. Whether this speeds things - * up or slows things down depends on the machine and the number - * being converted. If long long is available and the name is - * something other than "long long", #define Llong to be the name, - * and if "unsigned Llong" does not work as an unsigned version of - * Llong, #define #ULLong to be the corresponding unsigned type. - * #define Bad_float_h if your system lacks a float.h or if it does not - * define some or all of DBL_DIG, DBL_MAX_10_EXP, DBL_MAX_EXP, - * FLT_RADIX, FLT_ROUNDS, and DBL_MAX. - * #define MALLOC your_malloc, where your_malloc(n) acts like malloc(n) - * if memory is available and otherwise does something you deem - * appropriate. If MALLOC is undefined, malloc will be invoked - * directly -- and assumed always to succeed. Similarly, if you - * want something other than the system's free() to be called to - * recycle memory acquired from MALLOC, #define FREE to be the - * name of the alternate routine. (FREE or free is only called in - * pathological cases, e.g., in a dtoa call after a dtoa return in - * mode 3 with thousands of digits requested.) - * #define Omit_Private_Memory to omit logic (added Jan. 1998) for making - * memory allocations from a private pool of memory when possible. - * When used, the private pool is PRIVATE_MEM bytes long: 2304 bytes, - * unless #defined to be a different length. This default length - * suffices to get rid of MALLOC calls except for unusual cases, - * such as decimal-to-binary conversion of a very long string of - * digits. The longest string dtoa can return is about 751 bytes - * long. For conversions by strtod of strings of 800 digits and - * all dtoa conversions in single-threaded executions with 8-byte - * pointers, PRIVATE_MEM >= 7400 appears to suffice; with 4-byte - * pointers, PRIVATE_MEM >= 7112 appears adequate. - * #define NO_INFNAN_CHECK if you do not wish to have INFNAN_CHECK - * #defined automatically on IEEE systems. On such systems, - * when INFNAN_CHECK is #defined, strtod checks - * for Infinity and NaN (case insensitively). On some systems - * (e.g., some HP systems), it may be necessary to #define NAN_WORD0 - * appropriately -- to the most significant word of a quiet NaN. - * (On HP Series 700/800 machines, -DNAN_WORD0=0x7ff40000 works.) - * When INFNAN_CHECK is #defined and No_Hex_NaN is not #defined, - * strtod also accepts (case insensitively) strings of the form - * NaN(x), where x is a string of hexadecimal digits and spaces; - * if there is only one string of hexadecimal digits, it is taken - * for the 52 fraction bits of the resulting NaN; if there are two - * or more strings of hex digits, the first is for the high 20 bits, - * the second and subsequent for the low 32 bits, with intervening - * white space ignored; but if this results in none of the 52 - * fraction bits being on (an IEEE Infinity symbol), then NAN_WORD0 - * and NAN_WORD1 are used instead. - * #define MULTIPLE_THREADS if the system offers preemptively scheduled - * multiple threads. In this case, you must provide (or suitably - * #define) two locks, acquired by ACQUIRE_DTOA_LOCK(n) and freed - * by FREE_DTOA_LOCK(n) for n = 0 or 1. (The second lock, accessed - * in pow5mult, ensures lazy evaluation of only one copy of high - * powers of 5; omitting this lock would introduce a small - * probability of wasting memory, but would otherwise be harmless.) - * You must also invoke freedtoa(s) to free the value s returned by - * dtoa. You may do so whether or not MULTIPLE_THREADS is #defined. - - * When MULTIPLE_THREADS is #defined, this source file provides - * void set_max_dtoa_threads(unsigned int n); - * and expects - * unsigned int dtoa_get_threadno(void); - * to be available (possibly provided by - * #define dtoa_get_threadno omp_get_thread_num - * if OpenMP is in use or by - * #define dtoa_get_threadno pthread_self - * if Pthreads is in use), to return the current thread number. - * If set_max_dtoa_threads(n) was called and the current thread - * number is k with k < n, then calls on ACQUIRE_DTOA_LOCK(...) and - * FREE_DTOA_LOCK(...) are avoided; instead each thread with thread - * number < n has a separate copy of relevant data structures. - * After set_max_dtoa_threads(n), a call set_max_dtoa_threads(m) - * with m <= n has has no effect, but a call with m > n is honored. - * Such a call invokes REALLOC (assumed to be "realloc" if REALLOC - * is not #defined) to extend the size of the relevant array. - - * #define NO_IEEE_Scale to disable new (Feb. 1997) logic in strtod that - * avoids underflows on inputs whose result does not underflow. - * If you #define NO_IEEE_Scale on a machine that uses IEEE-format - * floating-point numbers and flushes underflows to zero rather - * than implementing gradual underflow, then you must also #define - * Sudden_Underflow. - * #define USE_LOCALE to use the current locale's decimal_point value. - * #define SET_INEXACT if IEEE arithmetic is being used and extra - * computation should be done to set the inexact flag when the - * result is inexact and avoid setting inexact when the result - * is exact. In this case, dtoa.c must be compiled in - * an environment, perhaps provided by #include "dtoa.c" in a - * suitable wrapper, that defines two functions, - * int get_inexact(void); - * void clear_inexact(void); - * such that get_inexact() returns a nonzero value if the - * inexact bit is already set, and clear_inexact() sets the - * inexact bit to 0. When SET_INEXACT is #defined, strtod - * also does extra computations to set the underflow and overflow - * flags when appropriate (i.e., when the result is tiny and - * inexact or when it is a numeric value rounded to +-infinity). - * #define NO_ERRNO if strtod should not assign errno = ERANGE when - * the result overflows to +-Infinity or underflows to 0. - * When errno should be assigned, under seemingly rare conditions - * it may be necessary to define Set_errno(x) suitably, e.g., in - * a local errno.h, such as - * #include - * #define Set_errno(x) _set_errno(x) - * #define NO_HEX_FP to omit recognition of hexadecimal floating-point - * values by strtod. - * #define NO_STRTOD_BIGCOMP (on IEEE-arithmetic systems only for now) - * to disable logic for "fast" testing of very long input strings - * to strtod. This testing proceeds by initially truncating the - * input string, then if necessary comparing the whole string with - * a decimal expansion to decide close cases. This logic is only - * used for input more than STRTOD_DIGLIM digits long (default 40). - */ - -#ifndef Long -#define Long int -#endif -#ifndef ULong -typedef unsigned Long ULong; -#endif - -#ifdef DEBUG -#include -#include "stdio.h" -#define Bug(x) {fprintf(stderr, "%s\n", x); exit(1);} -#define Debug(x) x -int dtoa_stats[7]; /* strtod_{64,96,bigcomp},dtoa_{exact,64,96,bigcomp} */ -#else -#define assert(x) /*nothing*/ -#define Debug(x) /*nothing*/ -#endif - -#include "stdlib.h" -#include "string.h" - -#ifdef USE_LOCALE -#include "locale.h" -#endif - -#ifdef Honor_FLT_ROUNDS -#ifndef Trust_FLT_ROUNDS -#include -#endif -#endif - -#ifdef __cplusplus -extern "C" { -#endif -#ifdef MALLOC -extern void *MALLOC(size_t); -#else -#define MALLOC malloc -#endif - -#ifdef REALLOC -extern void *REALLOC(void*,size_t); -#else -#define REALLOC realloc -#endif - -#ifndef FREE -#define FREE free -#endif - -#ifdef __cplusplus - } -#endif - -#ifndef Omit_Private_Memory -#ifndef PRIVATE_MEM -#define PRIVATE_MEM 2304 -#endif -#define PRIVATE_mem ((PRIVATE_MEM+sizeof(double)-1)/sizeof(double)) -static double private_mem[PRIVATE_mem], *pmem_next = private_mem; -#endif - -#undef IEEE_Arith -#undef Avoid_Underflow -#ifdef IEEE_MC68k -#define IEEE_Arith -#endif -#ifdef IEEE_8087 -#define IEEE_Arith -#endif - -#ifdef IEEE_Arith -#ifndef NO_INFNAN_CHECK -#undef INFNAN_CHECK -#define INFNAN_CHECK -#endif -#else -#undef INFNAN_CHECK -#define NO_STRTOD_BIGCOMP -#endif - -#include "errno.h" - -#ifdef NO_ERRNO /*{*/ -#undef Set_errno -#define Set_errno(x) -#else -#ifndef Set_errno -#define Set_errno(x) errno = x -#endif -#endif /*}*/ - -#ifdef Bad_float_h - -#ifdef IEEE_Arith -#define DBL_DIG 15 -#define DBL_MAX_10_EXP 308 -#define DBL_MAX_EXP 1024 -#define FLT_RADIX 2 -#endif /*IEEE_Arith*/ - -#ifdef IBM -#define DBL_DIG 16 -#define DBL_MAX_10_EXP 75 -#define DBL_MAX_EXP 63 -#define FLT_RADIX 16 -#define DBL_MAX 7.2370055773322621e+75 -#endif - -#ifdef VAX -#define DBL_DIG 16 -#define DBL_MAX_10_EXP 38 -#define DBL_MAX_EXP 127 -#define FLT_RADIX 2 -#define DBL_MAX 1.7014118346046923e+38 -#endif - -#ifndef LONG_MAX -#define LONG_MAX 2147483647 -#endif - -#else /* ifndef Bad_float_h */ -#include "float.h" -#endif /* Bad_float_h */ - -#ifndef __MATH_H__ -#include "math.h" -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(IEEE_8087) + defined(IEEE_MC68k) + defined(VAX) + defined(IBM) != 1 -Exactly one of IEEE_8087, IEEE_MC68k, VAX, or IBM should be defined. -#endif - -#undef USE_BF96 - -#ifdef NO_LONG_LONG /*{{*/ -#undef ULLong -#ifdef Just_16 -#undef Pack_32 -/* When Pack_32 is not defined, we store 16 bits per 32-bit Long. - * This makes some inner loops simpler and sometimes saves work - * during multiplications, but it often seems to make things slightly - * slower. Hence the default is now to store 32 bits per Long. - */ -#endif -#else /*}{ long long available */ -#ifndef Llong -#define Llong long long -#endif -#ifndef ULLong -#define ULLong unsigned Llong -#endif -#ifndef NO_BF96 /*{*/ -#define USE_BF96 - -#ifdef SET_INEXACT -#define dtoa_divmax 27 -#else -int dtoa_divmax = 2; /* Permit experimenting: on some systems, 64-bit integer */ - /* division is slow enough that we may sometimes want to */ - /* avoid using it. We assume (but do not check) that */ - /* dtoa_divmax <= 27.*/ -#endif - -typedef struct BF96 { /* Normalized 96-bit software floating point numbers */ - unsigned int b0,b1,b2; /* b0 = most significant, binary point just to its left */ - int e; /* number represented = b * 2^e, with .5 <= b < 1 */ - } BF96; - - static BF96 pten[667] = { - { 0xeef453d6, 0x923bd65a, 0x113faa29, -1136 }, - { 0x9558b466, 0x1b6565f8, 0x4ac7ca59, -1132 }, - { 0xbaaee17f, 0xa23ebf76, 0x5d79bcf0, -1129 }, - { 0xe95a99df, 0x8ace6f53, 0xf4d82c2c, -1126 }, - { 0x91d8a02b, 0xb6c10594, 0x79071b9b, -1122 }, - { 0xb64ec836, 0xa47146f9, 0x9748e282, -1119 }, - { 0xe3e27a44, 0x4d8d98b7, 0xfd1b1b23, -1116 }, - { 0x8e6d8c6a, 0xb0787f72, 0xfe30f0f5, -1112 }, - { 0xb208ef85, 0x5c969f4f, 0xbdbd2d33, -1109 }, - { 0xde8b2b66, 0xb3bc4723, 0xad2c7880, -1106 }, - { 0x8b16fb20, 0x3055ac76, 0x4c3bcb50, -1102 }, - { 0xaddcb9e8, 0x3c6b1793, 0xdf4abe24, -1099 }, - { 0xd953e862, 0x4b85dd78, 0xd71d6dad, -1096 }, - { 0x87d4713d, 0x6f33aa6b, 0x8672648c, -1092 }, - { 0xa9c98d8c, 0xcb009506, 0x680efdaf, -1089 }, - { 0xd43bf0ef, 0xfdc0ba48, 0x0212bd1b, -1086 }, - { 0x84a57695, 0xfe98746d, 0x014bb630, -1082 }, - { 0xa5ced43b, 0x7e3e9188, 0x419ea3bd, -1079 }, - { 0xcf42894a, 0x5dce35ea, 0x52064cac, -1076 }, - { 0x818995ce, 0x7aa0e1b2, 0x7343efeb, -1072 }, - { 0xa1ebfb42, 0x19491a1f, 0x1014ebe6, -1069 }, - { 0xca66fa12, 0x9f9b60a6, 0xd41a26e0, -1066 }, - { 0xfd00b897, 0x478238d0, 0x8920b098, -1063 }, - { 0x9e20735e, 0x8cb16382, 0x55b46e5f, -1059 }, - { 0xc5a89036, 0x2fddbc62, 0xeb2189f7, -1056 }, - { 0xf712b443, 0xbbd52b7b, 0xa5e9ec75, -1053 }, - { 0x9a6bb0aa, 0x55653b2d, 0x47b233c9, -1049 }, - { 0xc1069cd4, 0xeabe89f8, 0x999ec0bb, -1046 }, - { 0xf148440a, 0x256e2c76, 0xc00670ea, -1043 }, - { 0x96cd2a86, 0x5764dbca, 0x38040692, -1039 }, - { 0xbc807527, 0xed3e12bc, 0xc6050837, -1036 }, - { 0xeba09271, 0xe88d976b, 0xf7864a44, -1033 }, - { 0x93445b87, 0x31587ea3, 0x7ab3ee6a, -1029 }, - { 0xb8157268, 0xfdae9e4c, 0x5960ea05, -1026 }, - { 0xe61acf03, 0x3d1a45df, 0x6fb92487, -1023 }, - { 0x8fd0c162, 0x06306bab, 0xa5d3b6d4, -1019 }, - { 0xb3c4f1ba, 0x87bc8696, 0x8f48a489, -1016 }, - { 0xe0b62e29, 0x29aba83c, 0x331acdab, -1013 }, - { 0x8c71dcd9, 0xba0b4925, 0x9ff0c08b, -1009 }, - { 0xaf8e5410, 0x288e1b6f, 0x07ecf0ae, -1006 }, - { 0xdb71e914, 0x32b1a24a, 0xc9e82cd9, -1003 }, - { 0x892731ac, 0x9faf056e, 0xbe311c08, -999 }, - { 0xab70fe17, 0xc79ac6ca, 0x6dbd630a, -996 }, - { 0xd64d3d9d, 0xb981787d, 0x092cbbcc, -993 }, - { 0x85f04682, 0x93f0eb4e, 0x25bbf560, -989 }, - { 0xa76c5823, 0x38ed2621, 0xaf2af2b8, -986 }, - { 0xd1476e2c, 0x07286faa, 0x1af5af66, -983 }, - { 0x82cca4db, 0x847945ca, 0x50d98d9f, -979 }, - { 0xa37fce12, 0x6597973c, 0xe50ff107, -976 }, - { 0xcc5fc196, 0xfefd7d0c, 0x1e53ed49, -973 }, - { 0xff77b1fc, 0xbebcdc4f, 0x25e8e89c, -970 }, - { 0x9faacf3d, 0xf73609b1, 0x77b19161, -966 }, - { 0xc795830d, 0x75038c1d, 0xd59df5b9, -963 }, - { 0xf97ae3d0, 0xd2446f25, 0x4b057328, -960 }, - { 0x9becce62, 0x836ac577, 0x4ee367f9, -956 }, - { 0xc2e801fb, 0x244576d5, 0x229c41f7, -953 }, - { 0xf3a20279, 0xed56d48a, 0x6b435275, -950 }, - { 0x9845418c, 0x345644d6, 0x830a1389, -946 }, - { 0xbe5691ef, 0x416bd60c, 0x23cc986b, -943 }, - { 0xedec366b, 0x11c6cb8f, 0x2cbfbe86, -940 }, - { 0x94b3a202, 0xeb1c3f39, 0x7bf7d714, -936 }, - { 0xb9e08a83, 0xa5e34f07, 0xdaf5ccd9, -933 }, - { 0xe858ad24, 0x8f5c22c9, 0xd1b3400f, -930 }, - { 0x91376c36, 0xd99995be, 0x23100809, -926 }, - { 0xb5854744, 0x8ffffb2d, 0xabd40a0c, -923 }, - { 0xe2e69915, 0xb3fff9f9, 0x16c90c8f, -920 }, - { 0x8dd01fad, 0x907ffc3b, 0xae3da7d9, -916 }, - { 0xb1442798, 0xf49ffb4a, 0x99cd11cf, -913 }, - { 0xdd95317f, 0x31c7fa1d, 0x40405643, -910 }, - { 0x8a7d3eef, 0x7f1cfc52, 0x482835ea, -906 }, - { 0xad1c8eab, 0x5ee43b66, 0xda324365, -903 }, - { 0xd863b256, 0x369d4a40, 0x90bed43e, -900 }, - { 0x873e4f75, 0xe2224e68, 0x5a7744a6, -896 }, - { 0xa90de353, 0x5aaae202, 0x711515d0, -893 }, - { 0xd3515c28, 0x31559a83, 0x0d5a5b44, -890 }, - { 0x8412d999, 0x1ed58091, 0xe858790a, -886 }, - { 0xa5178fff, 0x668ae0b6, 0x626e974d, -883 }, - { 0xce5d73ff, 0x402d98e3, 0xfb0a3d21, -880 }, - { 0x80fa687f, 0x881c7f8e, 0x7ce66634, -876 }, - { 0xa139029f, 0x6a239f72, 0x1c1fffc1, -873 }, - { 0xc9874347, 0x44ac874e, 0xa327ffb2, -870 }, - { 0xfbe91419, 0x15d7a922, 0x4bf1ff9f, -867 }, - { 0x9d71ac8f, 0xada6c9b5, 0x6f773fc3, -863 }, - { 0xc4ce17b3, 0x99107c22, 0xcb550fb4, -860 }, - { 0xf6019da0, 0x7f549b2b, 0x7e2a53a1, -857 }, - { 0x99c10284, 0x4f94e0fb, 0x2eda7444, -853 }, - { 0xc0314325, 0x637a1939, 0xfa911155, -850 }, - { 0xf03d93ee, 0xbc589f88, 0x793555ab, -847 }, - { 0x96267c75, 0x35b763b5, 0x4bc1558b, -843 }, - { 0xbbb01b92, 0x83253ca2, 0x9eb1aaed, -840 }, - { 0xea9c2277, 0x23ee8bcb, 0x465e15a9, -837 }, - { 0x92a1958a, 0x7675175f, 0x0bfacd89, -833 }, - { 0xb749faed, 0x14125d36, 0xcef980ec, -830 }, - { 0xe51c79a8, 0x5916f484, 0x82b7e127, -827 }, - { 0x8f31cc09, 0x37ae58d2, 0xd1b2ecb8, -823 }, - { 0xb2fe3f0b, 0x8599ef07, 0x861fa7e6, -820 }, - { 0xdfbdcece, 0x67006ac9, 0x67a791e0, -817 }, - { 0x8bd6a141, 0x006042bd, 0xe0c8bb2c, -813 }, - { 0xaecc4991, 0x4078536d, 0x58fae9f7, -810 }, - { 0xda7f5bf5, 0x90966848, 0xaf39a475, -807 }, - { 0x888f9979, 0x7a5e012d, 0x6d8406c9, -803 }, - { 0xaab37fd7, 0xd8f58178, 0xc8e5087b, -800 }, - { 0xd5605fcd, 0xcf32e1d6, 0xfb1e4a9a, -797 }, - { 0x855c3be0, 0xa17fcd26, 0x5cf2eea0, -793 }, - { 0xa6b34ad8, 0xc9dfc06f, 0xf42faa48, -790 }, - { 0xd0601d8e, 0xfc57b08b, 0xf13b94da, -787 }, - { 0x823c1279, 0x5db6ce57, 0x76c53d08, -783 }, - { 0xa2cb1717, 0xb52481ed, 0x54768c4b, -780 }, - { 0xcb7ddcdd, 0xa26da268, 0xa9942f5d, -777 }, - { 0xfe5d5415, 0x0b090b02, 0xd3f93b35, -774 }, - { 0x9efa548d, 0x26e5a6e1, 0xc47bc501, -770 }, - { 0xc6b8e9b0, 0x709f109a, 0x359ab641, -767 }, - { 0xf867241c, 0x8cc6d4c0, 0xc30163d2, -764 }, - { 0x9b407691, 0xd7fc44f8, 0x79e0de63, -760 }, - { 0xc2109436, 0x4dfb5636, 0x985915fc, -757 }, - { 0xf294b943, 0xe17a2bc4, 0x3e6f5b7b, -754 }, - { 0x979cf3ca, 0x6cec5b5a, 0xa705992c, -750 }, - { 0xbd8430bd, 0x08277231, 0x50c6ff78, -747 }, - { 0xece53cec, 0x4a314ebd, 0xa4f8bf56, -744 }, - { 0x940f4613, 0xae5ed136, 0x871b7795, -740 }, - { 0xb9131798, 0x99f68584, 0x28e2557b, -737 }, - { 0xe757dd7e, 0xc07426e5, 0x331aeada, -734 }, - { 0x9096ea6f, 0x3848984f, 0x3ff0d2c8, -730 }, - { 0xb4bca50b, 0x065abe63, 0x0fed077a, -727 }, - { 0xe1ebce4d, 0xc7f16dfb, 0xd3e84959, -724 }, - { 0x8d3360f0, 0x9cf6e4bd, 0x64712dd7, -720 }, - { 0xb080392c, 0xc4349dec, 0xbd8d794d, -717 }, - { 0xdca04777, 0xf541c567, 0xecf0d7a0, -714 }, - { 0x89e42caa, 0xf9491b60, 0xf41686c4, -710 }, - { 0xac5d37d5, 0xb79b6239, 0x311c2875, -707 }, - { 0xd77485cb, 0x25823ac7, 0x7d633293, -704 }, - { 0x86a8d39e, 0xf77164bc, 0xae5dff9c, -700 }, - { 0xa8530886, 0xb54dbdeb, 0xd9f57f83, -697 }, - { 0xd267caa8, 0x62a12d66, 0xd072df63, -694 }, - { 0x8380dea9, 0x3da4bc60, 0x4247cb9e, -690 }, - { 0xa4611653, 0x8d0deb78, 0x52d9be85, -687 }, - { 0xcd795be8, 0x70516656, 0x67902e27, -684 }, - { 0x806bd971, 0x4632dff6, 0x00ba1cd8, -680 }, - { 0xa086cfcd, 0x97bf97f3, 0x80e8a40e, -677 }, - { 0xc8a883c0, 0xfdaf7df0, 0x6122cd12, -674 }, - { 0xfad2a4b1, 0x3d1b5d6c, 0x796b8057, -671 }, - { 0x9cc3a6ee, 0xc6311a63, 0xcbe33036, -667 }, - { 0xc3f490aa, 0x77bd60fc, 0xbedbfc44, -664 }, - { 0xf4f1b4d5, 0x15acb93b, 0xee92fb55, -661 }, - { 0x99171105, 0x2d8bf3c5, 0x751bdd15, -657 }, - { 0xbf5cd546, 0x78eef0b6, 0xd262d45a, -654 }, - { 0xef340a98, 0x172aace4, 0x86fb8971, -651 }, - { 0x9580869f, 0x0e7aac0e, 0xd45d35e6, -647 }, - { 0xbae0a846, 0xd2195712, 0x89748360, -644 }, - { 0xe998d258, 0x869facd7, 0x2bd1a438, -641 }, - { 0x91ff8377, 0x5423cc06, 0x7b6306a3, -637 }, - { 0xb67f6455, 0x292cbf08, 0x1a3bc84c, -634 }, - { 0xe41f3d6a, 0x7377eeca, 0x20caba5f, -631 }, - { 0x8e938662, 0x882af53e, 0x547eb47b, -627 }, - { 0xb23867fb, 0x2a35b28d, 0xe99e619a, -624 }, - { 0xdec681f9, 0xf4c31f31, 0x6405fa00, -621 }, - { 0x8b3c113c, 0x38f9f37e, 0xde83bc40, -617 }, - { 0xae0b158b, 0x4738705e, 0x9624ab50, -614 }, - { 0xd98ddaee, 0x19068c76, 0x3badd624, -611 }, - { 0x87f8a8d4, 0xcfa417c9, 0xe54ca5d7, -607 }, - { 0xa9f6d30a, 0x038d1dbc, 0x5e9fcf4c, -604 }, - { 0xd47487cc, 0x8470652b, 0x7647c320, -601 }, - { 0x84c8d4df, 0xd2c63f3b, 0x29ecd9f4, -597 }, - { 0xa5fb0a17, 0xc777cf09, 0xf4681071, -594 }, - { 0xcf79cc9d, 0xb955c2cc, 0x7182148d, -591 }, - { 0x81ac1fe2, 0x93d599bf, 0xc6f14cd8, -587 }, - { 0xa21727db, 0x38cb002f, 0xb8ada00e, -584 }, - { 0xca9cf1d2, 0x06fdc03b, 0xa6d90811, -581 }, - { 0xfd442e46, 0x88bd304a, 0x908f4a16, -578 }, - { 0x9e4a9cec, 0x15763e2e, 0x9a598e4e, -574 }, - { 0xc5dd4427, 0x1ad3cdba, 0x40eff1e1, -571 }, - { 0xf7549530, 0xe188c128, 0xd12bee59, -568 }, - { 0x9a94dd3e, 0x8cf578b9, 0x82bb74f8, -564 }, - { 0xc13a148e, 0x3032d6e7, 0xe36a5236, -561 }, - { 0xf18899b1, 0xbc3f8ca1, 0xdc44e6c3, -558 }, - { 0x96f5600f, 0x15a7b7e5, 0x29ab103a, -554 }, - { 0xbcb2b812, 0xdb11a5de, 0x7415d448, -551 }, - { 0xebdf6617, 0x91d60f56, 0x111b495b, -548 }, - { 0x936b9fce, 0xbb25c995, 0xcab10dd9, -544 }, - { 0xb84687c2, 0x69ef3bfb, 0x3d5d514f, -541 }, - { 0xe65829b3, 0x046b0afa, 0x0cb4a5a3, -538 }, - { 0x8ff71a0f, 0xe2c2e6dc, 0x47f0e785, -534 }, - { 0xb3f4e093, 0xdb73a093, 0x59ed2167, -531 }, - { 0xe0f218b8, 0xd25088b8, 0x306869c1, -528 }, - { 0x8c974f73, 0x83725573, 0x1e414218, -524 }, - { 0xafbd2350, 0x644eeacf, 0xe5d1929e, -521 }, - { 0xdbac6c24, 0x7d62a583, 0xdf45f746, -518 }, - { 0x894bc396, 0xce5da772, 0x6b8bba8c, -514 }, - { 0xab9eb47c, 0x81f5114f, 0x066ea92f, -511 }, - { 0xd686619b, 0xa27255a2, 0xc80a537b, -508 }, - { 0x8613fd01, 0x45877585, 0xbd06742c, -504 }, - { 0xa798fc41, 0x96e952e7, 0x2c481138, -501 }, - { 0xd17f3b51, 0xfca3a7a0, 0xf75a1586, -498 }, - { 0x82ef8513, 0x3de648c4, 0x9a984d73, -494 }, - { 0xa3ab6658, 0x0d5fdaf5, 0xc13e60d0, -491 }, - { 0xcc963fee, 0x10b7d1b3, 0x318df905, -488 }, - { 0xffbbcfe9, 0x94e5c61f, 0xfdf17746, -485 }, - { 0x9fd561f1, 0xfd0f9bd3, 0xfeb6ea8b, -481 }, - { 0xc7caba6e, 0x7c5382c8, 0xfe64a52e, -478 }, - { 0xf9bd690a, 0x1b68637b, 0x3dfdce7a, -475 }, - { 0x9c1661a6, 0x51213e2d, 0x06bea10c, -471 }, - { 0xc31bfa0f, 0xe5698db8, 0x486e494f, -468 }, - { 0xf3e2f893, 0xdec3f126, 0x5a89dba3, -465 }, - { 0x986ddb5c, 0x6b3a76b7, 0xf8962946, -461 }, - { 0xbe895233, 0x86091465, 0xf6bbb397, -458 }, - { 0xee2ba6c0, 0x678b597f, 0x746aa07d, -455 }, - { 0x94db4838, 0x40b717ef, 0xa8c2a44e, -451 }, - { 0xba121a46, 0x50e4ddeb, 0x92f34d62, -448 }, - { 0xe896a0d7, 0xe51e1566, 0x77b020ba, -445 }, - { 0x915e2486, 0xef32cd60, 0x0ace1474, -441 }, - { 0xb5b5ada8, 0xaaff80b8, 0x0d819992, -438 }, - { 0xe3231912, 0xd5bf60e6, 0x10e1fff6, -435 }, - { 0x8df5efab, 0xc5979c8f, 0xca8d3ffa, -431 }, - { 0xb1736b96, 0xb6fd83b3, 0xbd308ff8, -428 }, - { 0xddd0467c, 0x64bce4a0, 0xac7cb3f6, -425 }, - { 0x8aa22c0d, 0xbef60ee4, 0x6bcdf07a, -421 }, - { 0xad4ab711, 0x2eb3929d, 0x86c16c98, -418 }, - { 0xd89d64d5, 0x7a607744, 0xe871c7bf, -415 }, - { 0x87625f05, 0x6c7c4a8b, 0x11471cd7, -411 }, - { 0xa93af6c6, 0xc79b5d2d, 0xd598e40d, -408 }, - { 0xd389b478, 0x79823479, 0x4aff1d10, -405 }, - { 0x843610cb, 0x4bf160cb, 0xcedf722a, -401 }, - { 0xa54394fe, 0x1eedb8fe, 0xc2974eb4, -398 }, - { 0xce947a3d, 0xa6a9273e, 0x733d2262, -395 }, - { 0x811ccc66, 0x8829b887, 0x0806357d, -391 }, - { 0xa163ff80, 0x2a3426a8, 0xca07c2dc, -388 }, - { 0xc9bcff60, 0x34c13052, 0xfc89b393, -385 }, - { 0xfc2c3f38, 0x41f17c67, 0xbbac2078, -382 }, - { 0x9d9ba783, 0x2936edc0, 0xd54b944b, -378 }, - { 0xc5029163, 0xf384a931, 0x0a9e795e, -375 }, - { 0xf64335bc, 0xf065d37d, 0x4d4617b5, -372 }, - { 0x99ea0196, 0x163fa42e, 0x504bced1, -368 }, - { 0xc06481fb, 0x9bcf8d39, 0xe45ec286, -365 }, - { 0xf07da27a, 0x82c37088, 0x5d767327, -362 }, - { 0x964e858c, 0x91ba2655, 0x3a6a07f8, -358 }, - { 0xbbe226ef, 0xb628afea, 0x890489f7, -355 }, - { 0xeadab0ab, 0xa3b2dbe5, 0x2b45ac74, -352 }, - { 0x92c8ae6b, 0x464fc96f, 0x3b0b8bc9, -348 }, - { 0xb77ada06, 0x17e3bbcb, 0x09ce6ebb, -345 }, - { 0xe5599087, 0x9ddcaabd, 0xcc420a6a, -342 }, - { 0x8f57fa54, 0xc2a9eab6, 0x9fa94682, -338 }, - { 0xb32df8e9, 0xf3546564, 0x47939822, -335 }, - { 0xdff97724, 0x70297ebd, 0x59787e2b, -332 }, - { 0x8bfbea76, 0xc619ef36, 0x57eb4edb, -328 }, - { 0xaefae514, 0x77a06b03, 0xede62292, -325 }, - { 0xdab99e59, 0x958885c4, 0xe95fab36, -322 }, - { 0x88b402f7, 0xfd75539b, 0x11dbcb02, -318 }, - { 0xaae103b5, 0xfcd2a881, 0xd652bdc2, -315 }, - { 0xd59944a3, 0x7c0752a2, 0x4be76d33, -312 }, - { 0x857fcae6, 0x2d8493a5, 0x6f70a440, -308 }, - { 0xa6dfbd9f, 0xb8e5b88e, 0xcb4ccd50, -305 }, - { 0xd097ad07, 0xa71f26b2, 0x7e2000a4, -302 }, - { 0x825ecc24, 0xc873782f, 0x8ed40066, -298 }, - { 0xa2f67f2d, 0xfa90563b, 0x72890080, -295 }, - { 0xcbb41ef9, 0x79346bca, 0x4f2b40a0, -292 }, - { 0xfea126b7, 0xd78186bc, 0xe2f610c8, -289 }, - { 0x9f24b832, 0xe6b0f436, 0x0dd9ca7d, -285 }, - { 0xc6ede63f, 0xa05d3143, 0x91503d1c, -282 }, - { 0xf8a95fcf, 0x88747d94, 0x75a44c63, -279 }, - { 0x9b69dbe1, 0xb548ce7c, 0xc986afbe, -275 }, - { 0xc24452da, 0x229b021b, 0xfbe85bad, -272 }, - { 0xf2d56790, 0xab41c2a2, 0xfae27299, -269 }, - { 0x97c560ba, 0x6b0919a5, 0xdccd879f, -265 }, - { 0xbdb6b8e9, 0x05cb600f, 0x5400e987, -262 }, - { 0xed246723, 0x473e3813, 0x290123e9, -259 }, - { 0x9436c076, 0x0c86e30b, 0xf9a0b672, -255 }, - { 0xb9447093, 0x8fa89bce, 0xf808e40e, -252 }, - { 0xe7958cb8, 0x7392c2c2, 0xb60b1d12, -249 }, - { 0x90bd77f3, 0x483bb9b9, 0xb1c6f22b, -245 }, - { 0xb4ecd5f0, 0x1a4aa828, 0x1e38aeb6, -242 }, - { 0xe2280b6c, 0x20dd5232, 0x25c6da63, -239 }, - { 0x8d590723, 0x948a535f, 0x579c487e, -235 }, - { 0xb0af48ec, 0x79ace837, 0x2d835a9d, -232 }, - { 0xdcdb1b27, 0x98182244, 0xf8e43145, -229 }, - { 0x8a08f0f8, 0xbf0f156b, 0x1b8e9ecb, -225 }, - { 0xac8b2d36, 0xeed2dac5, 0xe272467e, -222 }, - { 0xd7adf884, 0xaa879177, 0x5b0ed81d, -219 }, - { 0x86ccbb52, 0xea94baea, 0x98e94712, -215 }, - { 0xa87fea27, 0xa539e9a5, 0x3f2398d7, -212 }, - { 0xd29fe4b1, 0x8e88640e, 0x8eec7f0d, -209 }, - { 0x83a3eeee, 0xf9153e89, 0x1953cf68, -205 }, - { 0xa48ceaaa, 0xb75a8e2b, 0x5fa8c342, -202 }, - { 0xcdb02555, 0x653131b6, 0x3792f412, -199 }, - { 0x808e1755, 0x5f3ebf11, 0xe2bbd88b, -195 }, - { 0xa0b19d2a, 0xb70e6ed6, 0x5b6aceae, -192 }, - { 0xc8de0475, 0x64d20a8b, 0xf245825a, -189 }, - { 0xfb158592, 0xbe068d2e, 0xeed6e2f0, -186 }, - { 0x9ced737b, 0xb6c4183d, 0x55464dd6, -182 }, - { 0xc428d05a, 0xa4751e4c, 0xaa97e14c, -179 }, - { 0xf5330471, 0x4d9265df, 0xd53dd99f, -176 }, - { 0x993fe2c6, 0xd07b7fab, 0xe546a803, -172 }, - { 0xbf8fdb78, 0x849a5f96, 0xde985204, -169 }, - { 0xef73d256, 0xa5c0f77c, 0x963e6685, -166 }, - { 0x95a86376, 0x27989aad, 0xdde70013, -162 }, - { 0xbb127c53, 0xb17ec159, 0x5560c018, -159 }, - { 0xe9d71b68, 0x9dde71af, 0xaab8f01e, -156 }, - { 0x92267121, 0x62ab070d, 0xcab39613, -152 }, - { 0xb6b00d69, 0xbb55c8d1, 0x3d607b97, -149 }, - { 0xe45c10c4, 0x2a2b3b05, 0x8cb89a7d, -146 }, - { 0x8eb98a7a, 0x9a5b04e3, 0x77f3608e, -142 }, - { 0xb267ed19, 0x40f1c61c, 0x55f038b2, -139 }, - { 0xdf01e85f, 0x912e37a3, 0x6b6c46de, -136 }, - { 0x8b61313b, 0xbabce2c6, 0x2323ac4b, -132 }, - { 0xae397d8a, 0xa96c1b77, 0xabec975e, -129 }, - { 0xd9c7dced, 0x53c72255, 0x96e7bd35, -126 }, - { 0x881cea14, 0x545c7575, 0x7e50d641, -122 }, - { 0xaa242499, 0x697392d2, 0xdde50bd1, -119 }, - { 0xd4ad2dbf, 0xc3d07787, 0x955e4ec6, -116 }, - { 0x84ec3c97, 0xda624ab4, 0xbd5af13b, -112 }, - { 0xa6274bbd, 0xd0fadd61, 0xecb1ad8a, -109 }, - { 0xcfb11ead, 0x453994ba, 0x67de18ed, -106 }, - { 0x81ceb32c, 0x4b43fcf4, 0x80eacf94, -102 }, - { 0xa2425ff7, 0x5e14fc31, 0xa1258379, -99 }, - { 0xcad2f7f5, 0x359a3b3e, 0x096ee458, -96 }, - { 0xfd87b5f2, 0x8300ca0d, 0x8bca9d6e, -93 }, - { 0x9e74d1b7, 0x91e07e48, 0x775ea264, -89 }, - { 0xc6120625, 0x76589dda, 0x95364afe, -86 }, - { 0xf79687ae, 0xd3eec551, 0x3a83ddbd, -83 }, - { 0x9abe14cd, 0x44753b52, 0xc4926a96, -79 }, - { 0xc16d9a00, 0x95928a27, 0x75b7053c, -76 }, - { 0xf1c90080, 0xbaf72cb1, 0x5324c68b, -73 }, - { 0x971da050, 0x74da7bee, 0xd3f6fc16, -69 }, - { 0xbce50864, 0x92111aea, 0x88f4bb1c, -66 }, - { 0xec1e4a7d, 0xb69561a5, 0x2b31e9e3, -63 }, - { 0x9392ee8e, 0x921d5d07, 0x3aff322e, -59 }, - { 0xb877aa32, 0x36a4b449, 0x09befeb9, -56 }, - { 0xe69594be, 0xc44de15b, 0x4c2ebe68, -53 }, - { 0x901d7cf7, 0x3ab0acd9, 0x0f9d3701, -49 }, - { 0xb424dc35, 0x095cd80f, 0x538484c1, -46 }, - { 0xe12e1342, 0x4bb40e13, 0x2865a5f2, -43 }, - { 0x8cbccc09, 0x6f5088cb, 0xf93f87b7, -39 }, - { 0xafebff0b, 0xcb24aafe, 0xf78f69a5, -36 }, - { 0xdbe6fece, 0xbdedd5be, 0xb573440e, -33 }, - { 0x89705f41, 0x36b4a597, 0x31680a88, -29 }, - { 0xabcc7711, 0x8461cefc, 0xfdc20d2b, -26 }, - { 0xd6bf94d5, 0xe57a42bc, 0x3d329076, -23 }, - { 0x8637bd05, 0xaf6c69b5, 0xa63f9a49, -19 }, - { 0xa7c5ac47, 0x1b478423, 0x0fcf80dc, -16 }, - { 0xd1b71758, 0xe219652b, 0xd3c36113, -13 }, - { 0x83126e97, 0x8d4fdf3b, 0x645a1cac, -9 }, - { 0xa3d70a3d, 0x70a3d70a, 0x3d70a3d7, -6 }, - { 0xcccccccc, 0xcccccccc, 0xcccccccc, -3 }, - { 0x80000000, 0x00000000, 0x00000000, 1 }, - { 0xa0000000, 0x00000000, 0x00000000, 4 }, - { 0xc8000000, 0x00000000, 0x00000000, 7 }, - { 0xfa000000, 0x00000000, 0x00000000, 10 }, - { 0x9c400000, 0x00000000, 0x00000000, 14 }, - { 0xc3500000, 0x00000000, 0x00000000, 17 }, - { 0xf4240000, 0x00000000, 0x00000000, 20 }, - { 0x98968000, 0x00000000, 0x00000000, 24 }, - { 0xbebc2000, 0x00000000, 0x00000000, 27 }, - { 0xee6b2800, 0x00000000, 0x00000000, 30 }, - { 0x9502f900, 0x00000000, 0x00000000, 34 }, - { 0xba43b740, 0x00000000, 0x00000000, 37 }, - { 0xe8d4a510, 0x00000000, 0x00000000, 40 }, - { 0x9184e72a, 0x00000000, 0x00000000, 44 }, - { 0xb5e620f4, 0x80000000, 0x00000000, 47 }, - { 0xe35fa931, 0xa0000000, 0x00000000, 50 }, - { 0x8e1bc9bf, 0x04000000, 0x00000000, 54 }, - { 0xb1a2bc2e, 0xc5000000, 0x00000000, 57 }, - { 0xde0b6b3a, 0x76400000, 0x00000000, 60 }, - { 0x8ac72304, 0x89e80000, 0x00000000, 64 }, - { 0xad78ebc5, 0xac620000, 0x00000000, 67 }, - { 0xd8d726b7, 0x177a8000, 0x00000000, 70 }, - { 0x87867832, 0x6eac9000, 0x00000000, 74 }, - { 0xa968163f, 0x0a57b400, 0x00000000, 77 }, - { 0xd3c21bce, 0xcceda100, 0x00000000, 80 }, - { 0x84595161, 0x401484a0, 0x00000000, 84 }, - { 0xa56fa5b9, 0x9019a5c8, 0x00000000, 87 }, - { 0xcecb8f27, 0xf4200f3a, 0x00000000, 90 }, - { 0x813f3978, 0xf8940984, 0x40000000, 94 }, - { 0xa18f07d7, 0x36b90be5, 0x50000000, 97 }, - { 0xc9f2c9cd, 0x04674ede, 0xa4000000, 100 }, - { 0xfc6f7c40, 0x45812296, 0x4d000000, 103 }, - { 0x9dc5ada8, 0x2b70b59d, 0xf0200000, 107 }, - { 0xc5371912, 0x364ce305, 0x6c280000, 110 }, - { 0xf684df56, 0xc3e01bc6, 0xc7320000, 113 }, - { 0x9a130b96, 0x3a6c115c, 0x3c7f4000, 117 }, - { 0xc097ce7b, 0xc90715b3, 0x4b9f1000, 120 }, - { 0xf0bdc21a, 0xbb48db20, 0x1e86d400, 123 }, - { 0x96769950, 0xb50d88f4, 0x13144480, 127 }, - { 0xbc143fa4, 0xe250eb31, 0x17d955a0, 130 }, - { 0xeb194f8e, 0x1ae525fd, 0x5dcfab08, 133 }, - { 0x92efd1b8, 0xd0cf37be, 0x5aa1cae5, 137 }, - { 0xb7abc627, 0x050305ad, 0xf14a3d9e, 140 }, - { 0xe596b7b0, 0xc643c719, 0x6d9ccd05, 143 }, - { 0x8f7e32ce, 0x7bea5c6f, 0xe4820023, 147 }, - { 0xb35dbf82, 0x1ae4f38b, 0xdda2802c, 150 }, - { 0xe0352f62, 0xa19e306e, 0xd50b2037, 153 }, - { 0x8c213d9d, 0xa502de45, 0x4526f422, 157 }, - { 0xaf298d05, 0x0e4395d6, 0x9670b12b, 160 }, - { 0xdaf3f046, 0x51d47b4c, 0x3c0cdd76, 163 }, - { 0x88d8762b, 0xf324cd0f, 0xa5880a69, 167 }, - { 0xab0e93b6, 0xefee0053, 0x8eea0d04, 170 }, - { 0xd5d238a4, 0xabe98068, 0x72a49045, 173 }, - { 0x85a36366, 0xeb71f041, 0x47a6da2b, 177 }, - { 0xa70c3c40, 0xa64e6c51, 0x999090b6, 180 }, - { 0xd0cf4b50, 0xcfe20765, 0xfff4b4e3, 183 }, - { 0x82818f12, 0x81ed449f, 0xbff8f10e, 187 }, - { 0xa321f2d7, 0x226895c7, 0xaff72d52, 190 }, - { 0xcbea6f8c, 0xeb02bb39, 0x9bf4f8a6, 193 }, - { 0xfee50b70, 0x25c36a08, 0x02f236d0, 196 }, - { 0x9f4f2726, 0x179a2245, 0x01d76242, 200 }, - { 0xc722f0ef, 0x9d80aad6, 0x424d3ad2, 203 }, - { 0xf8ebad2b, 0x84e0d58b, 0xd2e08987, 206 }, - { 0x9b934c3b, 0x330c8577, 0x63cc55f4, 210 }, - { 0xc2781f49, 0xffcfa6d5, 0x3cbf6b71, 213 }, - { 0xf316271c, 0x7fc3908a, 0x8bef464e, 216 }, - { 0x97edd871, 0xcfda3a56, 0x97758bf0, 220 }, - { 0xbde94e8e, 0x43d0c8ec, 0x3d52eeed, 223 }, - { 0xed63a231, 0xd4c4fb27, 0x4ca7aaa8, 226 }, - { 0x945e455f, 0x24fb1cf8, 0x8fe8caa9, 230 }, - { 0xb975d6b6, 0xee39e436, 0xb3e2fd53, 233 }, - { 0xe7d34c64, 0xa9c85d44, 0x60dbbca8, 236 }, - { 0x90e40fbe, 0xea1d3a4a, 0xbc8955e9, 240 }, - { 0xb51d13ae, 0xa4a488dd, 0x6babab63, 243 }, - { 0xe264589a, 0x4dcdab14, 0xc696963c, 246 }, - { 0x8d7eb760, 0x70a08aec, 0xfc1e1de5, 250 }, - { 0xb0de6538, 0x8cc8ada8, 0x3b25a55f, 253 }, - { 0xdd15fe86, 0xaffad912, 0x49ef0eb7, 256 }, - { 0x8a2dbf14, 0x2dfcc7ab, 0x6e356932, 260 }, - { 0xacb92ed9, 0x397bf996, 0x49c2c37f, 263 }, - { 0xd7e77a8f, 0x87daf7fb, 0xdc33745e, 266 }, - { 0x86f0ac99, 0xb4e8dafd, 0x69a028bb, 270 }, - { 0xa8acd7c0, 0x222311bc, 0xc40832ea, 273 }, - { 0xd2d80db0, 0x2aabd62b, 0xf50a3fa4, 276 }, - { 0x83c7088e, 0x1aab65db, 0x792667c6, 280 }, - { 0xa4b8cab1, 0xa1563f52, 0x577001b8, 283 }, - { 0xcde6fd5e, 0x09abcf26, 0xed4c0226, 286 }, - { 0x80b05e5a, 0xc60b6178, 0x544f8158, 290 }, - { 0xa0dc75f1, 0x778e39d6, 0x696361ae, 293 }, - { 0xc913936d, 0xd571c84c, 0x03bc3a19, 296 }, - { 0xfb587849, 0x4ace3a5f, 0x04ab48a0, 299 }, - { 0x9d174b2d, 0xcec0e47b, 0x62eb0d64, 303 }, - { 0xc45d1df9, 0x42711d9a, 0x3ba5d0bd, 306 }, - { 0xf5746577, 0x930d6500, 0xca8f44ec, 309 }, - { 0x9968bf6a, 0xbbe85f20, 0x7e998b13, 313 }, - { 0xbfc2ef45, 0x6ae276e8, 0x9e3fedd8, 316 }, - { 0xefb3ab16, 0xc59b14a2, 0xc5cfe94e, 319 }, - { 0x95d04aee, 0x3b80ece5, 0xbba1f1d1, 323 }, - { 0xbb445da9, 0xca61281f, 0x2a8a6e45, 326 }, - { 0xea157514, 0x3cf97226, 0xf52d09d7, 329 }, - { 0x924d692c, 0xa61be758, 0x593c2626, 333 }, - { 0xb6e0c377, 0xcfa2e12e, 0x6f8b2fb0, 336 }, - { 0xe498f455, 0xc38b997a, 0x0b6dfb9c, 339 }, - { 0x8edf98b5, 0x9a373fec, 0x4724bd41, 343 }, - { 0xb2977ee3, 0x00c50fe7, 0x58edec91, 346 }, - { 0xdf3d5e9b, 0xc0f653e1, 0x2f2967b6, 349 }, - { 0x8b865b21, 0x5899f46c, 0xbd79e0d2, 353 }, - { 0xae67f1e9, 0xaec07187, 0xecd85906, 356 }, - { 0xda01ee64, 0x1a708de9, 0xe80e6f48, 359 }, - { 0x884134fe, 0x908658b2, 0x3109058d, 363 }, - { 0xaa51823e, 0x34a7eede, 0xbd4b46f0, 366 }, - { 0xd4e5e2cd, 0xc1d1ea96, 0x6c9e18ac, 369 }, - { 0x850fadc0, 0x9923329e, 0x03e2cf6b, 373 }, - { 0xa6539930, 0xbf6bff45, 0x84db8346, 376 }, - { 0xcfe87f7c, 0xef46ff16, 0xe6126418, 379 }, - { 0x81f14fae, 0x158c5f6e, 0x4fcb7e8f, 383 }, - { 0xa26da399, 0x9aef7749, 0xe3be5e33, 386 }, - { 0xcb090c80, 0x01ab551c, 0x5cadf5bf, 389 }, - { 0xfdcb4fa0, 0x02162a63, 0x73d9732f, 392 }, - { 0x9e9f11c4, 0x014dda7e, 0x2867e7fd, 396 }, - { 0xc646d635, 0x01a1511d, 0xb281e1fd, 399 }, - { 0xf7d88bc2, 0x4209a565, 0x1f225a7c, 402 }, - { 0x9ae75759, 0x6946075f, 0x3375788d, 406 }, - { 0xc1a12d2f, 0xc3978937, 0x0052d6b1, 409 }, - { 0xf209787b, 0xb47d6b84, 0xc0678c5d, 412 }, - { 0x9745eb4d, 0x50ce6332, 0xf840b7ba, 416 }, - { 0xbd176620, 0xa501fbff, 0xb650e5a9, 419 }, - { 0xec5d3fa8, 0xce427aff, 0xa3e51f13, 422 }, - { 0x93ba47c9, 0x80e98cdf, 0xc66f336c, 426 }, - { 0xb8a8d9bb, 0xe123f017, 0xb80b0047, 429 }, - { 0xe6d3102a, 0xd96cec1d, 0xa60dc059, 432 }, - { 0x9043ea1a, 0xc7e41392, 0x87c89837, 436 }, - { 0xb454e4a1, 0x79dd1877, 0x29babe45, 439 }, - { 0xe16a1dc9, 0xd8545e94, 0xf4296dd6, 442 }, - { 0x8ce2529e, 0x2734bb1d, 0x1899e4a6, 446 }, - { 0xb01ae745, 0xb101e9e4, 0x5ec05dcf, 449 }, - { 0xdc21a117, 0x1d42645d, 0x76707543, 452 }, - { 0x899504ae, 0x72497eba, 0x6a06494a, 456 }, - { 0xabfa45da, 0x0edbde69, 0x0487db9d, 459 }, - { 0xd6f8d750, 0x9292d603, 0x45a9d284, 462 }, - { 0x865b8692, 0x5b9bc5c2, 0x0b8a2392, 466 }, - { 0xa7f26836, 0xf282b732, 0x8e6cac77, 469 }, - { 0xd1ef0244, 0xaf2364ff, 0x3207d795, 472 }, - { 0x8335616a, 0xed761f1f, 0x7f44e6bd, 476 }, - { 0xa402b9c5, 0xa8d3a6e7, 0x5f16206c, 479 }, - { 0xcd036837, 0x130890a1, 0x36dba887, 482 }, - { 0x80222122, 0x6be55a64, 0xc2494954, 486 }, - { 0xa02aa96b, 0x06deb0fd, 0xf2db9baa, 489 }, - { 0xc83553c5, 0xc8965d3d, 0x6f928294, 492 }, - { 0xfa42a8b7, 0x3abbf48c, 0xcb772339, 495 }, - { 0x9c69a972, 0x84b578d7, 0xff2a7604, 499 }, - { 0xc38413cf, 0x25e2d70d, 0xfef51385, 502 }, - { 0xf46518c2, 0xef5b8cd1, 0x7eb25866, 505 }, - { 0x98bf2f79, 0xd5993802, 0xef2f773f, 509 }, - { 0xbeeefb58, 0x4aff8603, 0xaafb550f, 512 }, - { 0xeeaaba2e, 0x5dbf6784, 0x95ba2a53, 515 }, - { 0x952ab45c, 0xfa97a0b2, 0xdd945a74, 519 }, - { 0xba756174, 0x393d88df, 0x94f97111, 522 }, - { 0xe912b9d1, 0x478ceb17, 0x7a37cd56, 525 }, - { 0x91abb422, 0xccb812ee, 0xac62e055, 529 }, - { 0xb616a12b, 0x7fe617aa, 0x577b986b, 532 }, - { 0xe39c4976, 0x5fdf9d94, 0xed5a7e85, 535 }, - { 0x8e41ade9, 0xfbebc27d, 0x14588f13, 539 }, - { 0xb1d21964, 0x7ae6b31c, 0x596eb2d8, 542 }, - { 0xde469fbd, 0x99a05fe3, 0x6fca5f8e, 545 }, - { 0x8aec23d6, 0x80043bee, 0x25de7bb9, 549 }, - { 0xada72ccc, 0x20054ae9, 0xaf561aa7, 552 }, - { 0xd910f7ff, 0x28069da4, 0x1b2ba151, 555 }, - { 0x87aa9aff, 0x79042286, 0x90fb44d2, 559 }, - { 0xa99541bf, 0x57452b28, 0x353a1607, 562 }, - { 0xd3fa922f, 0x2d1675f2, 0x42889b89, 565 }, - { 0x847c9b5d, 0x7c2e09b7, 0x69956135, 569 }, - { 0xa59bc234, 0xdb398c25, 0x43fab983, 572 }, - { 0xcf02b2c2, 0x1207ef2e, 0x94f967e4, 575 }, - { 0x8161afb9, 0x4b44f57d, 0x1d1be0ee, 579 }, - { 0xa1ba1ba7, 0x9e1632dc, 0x6462d92a, 582 }, - { 0xca28a291, 0x859bbf93, 0x7d7b8f75, 585 }, - { 0xfcb2cb35, 0xe702af78, 0x5cda7352, 588 }, - { 0x9defbf01, 0xb061adab, 0x3a088813, 592 }, - { 0xc56baec2, 0x1c7a1916, 0x088aaa18, 595 }, - { 0xf6c69a72, 0xa3989f5b, 0x8aad549e, 598 }, - { 0x9a3c2087, 0xa63f6399, 0x36ac54e2, 602 }, - { 0xc0cb28a9, 0x8fcf3c7f, 0x84576a1b, 605 }, - { 0xf0fdf2d3, 0xf3c30b9f, 0x656d44a2, 608 }, - { 0x969eb7c4, 0x7859e743, 0x9f644ae5, 612 }, - { 0xbc4665b5, 0x96706114, 0x873d5d9f, 615 }, - { 0xeb57ff22, 0xfc0c7959, 0xa90cb506, 618 }, - { 0x9316ff75, 0xdd87cbd8, 0x09a7f124, 622 }, - { 0xb7dcbf53, 0x54e9bece, 0x0c11ed6d, 625 }, - { 0xe5d3ef28, 0x2a242e81, 0x8f1668c8, 628 }, - { 0x8fa47579, 0x1a569d10, 0xf96e017d, 632 }, - { 0xb38d92d7, 0x60ec4455, 0x37c981dc, 635 }, - { 0xe070f78d, 0x3927556a, 0x85bbe253, 638 }, - { 0x8c469ab8, 0x43b89562, 0x93956d74, 642 }, - { 0xaf584166, 0x54a6babb, 0x387ac8d1, 645 }, - { 0xdb2e51bf, 0xe9d0696a, 0x06997b05, 648 }, - { 0x88fcf317, 0xf22241e2, 0x441fece3, 652 }, - { 0xab3c2fdd, 0xeeaad25a, 0xd527e81c, 655 }, - { 0xd60b3bd5, 0x6a5586f1, 0x8a71e223, 658 }, - { 0x85c70565, 0x62757456, 0xf6872d56, 662 }, - { 0xa738c6be, 0xbb12d16c, 0xb428f8ac, 665 }, - { 0xd106f86e, 0x69d785c7, 0xe13336d7, 668 }, - { 0x82a45b45, 0x0226b39c, 0xecc00246, 672 }, - { 0xa34d7216, 0x42b06084, 0x27f002d7, 675 }, - { 0xcc20ce9b, 0xd35c78a5, 0x31ec038d, 678 }, - { 0xff290242, 0xc83396ce, 0x7e670471, 681 }, - { 0x9f79a169, 0xbd203e41, 0x0f0062c6, 685 }, - { 0xc75809c4, 0x2c684dd1, 0x52c07b78, 688 }, - { 0xf92e0c35, 0x37826145, 0xa7709a56, 691 }, - { 0x9bbcc7a1, 0x42b17ccb, 0x88a66076, 695 }, - { 0xc2abf989, 0x935ddbfe, 0x6acff893, 698 }, - { 0xf356f7eb, 0xf83552fe, 0x0583f6b8, 701 }, - { 0x98165af3, 0x7b2153de, 0xc3727a33, 705 }, - { 0xbe1bf1b0, 0x59e9a8d6, 0x744f18c0, 708 }, - { 0xeda2ee1c, 0x7064130c, 0x1162def0, 711 }, - { 0x9485d4d1, 0xc63e8be7, 0x8addcb56, 715 }, - { 0xb9a74a06, 0x37ce2ee1, 0x6d953e2b, 718 }, - { 0xe8111c87, 0xc5c1ba99, 0xc8fa8db6, 721 }, - { 0x910ab1d4, 0xdb9914a0, 0x1d9c9892, 725 }, - { 0xb54d5e4a, 0x127f59c8, 0x2503beb6, 728 }, - { 0xe2a0b5dc, 0x971f303a, 0x2e44ae64, 731 }, - { 0x8da471a9, 0xde737e24, 0x5ceaecfe, 735 }, - { 0xb10d8e14, 0x56105dad, 0x7425a83e, 738 }, - { 0xdd50f199, 0x6b947518, 0xd12f124e, 741 }, - { 0x8a5296ff, 0xe33cc92f, 0x82bd6b70, 745 }, - { 0xace73cbf, 0xdc0bfb7b, 0x636cc64d, 748 }, - { 0xd8210bef, 0xd30efa5a, 0x3c47f7e0, 751 }, - { 0x8714a775, 0xe3e95c78, 0x65acfaec, 755 }, - { 0xa8d9d153, 0x5ce3b396, 0x7f1839a7, 758 }, - { 0xd31045a8, 0x341ca07c, 0x1ede4811, 761 }, - { 0x83ea2b89, 0x2091e44d, 0x934aed0a, 765 }, - { 0xa4e4b66b, 0x68b65d60, 0xf81da84d, 768 }, - { 0xce1de406, 0x42e3f4b9, 0x36251260, 771 }, - { 0x80d2ae83, 0xe9ce78f3, 0xc1d72b7c, 775 }, - { 0xa1075a24, 0xe4421730, 0xb24cf65b, 778 }, - { 0xc94930ae, 0x1d529cfc, 0xdee033f2, 781 }, - { 0xfb9b7cd9, 0xa4a7443c, 0x169840ef, 784 }, - { 0x9d412e08, 0x06e88aa5, 0x8e1f2895, 788 }, - { 0xc491798a, 0x08a2ad4e, 0xf1a6f2ba, 791 }, - { 0xf5b5d7ec, 0x8acb58a2, 0xae10af69, 794 }, - { 0x9991a6f3, 0xd6bf1765, 0xacca6da1, 798 }, - { 0xbff610b0, 0xcc6edd3f, 0x17fd090a, 801 }, - { 0xeff394dc, 0xff8a948e, 0xddfc4b4c, 804 }, - { 0x95f83d0a, 0x1fb69cd9, 0x4abdaf10, 808 }, - { 0xbb764c4c, 0xa7a4440f, 0x9d6d1ad4, 811 }, - { 0xea53df5f, 0xd18d5513, 0x84c86189, 814 }, - { 0x92746b9b, 0xe2f8552c, 0x32fd3cf5, 818 }, - { 0xb7118682, 0xdbb66a77, 0x3fbc8c33, 821 }, - { 0xe4d5e823, 0x92a40515, 0x0fabaf3f, 824 }, - { 0x8f05b116, 0x3ba6832d, 0x29cb4d87, 828 }, - { 0xb2c71d5b, 0xca9023f8, 0x743e20e9, 831 }, - { 0xdf78e4b2, 0xbd342cf6, 0x914da924, 834 }, - { 0x8bab8eef, 0xb6409c1a, 0x1ad089b6, 838 }, - { 0xae9672ab, 0xa3d0c320, 0xa184ac24, 841 }, - { 0xda3c0f56, 0x8cc4f3e8, 0xc9e5d72d, 844 }, - { 0x88658996, 0x17fb1871, 0x7e2fa67c, 848 }, - { 0xaa7eebfb, 0x9df9de8d, 0xddbb901b, 851 }, - { 0xd51ea6fa, 0x85785631, 0x552a7422, 854 }, - { 0x8533285c, 0x936b35de, 0xd53a8895, 858 }, - { 0xa67ff273, 0xb8460356, 0x8a892aba, 861 }, - { 0xd01fef10, 0xa657842c, 0x2d2b7569, 864 }, - { 0x8213f56a, 0x67f6b29b, 0x9c3b2962, 868 }, - { 0xa298f2c5, 0x01f45f42, 0x8349f3ba, 871 }, - { 0xcb3f2f76, 0x42717713, 0x241c70a9, 874 }, - { 0xfe0efb53, 0xd30dd4d7, 0xed238cd3, 877 }, - { 0x9ec95d14, 0x63e8a506, 0xf4363804, 881 }, - { 0xc67bb459, 0x7ce2ce48, 0xb143c605, 884 }, - { 0xf81aa16f, 0xdc1b81da, 0xdd94b786, 887 }, - { 0x9b10a4e5, 0xe9913128, 0xca7cf2b4, 891 }, - { 0xc1d4ce1f, 0x63f57d72, 0xfd1c2f61, 894 }, - { 0xf24a01a7, 0x3cf2dccf, 0xbc633b39, 897 }, - { 0x976e4108, 0x8617ca01, 0xd5be0503, 901 }, - { 0xbd49d14a, 0xa79dbc82, 0x4b2d8644, 904 }, - { 0xec9c459d, 0x51852ba2, 0xddf8e7d6, 907 }, - { 0x93e1ab82, 0x52f33b45, 0xcabb90e5, 911 }, - { 0xb8da1662, 0xe7b00a17, 0x3d6a751f, 914 }, - { 0xe7109bfb, 0xa19c0c9d, 0x0cc51267, 917 }, - { 0x906a617d, 0x450187e2, 0x27fb2b80, 921 }, - { 0xb484f9dc, 0x9641e9da, 0xb1f9f660, 924 }, - { 0xe1a63853, 0xbbd26451, 0x5e7873f8, 927 }, - { 0x8d07e334, 0x55637eb2, 0xdb0b487b, 931 }, - { 0xb049dc01, 0x6abc5e5f, 0x91ce1a9a, 934 }, - { 0xdc5c5301, 0xc56b75f7, 0x7641a140, 937 }, - { 0x89b9b3e1, 0x1b6329ba, 0xa9e904c8, 941 }, - { 0xac2820d9, 0x623bf429, 0x546345fa, 944 }, - { 0xd732290f, 0xbacaf133, 0xa97c1779, 947 }, - { 0x867f59a9, 0xd4bed6c0, 0x49ed8eab, 951 }, - { 0xa81f3014, 0x49ee8c70, 0x5c68f256, 954 }, - { 0xd226fc19, 0x5c6a2f8c, 0x73832eec, 957 }, - { 0x83585d8f, 0xd9c25db7, 0xc831fd53, 961 }, - { 0xa42e74f3, 0xd032f525, 0xba3e7ca8, 964 }, - { 0xcd3a1230, 0xc43fb26f, 0x28ce1bd2, 967 }, - { 0x80444b5e, 0x7aa7cf85, 0x7980d163, 971 }, - { 0xa0555e36, 0x1951c366, 0xd7e105bc, 974 }, - { 0xc86ab5c3, 0x9fa63440, 0x8dd9472b, 977 }, - { 0xfa856334, 0x878fc150, 0xb14f98f6, 980 }, - { 0x9c935e00, 0xd4b9d8d2, 0x6ed1bf9a, 984 }, - { 0xc3b83581, 0x09e84f07, 0x0a862f80, 987 }, - { 0xf4a642e1, 0x4c6262c8, 0xcd27bb61, 990 }, - { 0x98e7e9cc, 0xcfbd7dbd, 0x8038d51c, 994 }, - { 0xbf21e440, 0x03acdd2c, 0xe0470a63, 997 }, - { 0xeeea5d50, 0x04981478, 0x1858ccfc, 1000 }, - { 0x95527a52, 0x02df0ccb, 0x0f37801e, 1004 }, - { 0xbaa718e6, 0x8396cffd, 0xd3056025, 1007 }, - { 0xe950df20, 0x247c83fd, 0x47c6b82e, 1010 }, - { 0x91d28b74, 0x16cdd27e, 0x4cdc331d, 1014 }, - { 0xb6472e51, 0x1c81471d, 0xe0133fe4, 1017 }, - { 0xe3d8f9e5, 0x63a198e5, 0x58180fdd, 1020 }, - { 0x8e679c2f, 0x5e44ff8f, 0x570f09ea, 1024 }, - { 0xb201833b, 0x35d63f73, 0x2cd2cc65, 1027 }, - { 0xde81e40a, 0x034bcf4f, 0xf8077f7e, 1030 }, - { 0x8b112e86, 0x420f6191, 0xfb04afaf, 1034 }, - { 0xadd57a27, 0xd29339f6, 0x79c5db9a, 1037 }, - { 0xd94ad8b1, 0xc7380874, 0x18375281, 1040 }, - { 0x87cec76f, 0x1c830548, 0x8f229391, 1044 }, - { 0xa9c2794a, 0xe3a3c69a, 0xb2eb3875, 1047 }, - { 0xd433179d, 0x9c8cb841, 0x5fa60692, 1050 }, - { 0x849feec2, 0x81d7f328, 0xdbc7c41b, 1054 }, - { 0xa5c7ea73, 0x224deff3, 0x12b9b522, 1057 }, - { 0xcf39e50f, 0xeae16bef, 0xd768226b, 1060 }, - { 0x81842f29, 0xf2cce375, 0xe6a11583, 1064 }, - { 0xa1e53af4, 0x6f801c53, 0x60495ae3, 1067 }, - { 0xca5e89b1, 0x8b602368, 0x385bb19c, 1070 }, - { 0xfcf62c1d, 0xee382c42, 0x46729e03, 1073 }, - { 0x9e19db92, 0xb4e31ba9, 0x6c07a2c2, 1077 } - }; - static short int Lhint[2098] = { - /*18,*/19, 19, 19, 19, 20, 20, 20, 21, 21, - 21, 22, 22, 22, 23, 23, 23, 23, 24, 24, - 24, 25, 25, 25, 26, 26, 26, 26, 27, 27, - 27, 28, 28, 28, 29, 29, 29, 29, 30, 30, - 30, 31, 31, 31, 32, 32, 32, 32, 33, 33, - 33, 34, 34, 34, 35, 35, 35, 35, 36, 36, - 36, 37, 37, 37, 38, 38, 38, 38, 39, 39, - 39, 40, 40, 40, 41, 41, 41, 41, 42, 42, - 42, 43, 43, 43, 44, 44, 44, 44, 45, 45, - 45, 46, 46, 46, 47, 47, 47, 47, 48, 48, - 48, 49, 49, 49, 50, 50, 50, 51, 51, 51, - 51, 52, 52, 52, 53, 53, 53, 54, 54, 54, - 54, 55, 55, 55, 56, 56, 56, 57, 57, 57, - 57, 58, 58, 58, 59, 59, 59, 60, 60, 60, - 60, 61, 61, 61, 62, 62, 62, 63, 63, 63, - 63, 64, 64, 64, 65, 65, 65, 66, 66, 66, - 66, 67, 67, 67, 68, 68, 68, 69, 69, 69, - 69, 70, 70, 70, 71, 71, 71, 72, 72, 72, - 72, 73, 73, 73, 74, 74, 74, 75, 75, 75, - 75, 76, 76, 76, 77, 77, 77, 78, 78, 78, - 78, 79, 79, 79, 80, 80, 80, 81, 81, 81, - 82, 82, 82, 82, 83, 83, 83, 84, 84, 84, - 85, 85, 85, 85, 86, 86, 86, 87, 87, 87, - 88, 88, 88, 88, 89, 89, 89, 90, 90, 90, - 91, 91, 91, 91, 92, 92, 92, 93, 93, 93, - 94, 94, 94, 94, 95, 95, 95, 96, 96, 96, - 97, 97, 97, 97, 98, 98, 98, 99, 99, 99, - 100, 100, 100, 100, 101, 101, 101, 102, 102, 102, - 103, 103, 103, 103, 104, 104, 104, 105, 105, 105, - 106, 106, 106, 106, 107, 107, 107, 108, 108, 108, - 109, 109, 109, 110, 110, 110, 110, 111, 111, 111, - 112, 112, 112, 113, 113, 113, 113, 114, 114, 114, - 115, 115, 115, 116, 116, 116, 116, 117, 117, 117, - 118, 118, 118, 119, 119, 119, 119, 120, 120, 120, - 121, 121, 121, 122, 122, 122, 122, 123, 123, 123, - 124, 124, 124, 125, 125, 125, 125, 126, 126, 126, - 127, 127, 127, 128, 128, 128, 128, 129, 129, 129, - 130, 130, 130, 131, 131, 131, 131, 132, 132, 132, - 133, 133, 133, 134, 134, 134, 134, 135, 135, 135, - 136, 136, 136, 137, 137, 137, 137, 138, 138, 138, - 139, 139, 139, 140, 140, 140, 141, 141, 141, 141, - 142, 142, 142, 143, 143, 143, 144, 144, 144, 144, - 145, 145, 145, 146, 146, 146, 147, 147, 147, 147, - 148, 148, 148, 149, 149, 149, 150, 150, 150, 150, - 151, 151, 151, 152, 152, 152, 153, 153, 153, 153, - 154, 154, 154, 155, 155, 155, 156, 156, 156, 156, - 157, 157, 157, 158, 158, 158, 159, 159, 159, 159, - 160, 160, 160, 161, 161, 161, 162, 162, 162, 162, - 163, 163, 163, 164, 164, 164, 165, 165, 165, 165, - 166, 166, 166, 167, 167, 167, 168, 168, 168, 169, - 169, 169, 169, 170, 170, 170, 171, 171, 171, 172, - 172, 172, 172, 173, 173, 173, 174, 174, 174, 175, - 175, 175, 175, 176, 176, 176, 177, 177, 177, 178, - 178, 178, 178, 179, 179, 179, 180, 180, 180, 181, - 181, 181, 181, 182, 182, 182, 183, 183, 183, 184, - 184, 184, 184, 185, 185, 185, 186, 186, 186, 187, - 187, 187, 187, 188, 188, 188, 189, 189, 189, 190, - 190, 190, 190, 191, 191, 191, 192, 192, 192, 193, - 193, 193, 193, 194, 194, 194, 195, 195, 195, 196, - 196, 196, 197, 197, 197, 197, 198, 198, 198, 199, - 199, 199, 200, 200, 200, 200, 201, 201, 201, 202, - 202, 202, 203, 203, 203, 203, 204, 204, 204, 205, - 205, 205, 206, 206, 206, 206, 207, 207, 207, 208, - 208, 208, 209, 209, 209, 209, 210, 210, 210, 211, - 211, 211, 212, 212, 212, 212, 213, 213, 213, 214, - 214, 214, 215, 215, 215, 215, 216, 216, 216, 217, - 217, 217, 218, 218, 218, 218, 219, 219, 219, 220, - 220, 220, 221, 221, 221, 221, 222, 222, 222, 223, - 223, 223, 224, 224, 224, 224, 225, 225, 225, 226, - 226, 226, 227, 227, 227, 228, 228, 228, 228, 229, - 229, 229, 230, 230, 230, 231, 231, 231, 231, 232, - 232, 232, 233, 233, 233, 234, 234, 234, 234, 235, - 235, 235, 236, 236, 236, 237, 237, 237, 237, 238, - 238, 238, 239, 239, 239, 240, 240, 240, 240, 241, - 241, 241, 242, 242, 242, 243, 243, 243, 243, 244, - 244, 244, 245, 245, 245, 246, 246, 246, 246, 247, - 247, 247, 248, 248, 248, 249, 249, 249, 249, 250, - 250, 250, 251, 251, 251, 252, 252, 252, 252, 253, - 253, 253, 254, 254, 254, 255, 255, 255, 256, 256, - 256, 256, 257, 257, 257, 258, 258, 258, 259, 259, - 259, 259, 260, 260, 260, 261, 261, 261, 262, 262, - 262, 262, 263, 263, 263, 264, 264, 264, 265, 265, - 265, 265, 266, 266, 266, 267, 267, 267, 268, 268, - 268, 268, 269, 269, 269, 270, 270, 270, 271, 271, - 271, 271, 272, 272, 272, 273, 273, 273, 274, 274, - 274, 274, 275, 275, 275, 276, 276, 276, 277, 277, - 277, 277, 278, 278, 278, 279, 279, 279, 280, 280, - 280, 280, 281, 281, 281, 282, 282, 282, 283, 283, - 283, 283, 284, 284, 284, 285, 285, 285, 286, 286, - 286, 287, 287, 287, 287, 288, 288, 288, 289, 289, - 289, 290, 290, 290, 290, 291, 291, 291, 292, 292, - 292, 293, 293, 293, 293, 294, 294, 294, 295, 295, - 295, 296, 296, 296, 296, 297, 297, 297, 298, 298, - 298, 299, 299, 299, 299, 300, 300, 300, 301, 301, - 301, 302, 302, 302, 302, 303, 303, 303, 304, 304, - 304, 305, 305, 305, 305, 306, 306, 306, 307, 307, - 307, 308, 308, 308, 308, 309, 309, 309, 310, 310, - 310, 311, 311, 311, 311, 312, 312, 312, 313, 313, - 313, 314, 314, 314, 315, 315, 315, 315, 316, 316, - 316, 317, 317, 317, 318, 318, 318, 318, 319, 319, - 319, 320, 320, 320, 321, 321, 321, 321, 322, 322, - 322, 323, 323, 323, 324, 324, 324, 324, 325, 325, - 325, 326, 326, 326, 327, 327, 327, 327, 328, 328, - 328, 329, 329, 329, 330, 330, 330, 330, 331, 331, - 331, 332, 332, 332, 333, 333, 333, 333, 334, 334, - 334, 335, 335, 335, 336, 336, 336, 336, 337, 337, - 337, 338, 338, 338, 339, 339, 339, 339, 340, 340, - 340, 341, 341, 341, 342, 342, 342, 342, 343, 343, - 343, 344, 344, 344, 345, 345, 345, 346, 346, 346, - 346, 347, 347, 347, 348, 348, 348, 349, 349, 349, - 349, 350, 350, 350, 351, 351, 351, 352, 352, 352, - 352, 353, 353, 353, 354, 354, 354, 355, 355, 355, - 355, 356, 356, 356, 357, 357, 357, 358, 358, 358, - 358, 359, 359, 359, 360, 360, 360, 361, 361, 361, - 361, 362, 362, 362, 363, 363, 363, 364, 364, 364, - 364, 365, 365, 365, 366, 366, 366, 367, 367, 367, - 367, 368, 368, 368, 369, 369, 369, 370, 370, 370, - 370, 371, 371, 371, 372, 372, 372, 373, 373, 373, - 374, 374, 374, 374, 375, 375, 375, 376, 376, 376, - 377, 377, 377, 377, 378, 378, 378, 379, 379, 379, - 380, 380, 380, 380, 381, 381, 381, 382, 382, 382, - 383, 383, 383, 383, 384, 384, 384, 385, 385, 385, - 386, 386, 386, 386, 387, 387, 387, 388, 388, 388, - 389, 389, 389, 389, 390, 390, 390, 391, 391, 391, - 392, 392, 392, 392, 393, 393, 393, 394, 394, 394, - 395, 395, 395, 395, 396, 396, 396, 397, 397, 397, - 398, 398, 398, 398, 399, 399, 399, 400, 400, 400, - 401, 401, 401, 402, 402, 402, 402, 403, 403, 403, - 404, 404, 404, 405, 405, 405, 405, 406, 406, 406, - 407, 407, 407, 408, 408, 408, 408, 409, 409, 409, - 410, 410, 410, 411, 411, 411, 411, 412, 412, 412, - 413, 413, 413, 414, 414, 414, 414, 415, 415, 415, - 416, 416, 416, 417, 417, 417, 417, 418, 418, 418, - 419, 419, 419, 420, 420, 420, 420, 421, 421, 421, - 422, 422, 422, 423, 423, 423, 423, 424, 424, 424, - 425, 425, 425, 426, 426, 426, 426, 427, 427, 427, - 428, 428, 428, 429, 429, 429, 429, 430, 430, 430, - 431, 431, 431, 432, 432, 432, 433, 433, 433, 433, - 434, 434, 434, 435, 435, 435, 436, 436, 436, 436, - 437, 437, 437, 438, 438, 438, 439, 439, 439, 439, - 440, 440, 440, 441, 441, 441, 442, 442, 442, 442, - 443, 443, 443, 444, 444, 444, 445, 445, 445, 445, - 446, 446, 446, 447, 447, 447, 448, 448, 448, 448, - 449, 449, 449, 450, 450, 450, 451, 451, 451, 451, - 452, 452, 452, 453, 453, 453, 454, 454, 454, 454, - 455, 455, 455, 456, 456, 456, 457, 457, 457, 457, - 458, 458, 458, 459, 459, 459, 460, 460, 460, 461, - 461, 461, 461, 462, 462, 462, 463, 463, 463, 464, - 464, 464, 464, 465, 465, 465, 466, 466, 466, 467, - 467, 467, 467, 468, 468, 468, 469, 469, 469, 470, - 470, 470, 470, 471, 471, 471, 472, 472, 472, 473, - 473, 473, 473, 474, 474, 474, 475, 475, 475, 476, - 476, 476, 476, 477, 477, 477, 478, 478, 478, 479, - 479, 479, 479, 480, 480, 480, 481, 481, 481, 482, - 482, 482, 482, 483, 483, 483, 484, 484, 484, 485, - 485, 485, 485, 486, 486, 486, 487, 487, 487, 488, - 488, 488, 488, 489, 489, 489, 490, 490, 490, 491, - 491, 491, 492, 492, 492, 492, 493, 493, 493, 494, - 494, 494, 495, 495, 495, 495, 496, 496, 496, 497, - 497, 497, 498, 498, 498, 498, 499, 499, 499, 500, - 500, 500, 501, 501, 501, 501, 502, 502, 502, 503, - 503, 503, 504, 504, 504, 504, 505, 505, 505, 506, - 506, 506, 507, 507, 507, 507, 508, 508, 508, 509, - 509, 509, 510, 510, 510, 510, 511, 511, 511, 512, - 512, 512, 513, 513, 513, 513, 514, 514, 514, 515, - 515, 515, 516, 516, 516, 516, 517, 517, 517, 518, - 518, 518, 519, 519, 519, 520, 520, 520, 520, 521, - 521, 521, 522, 522, 522, 523, 523, 523, 523, 524, - 524, 524, 525, 525, 525, 526, 526, 526, 526, 527, - 527, 527, 528, 528, 528, 529, 529, 529, 529, 530, - 530, 530, 531, 531, 531, 532, 532, 532, 532, 533, - 533, 533, 534, 534, 534, 535, 535, 535, 535, 536, - 536, 536, 537, 537, 537, 538, 538, 538, 538, 539, - 539, 539, 540, 540, 540, 541, 541, 541, 541, 542, - 542, 542, 543, 543, 543, 544, 544, 544, 544, 545, - 545, 545, 546, 546, 546, 547, 547, 547, 548, 548, - 548, 548, 549, 549, 549, 550, 550, 550, 551, 551, - 551, 551, 552, 552, 552, 553, 553, 553, 554, 554, - 554, 554, 555, 555, 555, 556, 556, 556, 557, 557, - 557, 557, 558, 558, 558, 559, 559, 559, 560, 560, - 560, 560, 561, 561, 561, 562, 562, 562, 563, 563, - 563, 563, 564, 564, 564, 565, 565, 565, 566, 566, - 566, 566, 567, 567, 567, 568, 568, 568, 569, 569, - 569, 569, 570, 570, 570, 571, 571, 571, 572, 572, - 572, 572, 573, 573, 573, 574, 574, 574, 575, 575, - 575, 575, 576, 576, 576, 577, 577, 577, 578, 578, - 578, 579, 579, 579, 579, 580, 580, 580, 581, 581, - 581, 582, 582, 582, 582, 583, 583, 583, 584, 584, - 584, 585, 585, 585, 585, 586, 586, 586, 587, 587, - 587, 588, 588, 588, 588, 589, 589, 589, 590, 590, - 590, 591, 591, 591, 591, 592, 592, 592, 593, 593, - 593, 594, 594, 594, 594, 595, 595, 595, 596, 596, - 596, 597, 597, 597, 597, 598, 598, 598, 599, 599, - 599, 600, 600, 600, 600, 601, 601, 601, 602, 602, - 602, 603, 603, 603, 603, 604, 604, 604, 605, 605, - 605, 606, 606, 606, 607, 607, 607, 607, 608, 608, - 608, 609, 609, 609, 610, 610, 610, 610, 611, 611, - 611, 612, 612, 612, 613, 613, 613, 613, 614, 614, - 614, 615, 615, 615, 616, 616, 616, 616, 617, 617, - 617, 618, 618, 618, 619, 619, 619, 619, 620, 620, - 620, 621, 621, 621, 622, 622, 622, 622, 623, 623, - 623, 624, 624, 624, 625, 625, 625, 625, 626, 626, - 626, 627, 627, 627, 628, 628, 628, 628, 629, 629, - 629, 630, 630, 630, 631, 631, 631, 631, 632, 632, - 632, 633, 633, 633, 634, 634, 634, 634, 635, 635, - 635, 636, 636, 636, 637, 637, 637, 638, 638, 638, - 638, 639, 639, 639, 640, 640, 640, 641, 641, 641, - 641, 642, 642, 642, 643, 643, 643, 644, 644, 644, - 644, 645, 645, 645, 646, 646, 646, 647, 647, 647, - 647, 648, 648, 648, 649, 649, 649, 650, 650 }; - static ULLong pfive[27] = { - 5ll, - 25ll, - 125ll, - 625ll, - 3125ll, - 15625ll, - 78125ll, - 390625ll, - 1953125ll, - 9765625ll, - 48828125ll, - 244140625ll, - 1220703125ll, - 6103515625ll, - 30517578125ll, - 152587890625ll, - 762939453125ll, - 3814697265625ll, - 19073486328125ll, - 95367431640625ll, - 476837158203125ll, - 2384185791015625ll, - 11920928955078125ll, - 59604644775390625ll, - 298023223876953125ll, - 1490116119384765625ll, - 7450580596923828125ll - }; - - static int pfivebits[25] = {3, 5, 7, 10, 12, 14, 17, 19, 21, 24, 26, 28, 31, - 33, 35, 38, 40, 42, 45, 47, 49, 52, 54, 56, 59}; -#endif /*}*/ -#endif /*}} NO_LONG_LONG */ - -typedef union { double d; ULong L[2]; -#ifdef USE_BF96 - ULLong LL; -#endif - } U; - -#ifdef IEEE_8087 -#define word0(x) (x)->L[1] -#define word1(x) (x)->L[0] -#else -#define word0(x) (x)->L[0] -#define word1(x) (x)->L[1] -#endif -#define dval(x) (x)->d -#define LLval(x) (x)->LL - -#ifndef STRTOD_DIGLIM -#define STRTOD_DIGLIM 40 -#endif - -#ifdef DIGLIM_DEBUG -extern int strtod_diglim; -#else -#define strtod_diglim STRTOD_DIGLIM -#endif - -/* The following definition of Storeinc is appropriate for MIPS processors. - * An alternative that might be better on some machines is - * #define Storeinc(a,b,c) (*a++ = b << 16 | c & 0xffff) - */ -#if defined(IEEE_8087) + defined(VAX) -#define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \ -((unsigned short *)a)[0] = (unsigned short)c, a++) -#else -#define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \ -((unsigned short *)a)[1] = (unsigned short)c, a++) -#endif - -/* #define P DBL_MANT_DIG */ -/* Ten_pmax = floor(P*log(2)/log(5)) */ -/* Bletch = (highest power of 2 < DBL_MAX_10_EXP) / 16 */ -/* Quick_max = floor((P-1)*log(FLT_RADIX)/log(10) - 1) */ -/* Int_max = floor(P*log(FLT_RADIX)/log(10) - 1) */ - -#ifdef IEEE_Arith -#define Exp_shift 20 -#define Exp_shift1 20 -#define Exp_msk1 0x100000 -#define Exp_msk11 0x100000 -#define Exp_mask 0x7ff00000 -#define P 53 -#define Nbits 53 -#define Bias 1023 -#define Emax 1023 -#define Emin (-1022) -#define Exp_1 0x3ff00000 -#define Exp_11 0x3ff00000 -#define Ebits 11 -#define Frac_mask 0xfffff -#define Frac_mask1 0xfffff -#define Ten_pmax 22 -#define Bletch 0x10 -#define Bndry_mask 0xfffff -#define Bndry_mask1 0xfffff -#define LSB 1 -#define Sign_bit 0x80000000 -#define Log2P 1 -#define Tiny0 0 -#define Tiny1 1 -#define Quick_max 14 -#define Int_max 14 -#ifndef NO_IEEE_Scale -#define Avoid_Underflow -#ifdef Flush_Denorm /* debugging option */ -#undef Sudden_Underflow -#endif -#endif - -#ifndef Flt_Rounds -#ifdef FLT_ROUNDS -#define Flt_Rounds FLT_ROUNDS -#else -#define Flt_Rounds 1 -#endif -#endif /*Flt_Rounds*/ - -#ifdef Honor_FLT_ROUNDS -#undef Check_FLT_ROUNDS -#define Check_FLT_ROUNDS -#else -#define Rounding Flt_Rounds -#endif - -#else /* ifndef IEEE_Arith */ -#undef Check_FLT_ROUNDS -#undef Honor_FLT_ROUNDS -#undef SET_INEXACT -#undef Sudden_Underflow -#define Sudden_Underflow -#ifdef IBM -#undef Flt_Rounds -#define Flt_Rounds 0 -#define Exp_shift 24 -#define Exp_shift1 24 -#define Exp_msk1 0x1000000 -#define Exp_msk11 0x1000000 -#define Exp_mask 0x7f000000 -#define P 14 -#define Nbits 56 -#define Bias 65 -#define Emax 248 -#define Emin (-260) -#define Exp_1 0x41000000 -#define Exp_11 0x41000000 -#define Ebits 8 /* exponent has 7 bits, but 8 is the right value in b2d */ -#define Frac_mask 0xffffff -#define Frac_mask1 0xffffff -#define Bletch 4 -#define Ten_pmax 22 -#define Bndry_mask 0xefffff -#define Bndry_mask1 0xffffff -#define LSB 1 -#define Sign_bit 0x80000000 -#define Log2P 4 -#define Tiny0 0x100000 -#define Tiny1 0 -#define Quick_max 14 -#define Int_max 15 -#else /* VAX */ -#undef Flt_Rounds -#define Flt_Rounds 1 -#define Exp_shift 23 -#define Exp_shift1 7 -#define Exp_msk1 0x80 -#define Exp_msk11 0x800000 -#define Exp_mask 0x7f80 -#define P 56 -#define Nbits 56 -#define Bias 129 -#define Emax 126 -#define Emin (-129) -#define Exp_1 0x40800000 -#define Exp_11 0x4080 -#define Ebits 8 -#define Frac_mask 0x7fffff -#define Frac_mask1 0xffff007f -#define Ten_pmax 24 -#define Bletch 2 -#define Bndry_mask 0xffff007f -#define Bndry_mask1 0xffff007f -#define LSB 0x10000 -#define Sign_bit 0x8000 -#define Log2P 1 -#define Tiny0 0x80 -#define Tiny1 0 -#define Quick_max 15 -#define Int_max 15 -#endif /* IBM, VAX */ -#endif /* IEEE_Arith */ - -#ifndef IEEE_Arith -#define ROUND_BIASED -#else -#ifdef ROUND_BIASED_without_Round_Up -#undef ROUND_BIASED -#define ROUND_BIASED -#endif -#endif - -#ifdef RND_PRODQUOT -#define rounded_product(a,b) a = rnd_prod(a, b) -#define rounded_quotient(a,b) a = rnd_quot(a, b) -extern double rnd_prod(double, double), rnd_quot(double, double); -#else -#define rounded_product(a,b) a *= b -#define rounded_quotient(a,b) a /= b -#endif - -#define Big0 (Frac_mask1 | Exp_msk1*(DBL_MAX_EXP+Bias-1)) -#define Big1 0xffffffff - -#ifndef Pack_32 -#define Pack_32 -#endif - -typedef struct BCinfo BCinfo; - struct -BCinfo { int dp0, dp1, dplen, dsign, e0, inexact, nd, nd0, rounding, scale, uflchk; }; - -#define FFFFFFFF 0xffffffffUL - -#ifdef MULTIPLE_THREADS -#define MTa , PTI -#define MTb , &TI -#define MTd , ThInfo **PTI -static unsigned int maxthreads = 0; -#else -#define MTa /*nothing*/ -#define MTb /*nothing*/ -#define MTd /*nothing*/ -#endif - -#define Kmax 7 - -#ifdef __cplusplus -extern "C" double strtod(const char *s00, char **se); -extern "C" char *dtoa(double d, int mode, int ndigits, - int *decpt, int *sign, char **rve); -#endif - - struct -Bigint { - struct Bigint *next; - int k, maxwds, sign, wds; - ULong x[1]; - }; - - typedef struct Bigint Bigint; - typedef struct -ThInfo { - Bigint *Freelist[Kmax+1]; - Bigint *P5s; - } ThInfo; - - static ThInfo TI0; - -#ifdef MULTIPLE_THREADS - static ThInfo *TI1; - static int TI0_used; - - void -set_max_dtoa_threads(unsigned int n) -{ - size_t L; - - if (n > maxthreads) { - L = n*sizeof(ThInfo); - if (TI1) { - TI1 = (ThInfo*)REALLOC(TI1, L); - memset(TI1 + maxthreads, 0, (n-maxthreads)*sizeof(ThInfo)); - } - else { - TI1 = (ThInfo*)MALLOC(L); - if (TI0_used) { - memcpy(TI1, &TI0, sizeof(ThInfo)); - if (n > 1) - memset(TI1 + 1, 0, L - sizeof(ThInfo)); - memset(&TI0, 0, sizeof(ThInfo)); - } - else - memset(TI1, 0, L); - } - maxthreads = n; - } - } - - static ThInfo* -get_TI(void) -{ - unsigned int thno = dtoa_get_threadno(); - if (thno < maxthreads) - return TI1 + thno; - if (thno == 0) - TI0_used = 1; - return &TI0; - } -#define freelist TI->Freelist -#define p5s TI->P5s -#else -#define freelist TI0.Freelist -#define p5s TI0.P5s -#endif - - static Bigint * -Balloc(int k MTd) -{ - int x; - Bigint *rv; -#ifndef Omit_Private_Memory - unsigned int len; -#endif -#ifdef MULTIPLE_THREADS - ThInfo *TI; - - if (!(TI = *PTI)) - *PTI = TI = get_TI(); - if (TI == &TI0) - ACQUIRE_DTOA_LOCK(0); -#endif - /* The k > Kmax case does not need ACQUIRE_DTOA_LOCK(0), */ - /* but this case seems very unlikely. */ - if (k <= Kmax && (rv = freelist[k])) - freelist[k] = rv->next; - else { - x = 1 << k; -#ifdef Omit_Private_Memory - rv = (Bigint *)MALLOC(sizeof(Bigint) + (x-1)*sizeof(ULong)); -#else - len = (sizeof(Bigint) + (x-1)*sizeof(ULong) + sizeof(double) - 1) - /sizeof(double); - if (k <= Kmax && pmem_next - private_mem + len <= PRIVATE_mem -#ifdef MULTIPLE_THREADS - && TI == TI1 -#endif - ) { - rv = (Bigint*)pmem_next; - pmem_next += len; - } - else - rv = (Bigint*)MALLOC(len*sizeof(double)); -#endif - rv->k = k; - rv->maxwds = x; - } -#ifdef MULTIPLE_THREADS - if (TI == &TI0) - FREE_DTOA_LOCK(0); -#endif - rv->sign = rv->wds = 0; - return rv; - } - - static void -Bfree(Bigint *v MTd) -{ -#ifdef MULTIPLE_THREADS - ThInfo *TI; -#endif - if (v) { - if (v->k > Kmax) - FREE((void*)v); - else { -#ifdef MULTIPLE_THREADS - if (!(TI = *PTI)) - *PTI = TI = get_TI(); - if (TI == &TI0) - ACQUIRE_DTOA_LOCK(0); -#endif - v->next = freelist[v->k]; - freelist[v->k] = v; -#ifdef MULTIPLE_THREADS - if (TI == &TI0) - FREE_DTOA_LOCK(0); -#endif - } - } - } - -#define Bcopy(x,y) memcpy((char *)&x->sign, (char *)&y->sign, \ -y->wds*sizeof(Long) + 2*sizeof(int)) - - static Bigint * -multadd(Bigint *b, int m, int a MTd) /* multiply by m and add a */ -{ - int i, wds; -#ifdef ULLong - ULong *x; - ULLong carry, y; -#else - ULong carry, *x, y; -#ifdef Pack_32 - ULong xi, z; -#endif -#endif - Bigint *b1; - - wds = b->wds; - x = b->x; - i = 0; - carry = a; - do { -#ifdef ULLong - y = *x * (ULLong)m + carry; - carry = y >> 32; - *x++ = y & FFFFFFFF; -#else -#ifdef Pack_32 - xi = *x; - y = (xi & 0xffff) * m + carry; - z = (xi >> 16) * m + (y >> 16); - carry = z >> 16; - *x++ = (z << 16) + (y & 0xffff); -#else - y = *x * m + carry; - carry = y >> 16; - *x++ = y & 0xffff; -#endif -#endif - } - while(++i < wds); - if (carry) { - if (wds >= b->maxwds) { - b1 = Balloc(b->k+1 MTa); - Bcopy(b1, b); - Bfree(b MTa); - b = b1; - } - b->x[wds++] = carry; - b->wds = wds; - } - return b; - } - - static Bigint * -s2b(const char *s, int nd0, int nd, ULong y9, int dplen MTd) -{ - Bigint *b; - int i, k; - Long x, y; - - x = (nd + 8) / 9; - for(k = 0, y = 1; x > y; y <<= 1, k++) ; -#ifdef Pack_32 - b = Balloc(k MTa); - b->x[0] = y9; - b->wds = 1; -#else - b = Balloc(k+1 MTa); - b->x[0] = y9 & 0xffff; - b->wds = (b->x[1] = y9 >> 16) ? 2 : 1; -#endif - - i = 9; - if (9 < nd0) { - s += 9; - do b = multadd(b, 10, *s++ - '0' MTa); - while(++i < nd0); - s += dplen; - } - else - s += dplen + 9; - for(; i < nd; i++) - b = multadd(b, 10, *s++ - '0' MTa); - return b; - } - - static int -hi0bits(ULong x) -{ - int k = 0; - - if (!(x & 0xffff0000)) { - k = 16; - x <<= 16; - } - if (!(x & 0xff000000)) { - k += 8; - x <<= 8; - } - if (!(x & 0xf0000000)) { - k += 4; - x <<= 4; - } - if (!(x & 0xc0000000)) { - k += 2; - x <<= 2; - } - if (!(x & 0x80000000)) { - k++; - if (!(x & 0x40000000)) - return 32; - } - return k; - } - - static int -lo0bits(ULong *y) -{ - int k; - ULong x = *y; - - if (x & 7) { - if (x & 1) - return 0; - if (x & 2) { - *y = x >> 1; - return 1; - } - *y = x >> 2; - return 2; - } - k = 0; - if (!(x & 0xffff)) { - k = 16; - x >>= 16; - } - if (!(x & 0xff)) { - k += 8; - x >>= 8; - } - if (!(x & 0xf)) { - k += 4; - x >>= 4; - } - if (!(x & 0x3)) { - k += 2; - x >>= 2; - } - if (!(x & 1)) { - k++; - x >>= 1; - if (!x) - return 32; - } - *y = x; - return k; - } - - static Bigint * -i2b(int i MTd) -{ - Bigint *b; - - b = Balloc(1 MTa); - b->x[0] = i; - b->wds = 1; - return b; - } - - static Bigint * -mult(Bigint *a, Bigint *b MTd) -{ - Bigint *c; - int k, wa, wb, wc; - ULong *x, *xa, *xae, *xb, *xbe, *xc, *xc0; - ULong y; -#ifdef ULLong - ULLong carry, z; -#else - ULong carry, z; -#ifdef Pack_32 - ULong z2; -#endif -#endif - - if (a->wds < b->wds) { - c = a; - a = b; - b = c; - } - k = a->k; - wa = a->wds; - wb = b->wds; - wc = wa + wb; - if (wc > a->maxwds) - k++; - c = Balloc(k MTa); - for(x = c->x, xa = x + wc; x < xa; x++) - *x = 0; - xa = a->x; - xae = xa + wa; - xb = b->x; - xbe = xb + wb; - xc0 = c->x; -#ifdef ULLong - for(; xb < xbe; xc0++) { - if ((y = *xb++)) { - x = xa; - xc = xc0; - carry = 0; - do { - z = *x++ * (ULLong)y + *xc + carry; - carry = z >> 32; - *xc++ = z & FFFFFFFF; - } - while(x < xae); - *xc = carry; - } - } -#else -#ifdef Pack_32 - for(; xb < xbe; xb++, xc0++) { - if (y = *xb & 0xffff) { - x = xa; - xc = xc0; - carry = 0; - do { - z = (*x & 0xffff) * y + (*xc & 0xffff) + carry; - carry = z >> 16; - z2 = (*x++ >> 16) * y + (*xc >> 16) + carry; - carry = z2 >> 16; - Storeinc(xc, z2, z); - } - while(x < xae); - *xc = carry; - } - if (y = *xb >> 16) { - x = xa; - xc = xc0; - carry = 0; - z2 = *xc; - do { - z = (*x & 0xffff) * y + (*xc >> 16) + carry; - carry = z >> 16; - Storeinc(xc, z, z2); - z2 = (*x++ >> 16) * y + (*xc & 0xffff) + carry; - carry = z2 >> 16; - } - while(x < xae); - *xc = z2; - } - } -#else - for(; xb < xbe; xc0++) { - if (y = *xb++) { - x = xa; - xc = xc0; - carry = 0; - do { - z = *x++ * y + *xc + carry; - carry = z >> 16; - *xc++ = z & 0xffff; - } - while(x < xae); - *xc = carry; - } - } -#endif -#endif - for(xc0 = c->x, xc = xc0 + wc; wc > 0 && !*--xc; --wc) ; - c->wds = wc; - return c; - } - - static Bigint * -pow5mult(Bigint *b, int k MTd) -{ - Bigint *b1, *p5, *p51; -#ifdef MULTIPLE_THREADS - ThInfo *TI; -#endif - int i; - static int p05[3] = { 5, 25, 125 }; - - if ((i = k & 3)) - b = multadd(b, p05[i-1], 0 MTa); - - if (!(k >>= 2)) - return b; -#ifdef MULTIPLE_THREADS - if (!(TI = *PTI)) - *PTI = TI = get_TI(); -#endif - if (!(p5 = p5s)) { - /* first time */ -#ifdef MULTIPLE_THREADS - if (!(TI = *PTI)) - *PTI = TI = get_TI(); - if (TI == &TI0) - ACQUIRE_DTOA_LOCK(1); - if (!(p5 = p5s)) { - p5 = p5s = i2b(625 MTa); - p5->next = 0; - } - if (TI == &TI0) - FREE_DTOA_LOCK(1); -#else - p5 = p5s = i2b(625 MTa); - p5->next = 0; -#endif - } - for(;;) { - if (k & 1) { - b1 = mult(b, p5 MTa); - Bfree(b MTa); - b = b1; - } - if (!(k >>= 1)) - break; - if (!(p51 = p5->next)) { -#ifdef MULTIPLE_THREADS - if (!TI && !(TI = *PTI)) - *PTI = TI = get_TI(); - if (TI == &TI0) - ACQUIRE_DTOA_LOCK(1); - if (!(p51 = p5->next)) { - p51 = p5->next = mult(p5,p5 MTa); - p51->next = 0; - } - if (TI == &TI0) - FREE_DTOA_LOCK(1); -#else - p51 = p5->next = mult(p5,p5); - p51->next = 0; -#endif - } - p5 = p51; - } - return b; - } - - static Bigint * -lshift(Bigint *b, int k MTd) -{ - int i, k1, n, n1; - Bigint *b1; - ULong *x, *x1, *xe, z; - -#ifdef Pack_32 - n = k >> 5; -#else - n = k >> 4; -#endif - k1 = b->k; - n1 = n + b->wds + 1; - for(i = b->maxwds; n1 > i; i <<= 1) - k1++; - b1 = Balloc(k1 MTa); - x1 = b1->x; - for(i = 0; i < n; i++) - *x1++ = 0; - x = b->x; - xe = x + b->wds; -#ifdef Pack_32 - if (k &= 0x1f) { - k1 = 32 - k; - z = 0; - do { - *x1++ = *x << k | z; - z = *x++ >> k1; - } - while(x < xe); - if ((*x1 = z)) - ++n1; - } -#else - if (k &= 0xf) { - k1 = 16 - k; - z = 0; - do { - *x1++ = *x << k & 0xffff | z; - z = *x++ >> k1; - } - while(x < xe); - if (*x1 = z) - ++n1; - } -#endif - else do - *x1++ = *x++; - while(x < xe); - b1->wds = n1 - 1; - Bfree(b MTa); - return b1; - } - - static int -cmp(Bigint *a, Bigint *b) -{ - ULong *xa, *xa0, *xb, *xb0; - int i, j; - - i = a->wds; - j = b->wds; -#ifdef DEBUG - if (i > 1 && !a->x[i-1]) - Bug("cmp called with a->x[a->wds-1] == 0"); - if (j > 1 && !b->x[j-1]) - Bug("cmp called with b->x[b->wds-1] == 0"); -#endif - if (i -= j) - return i; - xa0 = a->x; - xa = xa0 + j; - xb0 = b->x; - xb = xb0 + j; - for(;;) { - if (*--xa != *--xb) - return *xa < *xb ? -1 : 1; - if (xa <= xa0) - break; - } - return 0; - } - - static Bigint * -diff(Bigint *a, Bigint *b MTd) -{ - Bigint *c; - int i, wa, wb; - ULong *xa, *xae, *xb, *xbe, *xc; -#ifdef ULLong - ULLong borrow, y; -#else - ULong borrow, y; -#ifdef Pack_32 - ULong z; -#endif -#endif - - i = cmp(a,b); - if (!i) { - c = Balloc(0 MTa); - c->wds = 1; - c->x[0] = 0; - return c; - } - if (i < 0) { - c = a; - a = b; - b = c; - i = 1; - } - else - i = 0; - c = Balloc(a->k MTa); - c->sign = i; - wa = a->wds; - xa = a->x; - xae = xa + wa; - wb = b->wds; - xb = b->x; - xbe = xb + wb; - xc = c->x; - borrow = 0; -#ifdef ULLong - do { - y = (ULLong)*xa++ - *xb++ - borrow; - borrow = y >> 32 & (ULong)1; - *xc++ = y & FFFFFFFF; - } - while(xb < xbe); - while(xa < xae) { - y = *xa++ - borrow; - borrow = y >> 32 & (ULong)1; - *xc++ = y & FFFFFFFF; - } -#else -#ifdef Pack_32 - do { - y = (*xa & 0xffff) - (*xb & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - z = (*xa++ >> 16) - (*xb++ >> 16) - borrow; - borrow = (z & 0x10000) >> 16; - Storeinc(xc, z, y); - } - while(xb < xbe); - while(xa < xae) { - y = (*xa & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - z = (*xa++ >> 16) - borrow; - borrow = (z & 0x10000) >> 16; - Storeinc(xc, z, y); - } -#else - do { - y = *xa++ - *xb++ - borrow; - borrow = (y & 0x10000) >> 16; - *xc++ = y & 0xffff; - } - while(xb < xbe); - while(xa < xae) { - y = *xa++ - borrow; - borrow = (y & 0x10000) >> 16; - *xc++ = y & 0xffff; - } -#endif -#endif - while(!*--xc) - wa--; - c->wds = wa; - return c; - } - - static double -ulp(U *x) -{ - Long L; - U u; - - L = (word0(x) & Exp_mask) - (P-1)*Exp_msk1; -#ifndef Avoid_Underflow -#ifndef Sudden_Underflow - if (L > 0) { -#endif -#endif -#ifdef IBM - L |= Exp_msk1 >> 4; -#endif - word0(&u) = L; - word1(&u) = 0; -#ifndef Avoid_Underflow -#ifndef Sudden_Underflow - } - else { - L = -L >> Exp_shift; - if (L < Exp_shift) { - word0(&u) = 0x80000 >> L; - word1(&u) = 0; - } - else { - word0(&u) = 0; - L -= Exp_shift; - word1(&u) = L >= 31 ? 1 : 1 << 31 - L; - } - } -#endif -#endif - return dval(&u); - } - - static double -b2d(Bigint *a, int *e) -{ - ULong *xa, *xa0, w, y, z; - int k; - U d; -#ifdef VAX - ULong d0, d1; -#else -#define d0 word0(&d) -#define d1 word1(&d) -#endif - - xa0 = a->x; - xa = xa0 + a->wds; - y = *--xa; -#ifdef DEBUG - if (!y) Bug("zero y in b2d"); -#endif - k = hi0bits(y); - *e = 32 - k; -#ifdef Pack_32 - if (k < Ebits) { - d0 = Exp_1 | y >> (Ebits - k); - w = xa > xa0 ? *--xa : 0; - d1 = y << ((32-Ebits) + k) | w >> (Ebits - k); - goto ret_d; - } - z = xa > xa0 ? *--xa : 0; - if (k -= Ebits) { - d0 = Exp_1 | y << k | z >> (32 - k); - y = xa > xa0 ? *--xa : 0; - d1 = z << k | y >> (32 - k); - } - else { - d0 = Exp_1 | y; - d1 = z; - } -#else - if (k < Ebits + 16) { - z = xa > xa0 ? *--xa : 0; - d0 = Exp_1 | y << k - Ebits | z >> Ebits + 16 - k; - w = xa > xa0 ? *--xa : 0; - y = xa > xa0 ? *--xa : 0; - d1 = z << k + 16 - Ebits | w << k - Ebits | y >> 16 + Ebits - k; - goto ret_d; - } - z = xa > xa0 ? *--xa : 0; - w = xa > xa0 ? *--xa : 0; - k -= Ebits + 16; - d0 = Exp_1 | y << k + 16 | z << k | w >> 16 - k; - y = xa > xa0 ? *--xa : 0; - d1 = w << k + 16 | y << k; -#endif - ret_d: -#ifdef VAX - word0(&d) = d0 >> 16 | d0 << 16; - word1(&d) = d1 >> 16 | d1 << 16; -#else -#undef d0 -#undef d1 -#endif - return dval(&d); - } - - static Bigint * -d2b(U *d, int *e, int *bits MTd) -{ - Bigint *b; - int de, k; - ULong *x, y, z; -#ifndef Sudden_Underflow - int i; -#endif -#ifdef VAX - ULong d0, d1; - d0 = word0(d) >> 16 | word0(d) << 16; - d1 = word1(d) >> 16 | word1(d) << 16; -#else -#define d0 word0(d) -#define d1 word1(d) -#endif - -#ifdef Pack_32 - b = Balloc(1 MTa); -#else - b = Balloc(2 MTa); -#endif - x = b->x; - - z = d0 & Frac_mask; - d0 &= 0x7fffffff; /* clear sign bit, which we ignore */ -#ifdef Sudden_Underflow - de = (int)(d0 >> Exp_shift); -#ifndef IBM - z |= Exp_msk11; -#endif -#else - if ((de = (int)(d0 >> Exp_shift))) - z |= Exp_msk1; -#endif -#ifdef Pack_32 - if ((y = d1)) { - if ((k = lo0bits(&y))) { - x[0] = y | z << (32 - k); - z >>= k; - } - else - x[0] = y; -#ifndef Sudden_Underflow - i = -#endif - b->wds = (x[1] = z) ? 2 : 1; - } - else { - k = lo0bits(&z); - x[0] = z; -#ifndef Sudden_Underflow - i = -#endif - b->wds = 1; - k += 32; - } -#else - if (y = d1) { - if (k = lo0bits(&y)) - if (k >= 16) { - x[0] = y | z << 32 - k & 0xffff; - x[1] = z >> k - 16 & 0xffff; - x[2] = z >> k; - i = 2; - } - else { - x[0] = y & 0xffff; - x[1] = y >> 16 | z << 16 - k & 0xffff; - x[2] = z >> k & 0xffff; - x[3] = z >> k+16; - i = 3; - } - else { - x[0] = y & 0xffff; - x[1] = y >> 16; - x[2] = z & 0xffff; - x[3] = z >> 16; - i = 3; - } - } - else { -#ifdef DEBUG - if (!z) - Bug("Zero passed to d2b"); -#endif - k = lo0bits(&z); - if (k >= 16) { - x[0] = z; - i = 0; - } - else { - x[0] = z & 0xffff; - x[1] = z >> 16; - i = 1; - } - k += 32; - } - while(!x[i]) - --i; - b->wds = i + 1; -#endif -#ifndef Sudden_Underflow - if (de) { -#endif -#ifdef IBM - *e = (de - Bias - (P-1) << 2) + k; - *bits = 4*P + 8 - k - hi0bits(word0(d) & Frac_mask); -#else - *e = de - Bias - (P-1) + k; - *bits = P - k; -#endif -#ifndef Sudden_Underflow - } - else { - *e = de - Bias - (P-1) + 1 + k; -#ifdef Pack_32 - *bits = 32*i - hi0bits(x[i-1]); -#else - *bits = (i+2)*16 - hi0bits(x[i]); -#endif - } -#endif - return b; - } -#undef d0 -#undef d1 - - static double -ratio(Bigint *a, Bigint *b) -{ - U da, db; - int k, ka, kb; - - dval(&da) = b2d(a, &ka); - dval(&db) = b2d(b, &kb); -#ifdef Pack_32 - k = ka - kb + 32*(a->wds - b->wds); -#else - k = ka - kb + 16*(a->wds - b->wds); -#endif -#ifdef IBM - if (k > 0) { - word0(&da) += (k >> 2)*Exp_msk1; - if (k &= 3) - dval(&da) *= 1 << k; - } - else { - k = -k; - word0(&db) += (k >> 2)*Exp_msk1; - if (k &= 3) - dval(&db) *= 1 << k; - } -#else - if (k > 0) - word0(&da) += k*Exp_msk1; - else { - k = -k; - word0(&db) += k*Exp_msk1; - } -#endif - return dval(&da) / dval(&db); - } - - static const double -tens[] = { - 1e0, 1e1, 1e2, 1e3, 1e4, 1e5, 1e6, 1e7, 1e8, 1e9, - 1e10, 1e11, 1e12, 1e13, 1e14, 1e15, 1e16, 1e17, 1e18, 1e19, - 1e20, 1e21, 1e22 -#ifdef VAX - , 1e23, 1e24 -#endif - }; - - static const double -#ifdef IEEE_Arith -bigtens[] = { 1e16, 1e32, 1e64, 1e128, 1e256 }; -static const double tinytens[] = { 1e-16, 1e-32, 1e-64, 1e-128, -#ifdef Avoid_Underflow - 9007199254740992.*9007199254740992.e-256 - /* = 2^106 * 1e-256 */ -#else - 1e-256 -#endif - }; -/* The factor of 2^53 in tinytens[4] helps us avoid setting the underflow */ -/* flag unnecessarily. It leads to a song and dance at the end of strtod. */ -#define Scale_Bit 0x10 -#define n_bigtens 5 -#else -#ifdef IBM -bigtens[] = { 1e16, 1e32, 1e64 }; -static const double tinytens[] = { 1e-16, 1e-32, 1e-64 }; -#define n_bigtens 3 -#else -bigtens[] = { 1e16, 1e32 }; -static const double tinytens[] = { 1e-16, 1e-32 }; -#define n_bigtens 2 -#endif -#endif - -#undef Need_Hexdig -#ifdef INFNAN_CHECK -#ifndef No_Hex_NaN -#define Need_Hexdig -#endif -#endif - -#ifndef Need_Hexdig -#ifndef NO_HEX_FP -#define Need_Hexdig -#endif -#endif - -#ifdef Need_Hexdig /*{*/ -#if 0 -static unsigned char hexdig[256]; - - static void -htinit(unsigned char *h, unsigned char *s, int inc) -{ - int i, j; - for(i = 0; (j = s[i]) !=0; i++) - h[j] = i + inc; - } - - static void -hexdig_init(void) /* Use of hexdig_init omitted 20121220 to avoid a */ - /* race condition when multiple threads are used. */ -{ -#define USC (unsigned char *) - htinit(hexdig, USC "0123456789", 0x10); - htinit(hexdig, USC "abcdef", 0x10 + 10); - htinit(hexdig, USC "ABCDEF", 0x10 + 10); - } -#else -static unsigned char hexdig[256] = { - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 16,17,18,19,20,21,22,23,24,25,0,0,0,0,0,0, - 0,26,27,28,29,30,31,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,26,27,28,29,30,31,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 - }; -#endif -#endif /* } Need_Hexdig */ - -#ifdef INFNAN_CHECK - -#ifndef NAN_WORD0 -#define NAN_WORD0 0x7ff80000 -#endif - -#ifndef NAN_WORD1 -#define NAN_WORD1 0 -#endif - - static int -match(const char **sp, const char *t) -{ - int c, d; - const char *s = *sp; - - while((d = *t++)) { - if ((c = *++s) >= 'A' && c <= 'Z') - c += 'a' - 'A'; - if (c != d) - return 0; - } - *sp = s + 1; - return 1; - } - -#ifndef No_Hex_NaN - static void -hexnan(U *rvp, const char **sp) -{ - ULong c, x[2]; - const char *s; - int c1, havedig, udx0, xshift; - - /**** if (!hexdig['0']) hexdig_init(); ****/ - x[0] = x[1] = 0; - havedig = xshift = 0; - udx0 = 1; - s = *sp; - /* allow optional initial 0x or 0X */ - while((c = *(const unsigned char*)(s+1)) && c <= ' ') - ++s; - if (s[1] == '0' && (s[2] == 'x' || s[2] == 'X')) - s += 2; - while((c = *(const unsigned char*)++s)) { - if ((c1 = hexdig[c])) - c = c1 & 0xf; - else if (c <= ' ') { - if (udx0 && havedig) { - udx0 = 0; - xshift = 1; - } - continue; - } -#ifdef GDTOA_NON_PEDANTIC_NANCHECK - else if (/*(*/ c == ')' && havedig) { - *sp = s + 1; - break; - } - else - return; /* invalid form: don't change *sp */ -#else - else { - do { - if (/*(*/ c == ')') { - *sp = s + 1; - break; - } - } while((c = *++s)); - break; - } -#endif - havedig = 1; - if (xshift) { - xshift = 0; - x[0] = x[1]; - x[1] = 0; - } - if (udx0) - x[0] = (x[0] << 4) | (x[1] >> 28); - x[1] = (x[1] << 4) | c; - } - if ((x[0] &= 0xfffff) || x[1]) { - word0(rvp) = Exp_mask | x[0]; - word1(rvp) = x[1]; - } - } -#endif /*No_Hex_NaN*/ -#endif /* INFNAN_CHECK */ - -#ifdef Pack_32 -#define ULbits 32 -#define kshift 5 -#define kmask 31 -#else -#define ULbits 16 -#define kshift 4 -#define kmask 15 -#endif - -#if !defined(NO_HEX_FP) || defined(Honor_FLT_ROUNDS) /*{*/ - static Bigint * -increment(Bigint *b MTd) -{ - ULong *x, *xe; - Bigint *b1; - - x = b->x; - xe = x + b->wds; - do { - if (*x < (ULong)0xffffffffL) { - ++*x; - return b; - } - *x++ = 0; - } while(x < xe); - { - if (b->wds >= b->maxwds) { - b1 = Balloc(b->k+1 MTa); - Bcopy(b1,b); - Bfree(b MTa); - b = b1; - } - b->x[b->wds++] = 1; - } - return b; - } - -#endif /*}*/ - -#ifndef NO_HEX_FP /*{*/ - - static void -rshift(Bigint *b, int k) -{ - ULong *x, *x1, *xe, y; - int n; - - x = x1 = b->x; - n = k >> kshift; - if (n < b->wds) { - xe = x + b->wds; - x += n; - if (k &= kmask) { - n = 32 - k; - y = *x++ >> k; - while(x < xe) { - *x1++ = (y | (*x << n)) & 0xffffffff; - y = *x++ >> k; - } - if ((*x1 = y) !=0) - x1++; - } - else - while(x < xe) - *x1++ = *x++; - } - if ((b->wds = x1 - b->x) == 0) - b->x[0] = 0; - } - - static ULong -any_on(Bigint *b, int k) -{ - int n, nwds; - ULong *x, *x0, x1, x2; - - x = b->x; - nwds = b->wds; - n = k >> kshift; - if (n > nwds) - n = nwds; - else if (n < nwds && (k &= kmask)) { - x1 = x2 = x[n]; - x1 >>= k; - x1 <<= k; - if (x1 != x2) - return 1; - } - x0 = x; - x += n; - while(x > x0) - if (*--x) - return 1; - return 0; - } - -enum { /* rounding values: same as FLT_ROUNDS */ - Round_zero = 0, - Round_near = 1, - Round_up = 2, - Round_down = 3 - }; - - void -gethex( const char **sp, U *rvp, int rounding, int sign MTd) -{ - Bigint *b; - const unsigned char *decpt, *s0, *s, *s1; - Long e, e1; - ULong L, lostbits, *x; - int big, denorm, esign, havedig, k, n, nbits, up, zret; -#ifdef IBM - int j; -#endif - enum { -#ifdef IEEE_Arith /*{{*/ - emax = 0x7fe - Bias - P + 1, - emin = Emin - P + 1 -#else /*}{*/ - emin = Emin - P, -#ifdef VAX - emax = 0x7ff - Bias - P + 1 -#endif -#ifdef IBM - emax = 0x7f - Bias - P -#endif -#endif /*}}*/ - }; -#ifdef USE_LOCALE - int i; -#ifdef NO_LOCALE_CACHE - const unsigned char *decimalpoint = (unsigned char*) - localeconv()->decimal_point; -#else - const unsigned char *decimalpoint; - static unsigned char *decimalpoint_cache; - if (!(s0 = decimalpoint_cache)) { - s0 = (unsigned char*)localeconv()->decimal_point; - if ((decimalpoint_cache = (unsigned char*) - MALLOC(strlen((const char*)s0) + 1))) { - strcpy((char*)decimalpoint_cache, (const char*)s0); - s0 = decimalpoint_cache; - } - } - decimalpoint = s0; -#endif -#endif - - /**** if (!hexdig['0']) hexdig_init(); ****/ - havedig = 0; - s0 = *(const unsigned char **)sp + 2; - while(s0[havedig] == '0') - havedig++; - s0 += havedig; - s = s0; - decpt = 0; - zret = 0; - e = 0; - if (hexdig[*s]) - havedig++; - else { - zret = 1; -#ifdef USE_LOCALE - for(i = 0; decimalpoint[i]; ++i) { - if (s[i] != decimalpoint[i]) - goto pcheck; - } - decpt = s += i; -#else - if (*s != '.') - goto pcheck; - decpt = ++s; -#endif - if (!hexdig[*s]) - goto pcheck; - while(*s == '0') - s++; - if (hexdig[*s]) - zret = 0; - havedig = 1; - s0 = s; - } - while(hexdig[*s]) - s++; -#ifdef USE_LOCALE - if (*s == *decimalpoint && !decpt) { - for(i = 1; decimalpoint[i]; ++i) { - if (s[i] != decimalpoint[i]) - goto pcheck; - } - decpt = s += i; -#else - if (*s == '.' && !decpt) { - decpt = ++s; -#endif - while(hexdig[*s]) - s++; - }/*}*/ - if (decpt) - e = -(((Long)(s-decpt)) << 2); - pcheck: - s1 = s; - big = esign = 0; - switch(*s) { - case 'p': - case 'P': - switch(*++s) { - case '-': - esign = 1; - /* no break */ - case '+': - s++; - } - if ((n = hexdig[*s]) == 0 || n > 0x19) { - s = s1; - break; - } - e1 = n - 0x10; - while((n = hexdig[*++s]) !=0 && n <= 0x19) { - if (e1 & 0xf8000000) - big = 1; - e1 = 10*e1 + n - 0x10; - } - if (esign) - e1 = -e1; - e += e1; - } - *sp = (char*)s; - if (!havedig) - *sp = (char*)s0 - 1; - if (zret) - goto retz1; - if (big) { - if (esign) { -#ifdef IEEE_Arith - switch(rounding) { - case Round_up: - if (sign) - break; - goto ret_tiny; - case Round_down: - if (!sign) - break; - goto ret_tiny; - } -#endif - goto retz; -#ifdef IEEE_Arith - ret_tinyf: - Bfree(b MTa); - ret_tiny: - Set_errno(ERANGE); - word0(rvp) = 0; - word1(rvp) = 1; - return; -#endif /* IEEE_Arith */ - } - switch(rounding) { - case Round_near: - goto ovfl1; - case Round_up: - if (!sign) - goto ovfl1; - goto ret_big; - case Round_down: - if (sign) - goto ovfl1; - goto ret_big; - } - ret_big: - word0(rvp) = Big0; - word1(rvp) = Big1; - return; - } - n = s1 - s0 - 1; - for(k = 0; n > (1 << (kshift-2)) - 1; n >>= 1) - k++; - b = Balloc(k MTa); - x = b->x; - n = 0; - L = 0; -#ifdef USE_LOCALE - for(i = 0; decimalpoint[i+1]; ++i); -#endif - while(s1 > s0) { -#ifdef USE_LOCALE - if (*--s1 == decimalpoint[i]) { - s1 -= i; - continue; - } -#else - if (*--s1 == '.') - continue; -#endif - if (n == ULbits) { - *x++ = L; - L = 0; - n = 0; - } - L |= (hexdig[*s1] & 0x0f) << n; - n += 4; - } - *x++ = L; - b->wds = n = x - b->x; - n = ULbits*n - hi0bits(L); - nbits = Nbits; - lostbits = 0; - x = b->x; - if (n > nbits) { - n -= nbits; - if (any_on(b,n)) { - lostbits = 1; - k = n - 1; - if (x[k>>kshift] & 1 << (k & kmask)) { - lostbits = 2; - if (k > 0 && any_on(b,k)) - lostbits = 3; - } - } - rshift(b, n); - e += n; - } - else if (n < nbits) { - n = nbits - n; - b = lshift(b, n MTa); - e -= n; - x = b->x; - } - if (e > emax) { - ovfl: - Bfree(b MTa); - ovfl1: - Set_errno(ERANGE); -#ifdef Honor_FLT_ROUNDS - switch (rounding) { - case Round_zero: - goto ret_big; - case Round_down: - if (!sign) - goto ret_big; - break; - case Round_up: - if (sign) - goto ret_big; - } -#endif - word0(rvp) = Exp_mask; - word1(rvp) = 0; - return; - } - denorm = 0; - if (e < emin) { - denorm = 1; - n = emin - e; - if (n >= nbits) { -#ifdef IEEE_Arith /*{*/ - switch (rounding) { - case Round_near: - if (n == nbits && (n < 2 || lostbits || any_on(b,n-1))) - goto ret_tinyf; - break; - case Round_up: - if (!sign) - goto ret_tinyf; - break; - case Round_down: - if (sign) - goto ret_tinyf; - } -#endif /* } IEEE_Arith */ - Bfree(b MTa); - retz: - Set_errno(ERANGE); - retz1: - rvp->d = 0.; - return; - } - k = n - 1; - if (lostbits) - lostbits = 1; - else if (k > 0) - lostbits = any_on(b,k); - if (x[k>>kshift] & 1 << (k & kmask)) - lostbits |= 2; - nbits -= n; - rshift(b,n); - e = emin; - } - if (lostbits) { - up = 0; - switch(rounding) { - case Round_zero: - break; - case Round_near: - if (lostbits & 2 - && (lostbits & 1) | (x[0] & 1)) - up = 1; - break; - case Round_up: - up = 1 - sign; - break; - case Round_down: - up = sign; - } - if (up) { - k = b->wds; - b = increment(b MTa); - x = b->x; - if (denorm) { -#if 0 - if (nbits == Nbits - 1 - && x[nbits >> kshift] & 1 << (nbits & kmask)) - denorm = 0; /* not currently used */ -#endif - } - else if (b->wds > k - || ((n = nbits & kmask) !=0 - && hi0bits(x[k-1]) < 32-n)) { - rshift(b,1); - if (++e > Emax) - goto ovfl; - } - } - } -#ifdef IEEE_Arith - if (denorm) - word0(rvp) = b->wds > 1 ? b->x[1] & ~0x100000 : 0; - else - word0(rvp) = (b->x[1] & ~0x100000) | ((e + 0x3ff + 52) << 20); - word1(rvp) = b->x[0]; -#endif -#ifdef IBM - if ((j = e & 3)) { - k = b->x[0] & ((1 << j) - 1); - rshift(b,j); - if (k) { - switch(rounding) { - case Round_up: - if (!sign) - increment(b); - break; - case Round_down: - if (sign) - increment(b); - break; - case Round_near: - j = 1 << (j-1); - if (k & j && ((k & (j-1)) | lostbits)) - increment(b); - } - } - } - e >>= 2; - word0(rvp) = b->x[1] | ((e + 65 + 13) << 24); - word1(rvp) = b->x[0]; -#endif -#ifdef VAX - /* The next two lines ignore swap of low- and high-order 2 bytes. */ - /* word0(rvp) = (b->x[1] & ~0x800000) | ((e + 129 + 55) << 23); */ - /* word1(rvp) = b->x[0]; */ - word0(rvp) = ((b->x[1] & ~0x800000) >> 16) | ((e + 129 + 55) << 7) | (b->x[1] << 16); - word1(rvp) = (b->x[0] >> 16) | (b->x[0] << 16); -#endif - Bfree(b MTa); - } -#endif /*!NO_HEX_FP}*/ - - static int -dshift(Bigint *b, int p2) -{ - int rv = hi0bits(b->x[b->wds-1]) - 4; - if (p2 > 0) - rv -= p2; - return rv & kmask; - } - - static int -quorem(Bigint *b, Bigint *S) -{ - int n; - ULong *bx, *bxe, q, *sx, *sxe; -#ifdef ULLong - ULLong borrow, carry, y, ys; -#else - ULong borrow, carry, y, ys; -#ifdef Pack_32 - ULong si, z, zs; -#endif -#endif - - n = S->wds; -#ifdef DEBUG - /*debug*/ if (b->wds > n) - /*debug*/ Bug("oversize b in quorem"); -#endif - if (b->wds < n) - return 0; - sx = S->x; - sxe = sx + --n; - bx = b->x; - bxe = bx + n; - q = *bxe / (*sxe + 1); /* ensure q <= true quotient */ -#ifdef DEBUG -#ifdef NO_STRTOD_BIGCOMP - /*debug*/ if (q > 9) -#else - /* An oversized q is possible when quorem is called from bigcomp and */ - /* the input is near, e.g., twice the smallest denormalized number. */ - /*debug*/ if (q > 15) -#endif - /*debug*/ Bug("oversized quotient in quorem"); -#endif - if (q) { - borrow = 0; - carry = 0; - do { -#ifdef ULLong - ys = *sx++ * (ULLong)q + carry; - carry = ys >> 32; - y = *bx - (ys & FFFFFFFF) - borrow; - borrow = y >> 32 & (ULong)1; - *bx++ = y & FFFFFFFF; -#else -#ifdef Pack_32 - si = *sx++; - ys = (si & 0xffff) * q + carry; - zs = (si >> 16) * q + (ys >> 16); - carry = zs >> 16; - y = (*bx & 0xffff) - (ys & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - z = (*bx >> 16) - (zs & 0xffff) - borrow; - borrow = (z & 0x10000) >> 16; - Storeinc(bx, z, y); -#else - ys = *sx++ * q + carry; - carry = ys >> 16; - y = *bx - (ys & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - *bx++ = y & 0xffff; -#endif -#endif - } - while(sx <= sxe); - if (!*bxe) { - bx = b->x; - while(--bxe > bx && !*bxe) - --n; - b->wds = n; - } - } - if (cmp(b, S) >= 0) { - q++; - borrow = 0; - carry = 0; - bx = b->x; - sx = S->x; - do { -#ifdef ULLong - ys = *sx++ + carry; - carry = ys >> 32; - y = *bx - (ys & FFFFFFFF) - borrow; - borrow = y >> 32 & (ULong)1; - *bx++ = y & FFFFFFFF; -#else -#ifdef Pack_32 - si = *sx++; - ys = (si & 0xffff) + carry; - zs = (si >> 16) + (ys >> 16); - carry = zs >> 16; - y = (*bx & 0xffff) - (ys & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - z = (*bx >> 16) - (zs & 0xffff) - borrow; - borrow = (z & 0x10000) >> 16; - Storeinc(bx, z, y); -#else - ys = *sx++ + carry; - carry = ys >> 16; - y = *bx - (ys & 0xffff) - borrow; - borrow = (y & 0x10000) >> 16; - *bx++ = y & 0xffff; -#endif -#endif - } - while(sx <= sxe); - bx = b->x; - bxe = bx + n; - if (!*bxe) { - while(--bxe > bx && !*bxe) - --n; - b->wds = n; - } - } - return q; - } - -#if defined(Avoid_Underflow) || !defined(NO_STRTOD_BIGCOMP) /*{*/ - static double -sulp(U *x, BCinfo *bc) -{ - U u; - double rv; - int i; - - rv = ulp(x); - if (!bc->scale || (i = 2*P + 1 - ((word0(x) & Exp_mask) >> Exp_shift)) <= 0) - return rv; /* Is there an example where i <= 0 ? */ - word0(&u) = Exp_1 + (i << Exp_shift); - word1(&u) = 0; - return rv * u.d; - } -#endif /*}*/ - -#ifndef NO_STRTOD_BIGCOMP - static void -bigcomp(U *rv, const char *s0, BCinfo *bc MTd) -{ - Bigint *b, *d; - int b2, bbits, d2, dd, dig, dsign, i, j, nd, nd0, p2, p5, speccase; - - dsign = bc->dsign; - nd = bc->nd; - nd0 = bc->nd0; - p5 = nd + bc->e0 - 1; - speccase = 0; -#ifndef Sudden_Underflow - if (rv->d == 0.) { /* special case: value near underflow-to-zero */ - /* threshold was rounded to zero */ - b = i2b(1 MTa); - p2 = Emin - P + 1; - bbits = 1; -#ifdef Avoid_Underflow - word0(rv) = (P+2) << Exp_shift; -#else - word1(rv) = 1; -#endif - i = 0; -#ifdef Honor_FLT_ROUNDS - if (bc->rounding == 1) -#endif - { - speccase = 1; - --p2; - dsign = 0; - goto have_i; - } - } - else -#endif - b = d2b(rv, &p2, &bbits MTa); -#ifdef Avoid_Underflow - p2 -= bc->scale; -#endif - /* floor(log2(rv)) == bbits - 1 + p2 */ - /* Check for denormal case. */ - i = P - bbits; - if (i > (j = P - Emin - 1 + p2)) { -#ifdef Sudden_Underflow - Bfree(b MTa); - b = i2b(1 MTa); - p2 = Emin; - i = P - 1; -#ifdef Avoid_Underflow - word0(rv) = (1 + bc->scale) << Exp_shift; -#else - word0(rv) = Exp_msk1; -#endif - word1(rv) = 0; -#else - i = j; -#endif - } -#ifdef Honor_FLT_ROUNDS - if (bc->rounding != 1) { - if (i > 0) - b = lshift(b, i MTa); - if (dsign) - b = increment(b MTa); - } - else -#endif - { - b = lshift(b, ++i MTa); - b->x[0] |= 1; - } -#ifndef Sudden_Underflow - have_i: -#endif - p2 -= p5 + i; - d = i2b(1 MTa); - /* Arrange for convenient computation of quotients: - * shift left if necessary so divisor has 4 leading 0 bits. - */ - if (p5 > 0) - d = pow5mult(d, p5 MTa); - else if (p5 < 0) - b = pow5mult(b, -p5 MTa); - if (p2 > 0) { - b2 = p2; - d2 = 0; - } - else { - b2 = 0; - d2 = -p2; - } - i = dshift(d, d2); - if ((b2 += i) > 0) - b = lshift(b, b2 MTa); - if ((d2 += i) > 0) - d = lshift(d, d2 MTa); - - /* Now b/d = exactly half-way between the two floating-point values */ - /* on either side of the input string. Compute first digit of b/d. */ - - if (!(dig = quorem(b,d))) { - b = multadd(b, 10, 0 MTa); /* very unlikely */ - dig = quorem(b,d); - } - - /* Compare b/d with s0 */ - - for(i = 0; i < nd0; ) { - if ((dd = s0[i++] - '0' - dig)) - goto ret; - if (!b->x[0] && b->wds == 1) { - if (i < nd) - dd = 1; - goto ret; - } - b = multadd(b, 10, 0 MTa); - dig = quorem(b,d); - } - for(j = bc->dp1; i++ < nd;) { - if ((dd = s0[j++] - '0' - dig)) - goto ret; - if (!b->x[0] && b->wds == 1) { - if (i < nd) - dd = 1; - goto ret; - } - b = multadd(b, 10, 0 MTa); - dig = quorem(b,d); - } - if (dig > 0 || b->x[0] || b->wds > 1) - dd = -1; - ret: - Bfree(b MTa); - Bfree(d MTa); -#ifdef Honor_FLT_ROUNDS - if (bc->rounding != 1) { - if (dd < 0) { - if (bc->rounding == 0) { - if (!dsign) - goto retlow1; - } - else if (dsign) - goto rethi1; - } - else if (dd > 0) { - if (bc->rounding == 0) { - if (dsign) - goto rethi1; - goto ret1; - } - if (!dsign) - goto rethi1; - dval(rv) += 2.*sulp(rv,bc); - } - else { - bc->inexact = 0; - if (dsign) - goto rethi1; - } - } - else -#endif - if (speccase) { - if (dd <= 0) - rv->d = 0.; - } - else if (dd < 0) { - if (!dsign) /* does not happen for round-near */ -retlow1: - dval(rv) -= sulp(rv,bc); - } - else if (dd > 0) { - if (dsign) { - rethi1: - dval(rv) += sulp(rv,bc); - } - } - else { - /* Exact half-way case: apply round-even rule. */ - if ((j = ((word0(rv) & Exp_mask) >> Exp_shift) - bc->scale) <= 0) { - i = 1 - j; - if (i <= 31) { - if (word1(rv) & (0x1 << i)) - goto odd; - } - else if (word0(rv) & (0x1 << (i-32))) - goto odd; - } - else if (word1(rv) & 1) { - odd: - if (dsign) - goto rethi1; - goto retlow1; - } - } - -#ifdef Honor_FLT_ROUNDS - ret1: -#endif - return; - } -#endif /* NO_STRTOD_BIGCOMP */ - - double -strtod(const char *s00, char **se) -{ - int bb2, bb5, bbe, bd2, bd5, bbbits, bs2, c, e, e1; - int esign, i, j, k, nd, nd0, nf, nz, nz0, nz1, sign; - const char *s, *s0, *s1; - double aadj, aadj1; - Long L; - U aadj2, adj, rv, rv0; - ULong y, z; - BCinfo bc; - Bigint *bb, *bb1, *bd, *bd0, *bs, *delta; -#ifdef USE_BF96 - ULLong bhi, blo, brv, t00, t01, t02, t10, t11, terv, tg, tlo, yz; - const BF96 *p10; - int bexact, erv; -#endif -#ifdef Avoid_Underflow - ULong Lsb, Lsb1; -#endif -#ifdef SET_INEXACT - int oldinexact; -#endif -#ifndef NO_STRTOD_BIGCOMP - int req_bigcomp = 0; -#endif -#ifdef MULTIPLE_THREADS - ThInfo *TI = 0; -#endif -#ifdef Honor_FLT_ROUNDS /*{*/ -#ifdef Trust_FLT_ROUNDS /*{{ only define this if FLT_ROUNDS really works! */ - bc.rounding = Flt_Rounds; -#else /*}{*/ - bc.rounding = 1; - switch(fegetround()) { - case FE_TOWARDZERO: bc.rounding = 0; break; - case FE_UPWARD: bc.rounding = 2; break; - case FE_DOWNWARD: bc.rounding = 3; - } -#endif /*}}*/ -#endif /*}*/ -#ifdef USE_LOCALE - const char *s2; -#endif - - sign = nz0 = nz1 = nz = bc.dplen = bc.uflchk = 0; - dval(&rv) = 0.; - for(s = s00;;s++) switch(*s) { - case '-': - sign = 1; - /* no break */ - case '+': - if (*++s) - goto break2; - /* no break */ - case 0: - goto ret0; - case '\t': - case '\n': - case '\v': - case '\f': - case '\r': - case ' ': - continue; - default: - goto break2; - } - break2: - if (*s == '0') { -#ifndef NO_HEX_FP /*{*/ - switch(s[1]) { - case 'x': - case 'X': -#ifdef Honor_FLT_ROUNDS - gethex(&s, &rv, bc.rounding, sign MTb); -#else - gethex(&s, &rv, 1, sign MTb); -#endif - goto ret; - } -#endif /*}*/ - nz0 = 1; - while(*++s == '0') ; - if (!*s) - goto ret; - } - s0 = s; - nd = nf = 0; -#ifdef USE_BF96 - yz = 0; - for(; (c = *s) >= '0' && c <= '9'; nd++, s++) - if (nd < 19) - yz = 10*yz + c - '0'; -#else - y = z = 0; - for(; (c = *s) >= '0' && c <= '9'; nd++, s++) - if (nd < 9) - y = 10*y + c - '0'; - else if (nd < DBL_DIG + 2) - z = 10*z + c - '0'; -#endif - nd0 = nd; - bc.dp0 = bc.dp1 = s - s0; - for(s1 = s; s1 > s0 && *--s1 == '0'; ) - ++nz1; -#ifdef USE_LOCALE - s1 = localeconv()->decimal_point; - if (c == *s1) { - c = '.'; - if (*++s1) { - s2 = s; - for(;;) { - if (*++s2 != *s1) { - c = 0; - break; - } - if (!*++s1) { - s = s2; - break; - } - } - } - } -#endif - if (c == '.') { - c = *++s; - bc.dp1 = s - s0; - bc.dplen = bc.dp1 - bc.dp0; - if (!nd) { - for(; c == '0'; c = *++s) - nz++; - if (c > '0' && c <= '9') { - bc.dp0 = s0 - s; - bc.dp1 = bc.dp0 + bc.dplen; - s0 = s; - nf += nz; - nz = 0; - goto have_dig; - } - goto dig_done; - } - for(; c >= '0' && c <= '9'; c = *++s) { - have_dig: - nz++; - if (c -= '0') { - nf += nz; - i = 1; -#ifdef USE_BF96 - for(; i < nz; ++i) { - if (++nd <= 19) - yz *= 10; - } - if (++nd <= 19) - yz = 10*yz + c; -#else - for(; i < nz; ++i) { - if (nd++ < 9) - y *= 10; - else if (nd <= DBL_DIG + 2) - z *= 10; - } - if (nd++ < 9) - y = 10*y + c; - else if (nd <= DBL_DIG + 2) - z = 10*z + c; -#endif - nz = nz1 = 0; - } - } - } - dig_done: - e = 0; - if (c == 'e' || c == 'E') { - if (!nd && !nz && !nz0) { - goto ret0; - } - s00 = s; - esign = 0; - switch(c = *++s) { - case '-': - esign = 1; - case '+': - c = *++s; - } - if (c >= '0' && c <= '9') { - while(c == '0') - c = *++s; - if (c > '0' && c <= '9') { - L = c - '0'; - s1 = s; - while((c = *++s) >= '0' && c <= '9') - L = 10*L + c - '0'; - if (s - s1 > 8 || L > 19999) - /* Avoid confusion from exponents - * so large that e might overflow. - */ - e = 19999; /* safe for 16 bit ints */ - else - e = (int)L; - if (esign) - e = -e; - } - else - e = 0; - } - else - s = s00; - } - if (!nd) { - if (!nz && !nz0) { -#ifdef INFNAN_CHECK /*{*/ - /* Check for Nan and Infinity */ - if (!bc.dplen) - switch(c) { - case 'i': - case 'I': - if (match(&s,"nf")) { - --s; - if (!match(&s,"inity")) - ++s; - word0(&rv) = 0x7ff00000; - word1(&rv) = 0; - goto ret; - } - break; - case 'n': - case 'N': - if (match(&s, "an")) { - word0(&rv) = NAN_WORD0; - word1(&rv) = NAN_WORD1; -#ifndef No_Hex_NaN - if (*s == '(') /*)*/ - hexnan(&rv, &s); -#endif - goto ret; - } - } -#endif /*} INFNAN_CHECK */ - ret0: - s = s00; - sign = 0; - } - goto ret; - } - bc.e0 = e1 = e -= nf; - - /* Now we have nd0 digits, starting at s0, followed by a - * decimal point, followed by nd-nd0 digits. The number we're - * after is the integer represented by those digits times - * 10**e */ - - if (!nd0) - nd0 = nd; -#ifndef USE_BF96 - k = nd < DBL_DIG + 2 ? nd : DBL_DIG + 2; - dval(&rv) = y; - if (k > 9) { -#ifdef SET_INEXACT - if (k > DBL_DIG) - oldinexact = get_inexact(); -#endif - dval(&rv) = tens[k - 9] * dval(&rv) + z; - } -#endif - bd0 = 0; - if (nd <= DBL_DIG -#ifndef RND_PRODQUOT -#ifndef Honor_FLT_ROUNDS - && Flt_Rounds == 1 -#endif -#endif - ) { -#ifdef USE_BF96 - dval(&rv) = yz; -#endif - if (!e) - goto ret; -#ifndef ROUND_BIASED_without_Round_Up - if (e > 0) { - if (e <= Ten_pmax) { -#ifdef SET_INEXACT - bc.inexact = 0; - oldinexact = 1; -#endif -#ifdef VAX - goto vax_ovfl_check; -#else -#ifdef Honor_FLT_ROUNDS - /* round correctly FLT_ROUNDS = 2 or 3 */ - if (sign) { - rv.d = -rv.d; - sign = 0; - } -#endif - /* rv = */ rounded_product(dval(&rv), tens[e]); - goto ret; -#endif - } - i = DBL_DIG - nd; - if (e <= Ten_pmax + i) { - /* A fancier test would sometimes let us do - * this for larger i values. - */ -#ifdef SET_INEXACT - bc.inexact = 0; - oldinexact = 1; -#endif -#ifdef Honor_FLT_ROUNDS - /* round correctly FLT_ROUNDS = 2 or 3 */ - if (sign) { - rv.d = -rv.d; - sign = 0; - } -#endif - e -= i; - dval(&rv) *= tens[i]; -#ifdef VAX - /* VAX exponent range is so narrow we must - * worry about overflow here... - */ - vax_ovfl_check: - word0(&rv) -= P*Exp_msk1; - /* rv = */ rounded_product(dval(&rv), tens[e]); - if ((word0(&rv) & Exp_mask) - > Exp_msk1*(DBL_MAX_EXP+Bias-1-P)) - goto ovfl; - word0(&rv) += P*Exp_msk1; -#else - /* rv = */ rounded_product(dval(&rv), tens[e]); -#endif - goto ret; - } - } -#ifndef Inaccurate_Divide - else if (e >= -Ten_pmax) { -#ifdef SET_INEXACT - bc.inexact = 0; - oldinexact = 1; -#endif -#ifdef Honor_FLT_ROUNDS - /* round correctly FLT_ROUNDS = 2 or 3 */ - if (sign) { - rv.d = -rv.d; - sign = 0; - } -#endif - /* rv = */ rounded_quotient(dval(&rv), tens[-e]); - goto ret; - } -#endif -#endif /* ROUND_BIASED_without_Round_Up */ - } -#ifdef USE_BF96 - k = nd < 19 ? nd : 19; -#endif - e1 += nd - k; /* scale factor = 10^e1 */ - -#ifdef IEEE_Arith -#ifdef SET_INEXACT - bc.inexact = 1; -#ifndef USE_BF96 - if (k <= DBL_DIG) -#endif - oldinexact = get_inexact(); -#endif -#ifdef Honor_FLT_ROUNDS - if (bc.rounding >= 2) { - if (sign) - bc.rounding = bc.rounding == 2 ? 0 : 2; - else - if (bc.rounding != 2) - bc.rounding = 0; - } -#endif -#endif /*IEEE_Arith*/ - -#ifdef USE_BF96 /*{*/ - Debug(++dtoa_stats[0]); - i = e1 + 342; - if (i < 0) - goto undfl; - if (i > 650) - goto ovfl; - p10 = &pten[i]; - brv = yz; - /* shift brv left, with i = number of bits shifted */ - i = 0; - if (!(brv & 0xffffffff00000000ull)) { - i = 32; - brv <<= 32; - } - if (!(brv & 0xffff000000000000ull)) { - i += 16; - brv <<= 16; - } - if (!(brv & 0xff00000000000000ull)) { - i += 8; - brv <<= 8; - } - if (!(brv & 0xf000000000000000ull)) { - i += 4; - brv <<= 4; - } - if (!(brv & 0xc000000000000000ull)) { - i += 2; - brv <<= 2; - } - if (!(brv & 0x8000000000000000ull)) { - i += 1; - brv <<= 1; - } - erv = (64 + 0x3fe) + p10->e - i; - if (erv <= 0 && nd > 19) - goto many_digits; /* denormal: may need to look at all digits */ - bhi = brv >> 32; - blo = brv & 0xffffffffull; - /* Unsigned 32-bit ints lie in [0,2^32-1] and */ - /* unsigned 64-bit ints lie in [0, 2^64-1]. The product of two unsigned */ - /* 32-bit ints is <= 2^64 - 2*2^32-1 + 1 = 2^64 - 1 - 2*(2^32 - 1), so */ - /* we can add two unsigned 32-bit ints to the product of two such ints, */ - /* and 64 bits suffice to contain the result. */ - t01 = bhi * p10->b1; - t10 = blo * p10->b0 + (t01 & 0xffffffffull); - t00 = bhi * p10->b0 + (t01 >> 32) + (t10 >> 32); - if (t00 & 0x8000000000000000ull) { - if ((t00 & 0x3ff) && (~t00 & 0x3fe)) { /* unambiguous result? */ - if (nd > 19 && ((t00 + (1< 19 && ((t00 + (1<b2; - t11 = blo * p10->b1 + (t02 & 0xffffffffull); - bexact = 1; - if (e1 < 0 || e1 > 41 || (t10 | t11) & 0xffffffffull || nd > 19) - bexact = 0; - tlo = (t10 & 0xffffffffull) + (t02 >> 32) + (t11 >> 32); - if (!bexact && (tlo + 0x10) >> 32 > tlo >> 32) - goto many_digits; - t00 += tlo >> 32; - if (t00 & 0x8000000000000000ull) { - if (erv <= 0) { /* denormal result */ - if (nd >= 20 || !((tlo & 0xfffffff0) | (t00 & 0x3ff))) - goto many_digits; - denormal: - if (erv <= -52) { -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto undfl; - case 2: goto tiniest; - } -#endif - if (erv < -52 || !(t00 & 0x7fffffffffffffffull)) - goto undfl; - goto tiniest; - } - tg = 1ull << (11 - erv); - t00 &= ~(tg - 1); /* clear low bits */ -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto noround_den; - case 2: goto roundup_den; - } -#endif - if (t00 & tg) { -#ifdef Honor_FLT_ROUNDS - roundup_den: -#endif - t00 += tg << 1; - if (!(t00 & 0x8000000000000000ull)) { - if (++erv > 0) - goto smallest_normal; - t00 = 0x8000000000000000ull; - } - } -#ifdef Honor_FLT_ROUNDS - noround_den: -#endif - LLval(&rv) = t00 >> (12 - erv); - Set_errno(ERANGE); - goto ret; - } - if (bexact) { -#ifdef SET_INEXACT - if (!(t00 & 0x7ff) && !(tlo & 0xffffffffull)) { - bc.inexact = 0; - goto noround; - } -#endif -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 2: - if (t00 & 0x7ff) - goto roundup; - case 0: goto noround; - } -#endif - if (t00 & 0x400 && (tlo & 0xffffffff) | (t00 & 0xbff)) - goto roundup; - goto noround; - } - if ((tlo & 0xfffffff0) | (t00 & 0x3ff) - && (nd <= 19 || ((t00 + (1ull << i)) & 0xfffffffffffffc00ull) - == (t00 & 0xfffffffffffffc00ull))) { - /* Unambiguous result. */ - /* If nd > 19, then incrementing the 19th digit */ - /* does not affect rv. */ -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto noround; - case 2: goto roundup; - } -#endif - if (t00 & 0x400) { /* round up */ - roundup: - t00 += 0x800; - if (!(t00 & 0x8000000000000000ull)) { - /* rounded up to a power of 2 */ - if (erv >= 0x7fe) - goto ovfl; - terv = erv + 1; - LLval(&rv) = terv << 52; - goto ret; - } - } - noround: - if (erv >= 0x7ff) - goto ovfl; - terv = erv; - LLval(&rv) = (terv << 52) | ((t00 & 0x7ffffffffffff800ull) >> 11); - goto ret; - } - } - else { - if (erv <= 1) { /* denormal result */ - if (nd >= 20 || !((tlo & 0xfffffff0) | (t00 & 0x1ff))) - goto many_digits; - denormal1: - if (erv <= -51) { -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto undfl; - case 2: goto tiniest; - } -#endif - if (erv < -51 || !(t00 & 0x3fffffffffffffffull)) - goto undfl; - tiniest: - LLval(&rv) = 1; - Set_errno(ERANGE); - goto ret; - } - tg = 1ull << (11 - erv); -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto noround1_den; - case 2: goto roundup1_den; - } -#endif - if (t00 & tg) { -#ifdef Honor_FLT_ROUNDS - roundup1_den: -#endif - if (0x8000000000000000ull & (t00 += (tg<<1)) && erv == 1) { - - smallest_normal: - LLval(&rv) = 0x0010000000000000ull; - goto ret; - } - } -#ifdef Honor_FLT_ROUNDS - noround1_den: -#endif - if (erv <= -52) - goto undfl; - LLval(&rv) = t00 >> (12 - erv); - Set_errno(ERANGE); - goto ret; - } - if (bexact) { -#ifdef SET_INEXACT - if (!(t00 & 0x3ff) && !(tlo & 0xffffffffull)) { - bc.inexact = 0; - goto noround1; - } -#endif -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 2: - if (t00 & 0x3ff) - goto roundup1; - case 0: goto noround1; - } -#endif - if (t00 & 0x200 && (t00 & 0x5ff || tlo)) - goto roundup1; - goto noround1; - } - if ((tlo & 0xfffffff0) | (t00 & 0x1ff) - && (nd <= 19 || ((t00 + (1ull << i)) & 0x7ffffffffffffe00ull) - == (t00 & 0x7ffffffffffffe00ull))) { - /* Unambiguous result. */ -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: goto noround1; - case 2: goto roundup1; - } -#endif - if (t00 & 0x200) { /* round up */ - roundup1: - t00 += 0x400; - if (!(t00 & 0x4000000000000000ull)) { - /* rounded up to a power of 2 */ - if (erv >= 0x7ff) - goto ovfl; - terv = erv; - LLval(&rv) = terv << 52; - goto ret; - } - } - noround1: - if (erv >= 0x800) - goto ovfl; - terv = erv - 1; - LLval(&rv) = (terv << 52) | ((t00 & 0x3ffffffffffffc00ull) >> 10); - goto ret; - } - } - many_digits: - Debug(++dtoa_stats[2]); - if (nd > 17) { - if (nd > 18) { - yz /= 100; - e1 += 2; - } - else { - yz /= 10; - e1 += 1; - } - y = yz / 100000000; - } - else if (nd > 9) { - i = nd - 9; - y = (yz >> i) / pfive[i-1]; - } - else - y = yz; - dval(&rv) = yz; -#endif /*}*/ - -#ifdef IEEE_Arith -#ifdef Avoid_Underflow - bc.scale = 0; -#endif -#endif /*IEEE_Arith*/ - - /* Get starting approximation = rv * 10**e1 */ - - if (e1 > 0) { - if ((i = e1 & 15)) - dval(&rv) *= tens[i]; - if (e1 &= ~15) { - if (e1 > DBL_MAX_10_EXP) { - ovfl: - /* Can't trust HUGE_VAL */ -#ifdef IEEE_Arith -#ifdef Honor_FLT_ROUNDS - switch(bc.rounding) { - case 0: /* toward 0 */ - case 3: /* toward -infinity */ - word0(&rv) = Big0; - word1(&rv) = Big1; - break; - default: - word0(&rv) = Exp_mask; - word1(&rv) = 0; - } -#else /*Honor_FLT_ROUNDS*/ - word0(&rv) = Exp_mask; - word1(&rv) = 0; -#endif /*Honor_FLT_ROUNDS*/ -#ifdef SET_INEXACT - /* set overflow bit */ - dval(&rv0) = 1e300; - dval(&rv0) *= dval(&rv0); -#endif -#else /*IEEE_Arith*/ - word0(&rv) = Big0; - word1(&rv) = Big1; -#endif /*IEEE_Arith*/ - range_err: - if (bd0) { - Bfree(bb MTb); - Bfree(bd MTb); - Bfree(bs MTb); - Bfree(bd0 MTb); - Bfree(delta MTb); - } - Set_errno(ERANGE); - goto ret; - } - e1 >>= 4; - for(j = 0; e1 > 1; j++, e1 >>= 1) - if (e1 & 1) - dval(&rv) *= bigtens[j]; - /* The last multiplication could overflow. */ - word0(&rv) -= P*Exp_msk1; - dval(&rv) *= bigtens[j]; - if ((z = word0(&rv) & Exp_mask) - > Exp_msk1*(DBL_MAX_EXP+Bias-P)) - goto ovfl; - if (z > Exp_msk1*(DBL_MAX_EXP+Bias-1-P)) { - /* set to largest number */ - /* (Can't trust DBL_MAX) */ - word0(&rv) = Big0; - word1(&rv) = Big1; - } - else - word0(&rv) += P*Exp_msk1; - } - } - else if (e1 < 0) { - e1 = -e1; - if ((i = e1 & 15)) - dval(&rv) /= tens[i]; - if (e1 >>= 4) { - if (e1 >= 1 << n_bigtens) - goto undfl; -#ifdef Avoid_Underflow - if (e1 & Scale_Bit) - bc.scale = 2*P; - for(j = 0; e1 > 0; j++, e1 >>= 1) - if (e1 & 1) - dval(&rv) *= tinytens[j]; - if (bc.scale && (j = 2*P + 1 - ((word0(&rv) & Exp_mask) - >> Exp_shift)) > 0) { - /* scaled rv is denormal; clear j low bits */ - if (j >= 32) { - if (j > 54) - goto undfl; - word1(&rv) = 0; - if (j >= 53) - word0(&rv) = (P+2)*Exp_msk1; - else - word0(&rv) &= 0xffffffff << (j-32); - } - else - word1(&rv) &= 0xffffffff << j; - } -#else - for(j = 0; e1 > 1; j++, e1 >>= 1) - if (e1 & 1) - dval(&rv) *= tinytens[j]; - /* The last multiplication could underflow. */ - dval(&rv0) = dval(&rv); - dval(&rv) *= tinytens[j]; - if (!dval(&rv)) { - dval(&rv) = 2.*dval(&rv0); - dval(&rv) *= tinytens[j]; -#endif - if (!dval(&rv)) { - undfl: - dval(&rv) = 0.; -#ifdef Honor_FLT_ROUNDS - if (bc.rounding == 2) - word1(&rv) = 1; -#endif - goto range_err; - } -#ifndef Avoid_Underflow - word0(&rv) = Tiny0; - word1(&rv) = Tiny1; - /* The refinement below will clean - * this approximation up. - */ - } -#endif - } - } - - /* Now the hard part -- adjusting rv to the correct value.*/ - - /* Put digits into bd: true value = bd * 10^e */ - - bc.nd = nd - nz1; -#ifndef NO_STRTOD_BIGCOMP - bc.nd0 = nd0; /* Only needed if nd > strtod_diglim, but done here */ - /* to silence an erroneous warning about bc.nd0 */ - /* possibly not being initialized. */ - if (nd > strtod_diglim) { - /* ASSERT(strtod_diglim >= 18); 18 == one more than the */ - /* minimum number of decimal digits to distinguish double values */ - /* in IEEE arithmetic. */ - i = j = 18; - if (i > nd0) - j += bc.dplen; - for(;;) { - if (--j < bc.dp1 && j >= bc.dp0) - j = bc.dp0 - 1; - if (s0[j] != '0') - break; - --i; - } - e += nd - i; - nd = i; - if (nd0 > nd) - nd0 = nd; - if (nd < 9) { /* must recompute y */ - y = 0; - for(i = 0; i < nd0; ++i) - y = 10*y + s0[i] - '0'; - for(j = bc.dp1; i < nd; ++i) - y = 10*y + s0[j++] - '0'; - } - } -#endif - bd0 = s2b(s0, nd0, nd, y, bc.dplen MTb); - - for(;;) { - bd = Balloc(bd0->k MTb); - Bcopy(bd, bd0); - bb = d2b(&rv, &bbe, &bbbits MTb); /* rv = bb * 2^bbe */ - bs = i2b(1 MTb); - - if (e >= 0) { - bb2 = bb5 = 0; - bd2 = bd5 = e; - } - else { - bb2 = bb5 = -e; - bd2 = bd5 = 0; - } - if (bbe >= 0) - bb2 += bbe; - else - bd2 -= bbe; - bs2 = bb2; -#ifdef Honor_FLT_ROUNDS - if (bc.rounding != 1) - bs2++; -#endif -#ifdef Avoid_Underflow - Lsb = LSB; - Lsb1 = 0; - j = bbe - bc.scale; - i = j + bbbits - 1; /* logb(rv) */ - j = P + 1 - bbbits; - if (i < Emin) { /* denormal */ - i = Emin - i; - j -= i; - if (i < 32) - Lsb <<= i; - else if (i < 52) - Lsb1 = Lsb << (i-32); - else - Lsb1 = Exp_mask; - } -#else /*Avoid_Underflow*/ -#ifdef Sudden_Underflow -#ifdef IBM - j = 1 + 4*P - 3 - bbbits + ((bbe + bbbits - 1) & 3); -#else - j = P + 1 - bbbits; -#endif -#else /*Sudden_Underflow*/ - j = bbe; - i = j + bbbits - 1; /* logb(rv) */ - if (i < Emin) /* denormal */ - j += P - Emin; - else - j = P + 1 - bbbits; -#endif /*Sudden_Underflow*/ -#endif /*Avoid_Underflow*/ - bb2 += j; - bd2 += j; -#ifdef Avoid_Underflow - bd2 += bc.scale; -#endif - i = bb2 < bd2 ? bb2 : bd2; - if (i > bs2) - i = bs2; - if (i > 0) { - bb2 -= i; - bd2 -= i; - bs2 -= i; - } - if (bb5 > 0) { - bs = pow5mult(bs, bb5 MTb); - bb1 = mult(bs, bb MTb); - Bfree(bb MTb); - bb = bb1; - } - if (bb2 > 0) - bb = lshift(bb, bb2 MTb); - if (bd5 > 0) - bd = pow5mult(bd, bd5 MTb); - if (bd2 > 0) - bd = lshift(bd, bd2 MTb); - if (bs2 > 0) - bs = lshift(bs, bs2 MTb); - delta = diff(bb, bd MTb); - bc.dsign = delta->sign; - delta->sign = 0; - i = cmp(delta, bs); -#ifndef NO_STRTOD_BIGCOMP /*{*/ - if (bc.nd > nd && i <= 0) { - if (bc.dsign) { - /* Must use bigcomp(). */ - req_bigcomp = 1; - break; - } -#ifdef Honor_FLT_ROUNDS - if (bc.rounding != 1) { - if (i < 0) { - req_bigcomp = 1; - break; - } - } - else -#endif - i = -1; /* Discarded digits make delta smaller. */ - } -#endif /*}*/ -#ifdef Honor_FLT_ROUNDS /*{*/ - if (bc.rounding != 1) { - if (i < 0) { - /* Error is less than an ulp */ - if (!delta->x[0] && delta->wds <= 1) { - /* exact */ -#ifdef SET_INEXACT - bc.inexact = 0; -#endif - break; - } - if (bc.rounding) { - if (bc.dsign) { - adj.d = 1.; - goto apply_adj; - } - } - else if (!bc.dsign) { - adj.d = -1.; - if (!word1(&rv) - && !(word0(&rv) & Frac_mask)) { - y = word0(&rv) & Exp_mask; -#ifdef Avoid_Underflow - if (!bc.scale || y > 2*P*Exp_msk1) -#else - if (y) -#endif - { - delta = lshift(delta,Log2P MTb); - if (cmp(delta, bs) <= 0) - adj.d = -0.5; - } - } - apply_adj: -#ifdef Avoid_Underflow /*{*/ - if (bc.scale && (y = word0(&rv) & Exp_mask) - <= 2*P*Exp_msk1) - word0(&adj) += (2*P+1)*Exp_msk1 - y; -#else -#ifdef Sudden_Underflow - if ((word0(&rv) & Exp_mask) <= - P*Exp_msk1) { - word0(&rv) += P*Exp_msk1; - dval(&rv) += adj.d*ulp(dval(&rv)); - word0(&rv) -= P*Exp_msk1; - } - else -#endif /*Sudden_Underflow*/ -#endif /*Avoid_Underflow}*/ - dval(&rv) += adj.d*ulp(&rv); - } - break; - } - adj.d = ratio(delta, bs); - if (adj.d < 1.) - adj.d = 1.; - if (adj.d <= 0x7ffffffe) { - /* adj = rounding ? ceil(adj) : floor(adj); */ - y = adj.d; - if (y != adj.d) { - if (!((bc.rounding>>1) ^ bc.dsign)) - y++; - adj.d = y; - } - } -#ifdef Avoid_Underflow /*{*/ - if (bc.scale && (y = word0(&rv) & Exp_mask) <= 2*P*Exp_msk1) - word0(&adj) += (2*P+1)*Exp_msk1 - y; -#else -#ifdef Sudden_Underflow - if ((word0(&rv) & Exp_mask) <= P*Exp_msk1) { - word0(&rv) += P*Exp_msk1; - adj.d *= ulp(dval(&rv)); - if (bc.dsign) - dval(&rv) += adj.d; - else - dval(&rv) -= adj.d; - word0(&rv) -= P*Exp_msk1; - goto cont; - } -#endif /*Sudden_Underflow*/ -#endif /*Avoid_Underflow}*/ - adj.d *= ulp(&rv); - if (bc.dsign) { - if (word0(&rv) == Big0 && word1(&rv) == Big1) - goto ovfl; - dval(&rv) += adj.d; - } - else - dval(&rv) -= adj.d; - goto cont; - } -#endif /*}Honor_FLT_ROUNDS*/ - - if (i < 0) { - /* Error is less than half an ulp -- check for - * special case of mantissa a power of two. - */ - if (bc.dsign || word1(&rv) || word0(&rv) & Bndry_mask -#ifdef IEEE_Arith /*{*/ -#ifdef Avoid_Underflow - || (word0(&rv) & Exp_mask) <= (2*P+1)*Exp_msk1 -#else - || (word0(&rv) & Exp_mask) <= Exp_msk1 -#endif -#endif /*}*/ - ) { -#ifdef SET_INEXACT - if (!delta->x[0] && delta->wds <= 1) - bc.inexact = 0; -#endif - break; - } - if (!delta->x[0] && delta->wds <= 1) { - /* exact result */ -#ifdef SET_INEXACT - bc.inexact = 0; -#endif - break; - } - delta = lshift(delta,Log2P MTb); - if (cmp(delta, bs) > 0) - goto drop_down; - break; - } - if (i == 0) { - /* exactly half-way between */ - if (bc.dsign) { - if ((word0(&rv) & Bndry_mask1) == Bndry_mask1 - && word1(&rv) == ( -#ifdef Avoid_Underflow - (bc.scale && (y = word0(&rv) & Exp_mask) <= 2*P*Exp_msk1) - ? (0xffffffff & (0xffffffff << (2*P+1-(y>>Exp_shift)))) : -#endif - 0xffffffff)) { - /*boundary case -- increment exponent*/ - if (word0(&rv) == Big0 && word1(&rv) == Big1) - goto ovfl; - word0(&rv) = (word0(&rv) & Exp_mask) - + Exp_msk1 -#ifdef IBM - | Exp_msk1 >> 4 -#endif - ; - word1(&rv) = 0; -#ifdef Avoid_Underflow - bc.dsign = 0; -#endif - break; - } - } - else if (!(word0(&rv) & Bndry_mask) && !word1(&rv)) { - drop_down: - /* boundary case -- decrement exponent */ -#ifdef Sudden_Underflow /*{{*/ - L = word0(&rv) & Exp_mask; -#ifdef IBM - if (L < Exp_msk1) -#else -#ifdef Avoid_Underflow - if (L <= (bc.scale ? (2*P+1)*Exp_msk1 : Exp_msk1)) -#else - if (L <= Exp_msk1) -#endif /*Avoid_Underflow*/ -#endif /*IBM*/ - { - if (bc.nd >nd) { - bc.uflchk = 1; - break; - } - goto undfl; - } - L -= Exp_msk1; -#else /*Sudden_Underflow}{*/ -#ifdef Avoid_Underflow - if (bc.scale) { - L = word0(&rv) & Exp_mask; - if (L <= (2*P+1)*Exp_msk1) { - if (L > (P+2)*Exp_msk1) - /* round even ==> */ - /* accept rv */ - break; - /* rv = smallest denormal */ - if (bc.nd >nd) { - bc.uflchk = 1; - break; - } - goto undfl; - } - } -#endif /*Avoid_Underflow*/ - L = (word0(&rv) & Exp_mask) - Exp_msk1; -#endif /*Sudden_Underflow}}*/ - word0(&rv) = L | Bndry_mask1; - word1(&rv) = 0xffffffff; -#ifdef IBM - goto cont; -#else -#ifndef NO_STRTOD_BIGCOMP - if (bc.nd > nd) - goto cont; -#endif - break; -#endif - } -#ifndef ROUND_BIASED -#ifdef Avoid_Underflow - if (Lsb1) { - if (!(word0(&rv) & Lsb1)) - break; - } - else if (!(word1(&rv) & Lsb)) - break; -#else - if (!(word1(&rv) & LSB)) - break; -#endif -#endif - if (bc.dsign) -#ifdef Avoid_Underflow - dval(&rv) += sulp(&rv, &bc); -#else - dval(&rv) += ulp(&rv); -#endif -#ifndef ROUND_BIASED - else { -#ifdef Avoid_Underflow - dval(&rv) -= sulp(&rv, &bc); -#else - dval(&rv) -= ulp(&rv); -#endif -#ifndef Sudden_Underflow - if (!dval(&rv)) { - if (bc.nd >nd) { - bc.uflchk = 1; - break; - } - goto undfl; - } -#endif - } -#ifdef Avoid_Underflow - bc.dsign = 1 - bc.dsign; -#endif -#endif - break; - } - if ((aadj = ratio(delta, bs)) <= 2.) { - if (bc.dsign) - aadj = aadj1 = 1.; - else if (word1(&rv) || word0(&rv) & Bndry_mask) { -#ifndef Sudden_Underflow - if (word1(&rv) == Tiny1 && !word0(&rv)) { - if (bc.nd >nd) { - bc.uflchk = 1; - break; - } - goto undfl; - } -#endif - aadj = 1.; - aadj1 = -1.; - } - else { - /* special case -- power of FLT_RADIX to be */ - /* rounded down... */ - - if (aadj < 2./FLT_RADIX) - aadj = 1./FLT_RADIX; - else - aadj *= 0.5; - aadj1 = -aadj; - } - } - else { - aadj *= 0.5; - aadj1 = bc.dsign ? aadj : -aadj; -#ifdef Check_FLT_ROUNDS - switch(bc.rounding) { - case 2: /* towards +infinity */ - aadj1 -= 0.5; - break; - case 0: /* towards 0 */ - case 3: /* towards -infinity */ - aadj1 += 0.5; - } -#else - if (Flt_Rounds == 0) - aadj1 += 0.5; -#endif /*Check_FLT_ROUNDS*/ - } - y = word0(&rv) & Exp_mask; - - /* Check for overflow */ - - if (y == Exp_msk1*(DBL_MAX_EXP+Bias-1)) { - dval(&rv0) = dval(&rv); - word0(&rv) -= P*Exp_msk1; - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; - if ((word0(&rv) & Exp_mask) >= - Exp_msk1*(DBL_MAX_EXP+Bias-P)) { - if (word0(&rv0) == Big0 && word1(&rv0) == Big1) - goto ovfl; - word0(&rv) = Big0; - word1(&rv) = Big1; - goto cont; - } - else - word0(&rv) += P*Exp_msk1; - } - else { -#ifdef Avoid_Underflow - if (bc.scale && y <= 2*P*Exp_msk1) { - if (aadj <= 0x7fffffff) { - if ((z = aadj) <= 0) - z = 1; - aadj = z; - aadj1 = bc.dsign ? aadj : -aadj; - } - dval(&aadj2) = aadj1; - word0(&aadj2) += (2*P+1)*Exp_msk1 - y; - aadj1 = dval(&aadj2); - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; - if (rv.d == 0.) -#ifdef NO_STRTOD_BIGCOMP - goto undfl; -#else - { - req_bigcomp = 1; - break; - } -#endif - } - else { - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; - } -#else -#ifdef Sudden_Underflow - if ((word0(&rv) & Exp_mask) <= P*Exp_msk1) { - dval(&rv0) = dval(&rv); - word0(&rv) += P*Exp_msk1; - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; -#ifdef IBM - if ((word0(&rv) & Exp_mask) < P*Exp_msk1) -#else - if ((word0(&rv) & Exp_mask) <= P*Exp_msk1) -#endif - { - if (word0(&rv0) == Tiny0 - && word1(&rv0) == Tiny1) { - if (bc.nd >nd) { - bc.uflchk = 1; - break; - } - goto undfl; - } - word0(&rv) = Tiny0; - word1(&rv) = Tiny1; - goto cont; - } - else - word0(&rv) -= P*Exp_msk1; - } - else { - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; - } -#else /*Sudden_Underflow*/ - /* Compute adj so that the IEEE rounding rules will - * correctly round rv + adj in some half-way cases. - * If rv * ulp(rv) is denormalized (i.e., - * y <= (P-1)*Exp_msk1), we must adjust aadj to avoid - * trouble from bits lost to denormalization; - * example: 1.2e-307 . - */ - if (y <= (P-1)*Exp_msk1 && aadj > 1.) { - aadj1 = (double)(int)(aadj + 0.5); - if (!bc.dsign) - aadj1 = -aadj1; - } - adj.d = aadj1 * ulp(&rv); - dval(&rv) += adj.d; -#endif /*Sudden_Underflow*/ -#endif /*Avoid_Underflow*/ - } - z = word0(&rv) & Exp_mask; -#ifndef SET_INEXACT - if (bc.nd == nd) { -#ifdef Avoid_Underflow - if (!bc.scale) -#endif - if (y == z) { - /* Can we stop now? */ - L = (Long)aadj; - aadj -= L; - /* The tolerances below are conservative. */ - if (bc.dsign || word1(&rv) || word0(&rv) & Bndry_mask) { - if (aadj < .4999999 || aadj > .5000001) - break; - } - else if (aadj < .4999999/FLT_RADIX) - break; - } - } -#endif - cont: - Bfree(bb MTb); - Bfree(bd MTb); - Bfree(bs MTb); - Bfree(delta MTb); - } - Bfree(bb MTb); - Bfree(bd MTb); - Bfree(bs MTb); - Bfree(bd0 MTb); - Bfree(delta MTb); -#ifndef NO_STRTOD_BIGCOMP - if (req_bigcomp) { - bd0 = 0; - bc.e0 += nz1; - bigcomp(&rv, s0, &bc MTb); - y = word0(&rv) & Exp_mask; - if (y == Exp_mask) - goto ovfl; - if (y == 0 && rv.d == 0.) - goto undfl; - } -#endif -#ifdef Avoid_Underflow - if (bc.scale) { - word0(&rv0) = Exp_1 - 2*P*Exp_msk1; - word1(&rv0) = 0; - dval(&rv) *= dval(&rv0); -#ifndef NO_ERRNO - /* try to avoid the bug of testing an 8087 register value */ -#ifdef IEEE_Arith - if (!(word0(&rv) & Exp_mask)) -#else - if (word0(&rv) == 0 && word1(&rv) == 0) -#endif - Set_errno(ERANGE); -#endif - } -#endif /* Avoid_Underflow */ - ret: -#ifdef SET_INEXACT - if (bc.inexact) { - if (!(word0(&rv) & Exp_mask)) { - /* set underflow and inexact bits */ - dval(&rv0) = 1e-300; - dval(&rv0) *= dval(&rv0); - } - else if (!oldinexact) { - word0(&rv0) = Exp_1 + (70 << Exp_shift); - word1(&rv0) = 0; - dval(&rv0) += 1.; - } - } - else if (!oldinexact) - clear_inexact(); -#endif - if (se) - *se = (char *)s; - return sign ? -dval(&rv) : dval(&rv); - } - -#ifndef MULTIPLE_THREADS - static char *dtoa_result; -#endif - - static char * -rv_alloc(int i MTd) -{ - int j, k, *r; - - j = sizeof(ULong); - for(k = 0; - sizeof(Bigint) - sizeof(ULong) - sizeof(int) + j <= i; - j <<= 1) - k++; - r = (int*)Balloc(k MTa); - *r = k; - return -#ifndef MULTIPLE_THREADS - dtoa_result = -#endif - (char *)(r+1); - } - - static char * -nrv_alloc(const char *s, char *s0, size_t s0len, char **rve, int n MTd) -{ - char *rv, *t; - - if (!s0) - s0 = rv_alloc(n MTa); - else if (s0len <= n) { - rv = 0; - t = rv + n; - goto rve_chk; - } - t = rv = s0; - while((*t = *s++)) - ++t; - rve_chk: - if (rve) - *rve = t; - return rv; - } - -/* freedtoa(s) must be used to free values s returned by dtoa - * when MULTIPLE_THREADS is #defined. It should be used in all cases, - * but for consistency with earlier versions of dtoa, it is optional - * when MULTIPLE_THREADS is not defined. - */ - - void -freedtoa(char *s) -{ -#ifdef MULTIPLE_THREADS - ThInfo *TI = 0; -#endif - Bigint *b = (Bigint *)((int *)s - 1); - b->maxwds = 1 << (b->k = *(int*)b); - Bfree(b MTb); -#ifndef MULTIPLE_THREADS - if (s == dtoa_result) - dtoa_result = 0; -#endif - } - -/* dtoa for IEEE arithmetic (dmg): convert double to ASCII string. - * - * Inspired by "How to Print Floating-Point Numbers Accurately" by - * Guy L. Steele, Jr. and Jon L. White [Proc. ACM SIGPLAN '90, pp. 112-126]. - * - * Modifications: - * 1. Rather than iterating, we use a simple numeric overestimate - * to determine k = floor(log10(d)). We scale relevant - * quantities using O(log2(k)) rather than O(k) multiplications. - * 2. For some modes > 2 (corresponding to ecvt and fcvt), we don't - * try to generate digits strictly left to right. Instead, we - * compute with fewer bits and propagate the carry if necessary - * when rounding the final digit up. This is often faster. - * 3. Under the assumption that input will be rounded nearest, - * mode 0 renders 1e23 as 1e23 rather than 9.999999999999999e22. - * That is, we allow equality in stopping tests when the - * round-nearest rule will give the same floating-point value - * as would satisfaction of the stopping test with strict - * inequality. - * 4. We remove common factors of powers of 2 from relevant - * quantities. - * 5. When converting floating-point integers less than 1e16, - * we use floating-point arithmetic rather than resorting - * to multiple-precision integers. - * 6. When asked to produce fewer than 15 digits, we first try - * to get by with floating-point arithmetic; we resort to - * multiple-precision integer arithmetic only if we cannot - * guarantee that the floating-point calculation has given - * the correctly rounded result. For k requested digits and - * "uniformly" distributed input, the probability is - * something like 10^(k-15) that we must resort to the Long - * calculation. - */ - - char * -dtoa_r(double dd, int mode, int ndigits, int *decpt, int *sign, char **rve, char *buf, size_t blen) -{ - /* Arguments ndigits, decpt, sign are similar to those - of ecvt and fcvt; trailing zeros are suppressed from - the returned string. If not null, *rve is set to point - to the end of the return value. If d is +-Infinity or NaN, - then *decpt is set to 9999. - - mode: - 0 ==> shortest string that yields d when read in - and rounded to nearest. - 1 ==> like 0, but with Steele & White stopping rule; - e.g. with IEEE P754 arithmetic , mode 0 gives - 1e23 whereas mode 1 gives 9.999999999999999e22. - 2 ==> max(1,ndigits) significant digits. This gives a - return value similar to that of ecvt, except - that trailing zeros are suppressed. - 3 ==> through ndigits past the decimal point. This - gives a return value similar to that from fcvt, - except that trailing zeros are suppressed, and - ndigits can be negative. - 4,5 ==> similar to 2 and 3, respectively, but (in - round-nearest mode) with the tests of mode 0 to - possibly return a shorter string that rounds to d. - With IEEE arithmetic and compilation with - -DHonor_FLT_ROUNDS, modes 4 and 5 behave the same - as modes 2 and 3 when FLT_ROUNDS != 1. - 6-9 ==> Debugging modes similar to mode - 4: don't try - fast floating-point estimate (if applicable). - - Values of mode other than 0-9 are treated as mode 0. - - When not NULL, buf is an output buffer of length blen, which must - be large enough to accommodate suppressed trailing zeros and a trailing - null byte. If blen is too small, rv = NULL is returned, in which case - if rve is not NULL, a subsequent call with blen >= (*rve - rv) + 1 - should succeed in returning buf. - - When buf is NULL, sufficient space is allocated for the return value, - which, when done using, the caller should pass to freedtoa(). - - USE_BF is automatically defined when neither NO_LONG_LONG nor NO_BF96 - is defined. - */ - -#ifdef MULTIPLE_THREADS - ThInfo *TI = 0; -#endif - int bbits, b2, b5, be, dig, i, ilim, ilim1, - j, j1, k, leftright, m2, m5, s2, s5, spec_case; -#if !defined(Sudden_Underflow) || defined(USE_BF96) - int denorm; -#endif - Bigint *b, *b1, *delta, *mlo, *mhi, *S; - U u; - char *s; -#ifdef SET_INEXACT - int inexact, oldinexact; -#endif -#ifdef USE_BF96 /*{{*/ - BF96 *p10; - ULLong dbhi, dbits, dblo, den, hb, rb, rblo, res, res0, res3, reslo, sres, - sulp, tv0, tv1, tv2, tv3, ulp, ulplo, ulpmask, ures, ureslo, zb; - int eulp, k1, n2, ulpadj, ulpshift; -#else /*}{*/ -#ifndef Sudden_Underflow - ULong x; -#endif - Long L; - U d2, eps; - double ds; - int ieps, ilim0, k0, k_check, try_quick; -#ifndef No_leftright -#ifdef IEEE_Arith - U eps1; -#endif -#endif -#endif /*}}*/ -#ifdef Honor_FLT_ROUNDS /*{*/ - int Rounding; -#ifdef Trust_FLT_ROUNDS /*{{ only define this if FLT_ROUNDS really works! */ - Rounding = Flt_Rounds; -#else /*}{*/ - Rounding = 1; - switch(fegetround()) { - case FE_TOWARDZERO: Rounding = 0; break; - case FE_UPWARD: Rounding = 2; break; - case FE_DOWNWARD: Rounding = 3; - } -#endif /*}}*/ -#endif /*}*/ - - u.d = dd; - if (word0(&u) & Sign_bit) { - /* set sign for everything, including 0's and NaNs */ - *sign = 1; - word0(&u) &= ~Sign_bit; /* clear sign bit */ - } - else - *sign = 0; - -#if defined(IEEE_Arith) + defined(VAX) -#ifdef IEEE_Arith - if ((word0(&u) & Exp_mask) == Exp_mask) -#else - if (word0(&u) == 0x8000) -#endif - { - /* Infinity or NaN */ - *decpt = 9999; -#ifdef IEEE_Arith - if (!word1(&u) && !(word0(&u) & 0xfffff)) - return nrv_alloc("Infinity", buf, blen, rve, 8 MTb); -#endif - return nrv_alloc("NaN", buf, blen, rve, 3 MTb); - } -#endif -#ifdef IBM - dval(&u) += 0; /* normalize */ -#endif - if (!dval(&u)) { - *decpt = 1; - return nrv_alloc("0", buf, blen, rve, 1 MTb); - } - -#ifdef SET_INEXACT -#ifndef USE_BF96 - try_quick = -#endif - oldinexact = get_inexact(); - inexact = 1; -#endif -#ifdef Honor_FLT_ROUNDS - if (Rounding >= 2) { - if (*sign) - Rounding = Rounding == 2 ? 0 : 2; - else - if (Rounding != 2) - Rounding = 0; - } -#endif -#ifdef USE_BF96 /*{{*/ - dbits = (u.LL & 0xfffffffffffffull) << 11; /* fraction bits */ - if ((be = u.LL >> 52)) /* biased exponent; nonzero ==> normal */ { - dbits |= 0x8000000000000000ull; - denorm = ulpadj = 0; - } - else { - denorm = 1; - ulpadj = be + 1; - dbits <<= 1; - if (!(dbits & 0xffffffff00000000ull)) { - dbits <<= 32; - be -= 32; - } - if (!(dbits & 0xffff000000000000ull)) { - dbits <<= 16; - be -= 16; - } - if (!(dbits & 0xff00000000000000ull)) { - dbits <<= 8; - be -= 8; - } - if (!(dbits & 0xf000000000000000ull)) { - dbits <<= 4; - be -= 4; - } - if (!(dbits & 0xc000000000000000ull)) { - dbits <<= 2; - be -= 2; - } - if (!(dbits & 0x8000000000000000ull)) { - dbits <<= 1; - be -= 1; - } - assert(be >= -51); - ulpadj -= be; - } - j = Lhint[be + 51]; - p10 = &pten[j]; - dbhi = dbits >> 32; - dblo = dbits & 0xffffffffull; - i = be - 0x3fe; - if (i < p10->e - || (i == p10->e && (dbhi < p10->b0 || (dbhi == p10->b0 && dblo < p10->b1)))) - --j; - k = j - 342; - - /* now 10^k <= dd < 10^(k+1) */ - -#else /*}{*/ - - b = d2b(&u, &be, &bbits MTb); -#ifdef Sudden_Underflow - i = (int)(word0(&u) >> Exp_shift1 & (Exp_mask>>Exp_shift1)); -#else - if ((i = (int)(word0(&u) >> Exp_shift1 & (Exp_mask>>Exp_shift1)))) { -#endif - dval(&d2) = dval(&u); - word0(&d2) &= Frac_mask1; - word0(&d2) |= Exp_11; -#ifdef IBM - if (j = 11 - hi0bits(word0(&d2) & Frac_mask)) - dval(&d2) /= 1 << j; -#endif - - /* log(x) ~=~ log(1.5) + (x-1.5)/1.5 - * log10(x) = log(x) / log(10) - * ~=~ log(1.5)/log(10) + (x-1.5)/(1.5*log(10)) - * log10(d) = (i-Bias)*log(2)/log(10) + log10(d2) - * - * This suggests computing an approximation k to log10(d) by - * - * k = (i - Bias)*0.301029995663981 - * + ( (d2-1.5)*0.289529654602168 + 0.176091259055681 ); - * - * We want k to be too large rather than too small. - * The error in the first-order Taylor series approximation - * is in our favor, so we just round up the constant enough - * to compensate for any error in the multiplication of - * (i - Bias) by 0.301029995663981; since |i - Bias| <= 1077, - * and 1077 * 0.30103 * 2^-52 ~=~ 7.2e-14, - * adding 1e-13 to the constant term more than suffices. - * Hence we adjust the constant term to 0.1760912590558. - * (We could get a more accurate k by invoking log10, - * but this is probably not worthwhile.) - */ - - i -= Bias; -#ifdef IBM - i <<= 2; - i += j; -#endif -#ifndef Sudden_Underflow - denorm = 0; - } - else { - /* d is denormalized */ - - i = bbits + be + (Bias + (P-1) - 1); - x = i > 32 ? word0(&u) << (64 - i) | word1(&u) >> (i - 32) - : word1(&u) << (32 - i); - dval(&d2) = x; - word0(&d2) -= 31*Exp_msk1; /* adjust exponent */ - i -= (Bias + (P-1) - 1) + 1; - denorm = 1; - } -#endif - ds = (dval(&d2)-1.5)*0.289529654602168 + 0.1760912590558 + i*0.301029995663981; - k = (int)ds; - if (ds < 0. && ds != k) - k--; /* want k = floor(ds) */ - k_check = 1; - if (k >= 0 && k <= Ten_pmax) { - if (dval(&u) < tens[k]) - k--; - k_check = 0; - } - j = bbits - i - 1; - if (j >= 0) { - b2 = 0; - s2 = j; - } - else { - b2 = -j; - s2 = 0; - } - if (k >= 0) { - b5 = 0; - s5 = k; - s2 += k; - } - else { - b2 -= k; - b5 = -k; - s5 = 0; - } -#endif /*}}*/ - if (mode < 0 || mode > 9) - mode = 0; - -#ifndef USE_BF96 -#ifndef SET_INEXACT -#ifdef Check_FLT_ROUNDS - try_quick = Rounding == 1; -#endif -#endif /*SET_INEXACT*/ -#endif - - if (mode > 5) { - mode -= 4; -#ifndef USE_BF96 - try_quick = 0; -#endif - } - leftright = 1; - ilim = ilim1 = -1; /* Values for cases 0 and 1; done here to */ - /* silence erroneous "gcc -Wall" warning. */ - switch(mode) { - case 0: - case 1: - i = 18; - ndigits = 0; - break; - case 2: - leftright = 0; - /* no break */ - case 4: - if (ndigits <= 0) - ndigits = 1; - ilim = ilim1 = i = ndigits; - break; - case 3: - leftright = 0; - /* no break */ - case 5: - i = ndigits + k + 1; - ilim = i; - ilim1 = i - 1; - if (i <= 0) - i = 1; - } - if (!buf) { - buf = rv_alloc(i MTb); - blen = sizeof(Bigint) + ((1 << ((int*)buf)[-1]) - 1)*sizeof(ULong) - sizeof(int); - } - else if (blen <= i) { - buf = 0; - if (rve) - *rve = buf + i; - return buf; - } - s = buf; - - /* Check for special case that d is a normalized power of 2. */ - - spec_case = 0; - if (mode < 2 || (leftright -#ifdef Honor_FLT_ROUNDS - && Rounding == 1 -#endif - )) { - if (!word1(&u) && !(word0(&u) & Bndry_mask) -#ifndef Sudden_Underflow - && word0(&u) & (Exp_mask & ~Exp_msk1) -#endif - ) { - /* The special case */ - spec_case = 1; - } - } - -#ifdef USE_BF96 /*{*/ - b = 0; - if (ilim < 0 && (mode == 3 || mode == 5)) { - S = mhi = 0; - goto no_digits; - } - i = 1; - j = 52 + 0x3ff - be; - ulpshift = 0; - ulplo = 0; - /* Can we do an exact computation with 64-bit integer arithmetic? */ - if (k < 0) { - if (k < -25) - goto toobig; - res = dbits >> 11; - n2 = pfivebits[k1 = -(k + 1)] + 53; - j1 = j; - if (n2 > 61) { - ulpshift = n2 - 61; - if (res & (ulpmask = (1ull << ulpshift) - 1)) - goto toobig; - j -= ulpshift; - res >>= ulpshift; - } - /* Yes. */ - res *= ulp = pfive[k1]; - if (ulpshift) { - ulplo = ulp; - ulp >>= ulpshift; - } - j += k; - if (ilim == 0) { - S = mhi = 0; - if (res > (5ull << j)) - goto one_digit; - goto no_digits; - } - goto no_div; - } - if (ilim == 0 && j + k >= 0) { - S = mhi = 0; - if ((dbits >> 11) > (pfive[k-1] << j)) - goto one_digit; - goto no_digits; - } - if (k <= dtoa_divmax && j + k >= 0) { - /* Another "yes" case -- we will use exact integer arithmetic. */ - use_exact: - Debug(++dtoa_stats[3]); - res = dbits >> 11; /* residual */ - ulp = 1; - if (k <= 0) - goto no_div; - j1 = j + k + 1; - den = pfive[k-i] << (j1 - i); - for(;;) { - dig = res / den; - *s++ = '0' + dig; - if (!(res -= dig*den)) { -#ifdef SET_INEXACT - inexact = 0; - oldinexact = 1; -#endif - goto retc; - } - if (ilim < 0) { - ures = den - res; - if (2*res <= ulp - && (spec_case ? 4*res <= ulp : (2*res < ulp || dig & 1))) - goto ulp_reached; - if (2*ures < ulp) - goto Roundup; - } - else if (i == ilim) { - switch(Rounding) { - case 0: goto retc; - case 2: goto Roundup; - } - ures = 2*res; - if (ures > den - || (ures == den && dig & 1) - || (spec_case && res <= ulp && 2*res >= ulp)) - goto Roundup; - goto retc; - } - if (j1 < ++i) { - res *= 10; - ulp *= 10; - } - else { - if (i > k) - break; - den = pfive[k-i] << (j1 - i); - } - } - no_div: - for(;;) { - dig = den = res >> j; - *s++ = '0' + dig; - if (!(res -= den << j)) { -#ifdef SET_INEXACT - inexact = 0; - oldinexact = 1; -#endif - goto retc; - } - if (ilim < 0) { - ures = (1ull << j) - res; - if (2*res <= ulp - && (spec_case ? 4*res <= ulp : (2*res < ulp || dig & 1))) { - ulp_reached: - if (ures < res - || (ures == res && dig & 1)) - goto Roundup; - goto retc; - } - if (2*ures < ulp) - goto Roundup; - } - --j; - if (i == ilim) { -#ifdef Honor_FLT_ROUNDS - switch(Rounding) { - case 0: goto retc; - case 2: goto Roundup; - } -#endif - hb = 1ull << j; - if (res & hb && (dig & 1 || res & (hb-1))) - goto Roundup; - if (spec_case && res <= ulp && 2*res >= ulp) { - Roundup: - while(*--s == '9') - if (s == buf) { - ++k; - *s++ = '1'; - goto ret1; - } - ++*s++; - goto ret1; - } - goto retc; - } - ++i; - res *= 5; - if (ulpshift) { - ulplo = 5*(ulplo & ulpmask); - ulp = 5*ulp + (ulplo >> ulpshift); - } - else - ulp *= 5; - } - } - toobig: - if (ilim > 28) - goto Fast_failed1; - /* Scale by 10^-k */ - p10 = &pten[342-k]; - tv0 = p10->b2 * dblo; /* rarely matters, but does, e.g., for 9.862818194192001e18 */ - tv1 = p10->b1 * dblo + (tv0 >> 32); - tv2 = p10->b2 * dbhi + (tv1 & 0xffffffffull); - tv3 = p10->b0 * dblo + (tv1>>32) + (tv2>>32); - res3 = p10->b1 * dbhi + (tv3 & 0xffffffffull); - res = p10->b0 * dbhi + (tv3>>32) + (res3>>32); - be += p10->e - 0x3fe; - eulp = j1 = be - 54 + ulpadj; - if (!(res & 0x8000000000000000ull)) { - --be; - res3 <<= 1; - res = (res << 1) | ((res3 & 0x100000000ull) >> 32); - } - res0 = res; /* save for Fast_failed */ -#if !defined(SET_INEXACT) && !defined(NO_DTOA_64) /*{*/ - if (ilim > 19) - goto Fast_failed; - Debug(++dtoa_stats[4]); - assert(be >= 0 && be <= 4); /* be = 0 is rare, but possible, e.g., for 1e20 */ - res >>= 4 - be; - ulp = p10->b0; /* ulp */ - ulp = (ulp << 29) | (p10->b1 >> 3); - /* scaled ulp = ulp * 2^(eulp - 60) */ - /* We maintain 61 bits of the scaled ulp. */ - if (ilim == 0) { - if (!(res & 0x7fffffffffffffeull) - || !((~res) & 0x7fffffffffffffeull)) - goto Fast_failed1; - S = mhi = 0; - if (res >= 0x5000000000000000ull) - goto one_digit; - goto no_digits; - } - rb = 1; /* upper bound on rounding error */ - for(;;++i) { - dig = res >> 60; - *s++ = '0' + dig; - res &= 0xfffffffffffffffull; - if (ilim < 0) { - ures = 0x1000000000000000ull - res; - if (eulp > 0) { - assert(eulp <= 4); - sulp = ulp << (eulp - 1); - if (res <= ures) { - if (res + rb > ures - rb) - goto Fast_failed; - if (res < sulp) - goto retc; - } - else { - if (res - rb <= ures + rb) - goto Fast_failed; - if (ures < sulp) - goto Roundup; - } - } - else { - zb = -(1ull << (eulp + 63)); - if (!(zb & res)) { - sres = res << (1 - eulp); - if (sres < ulp && (!spec_case || 2*sres < ulp)) { - if ((res+rb) << (1 - eulp) >= ulp) - goto Fast_failed; - if (ures < res) { - if (ures + rb >= res - rb) - goto Fast_failed; - goto Roundup; - } - if (ures - rb < res + rb) - goto Fast_failed; - goto retc; - } - } - if (!(zb & ures) && ures << -eulp < ulp) { - if (ures << (1 - eulp) < ulp) - goto Roundup; - goto Fast_failed; - } - } - } - else if (i == ilim) { - ures = 0x1000000000000000ull - res; - if (ures < res) { - if (ures <= rb || res - rb <= ures + rb) { - if (j + k >= 0 && k >= 0 && k <= 27) - goto use_exact1; - goto Fast_failed; - } -#ifdef Honor_FLT_ROUNDS - if (Rounding == 0) - goto retc; -#endif - goto Roundup; - } - if (res <= rb || ures - rb <= res + rb) { - if (j + k >= 0 && k >= 0 && k <= 27) { - use_exact1: - s = buf; - i = 1; - goto use_exact; - } - goto Fast_failed; - } -#ifdef Honor_FLT_ROUNDS - if (Rounding == 2) - goto Roundup; -#endif - goto retc; - } - rb *= 10; - if (rb >= 0x1000000000000000ull) - goto Fast_failed; - res *= 10; - ulp *= 5; - if (ulp & 0x8000000000000000ull) { - eulp += 4; - ulp >>= 3; - } - else { - eulp += 3; - ulp >>= 2; - } - } -#endif /*}*/ -#ifndef NO_BF96 - Fast_failed: -#endif - Debug(++dtoa_stats[5]); - s = buf; - i = 4 - be; - res = res0 >> i; - reslo = 0xffffffffull & res3; - if (i) - reslo = (res0 << (64 - i)) >> 32 | (reslo >> i); - rb = 0; - rblo = 4; /* roundoff bound */ - ulp = p10->b0; /* ulp */ - ulp = (ulp << 29) | (p10->b1 >> 3); - eulp = j1; - for(i = 1;;++i) { - dig = res >> 60; - *s++ = '0' + dig; - res &= 0xfffffffffffffffull; -#ifdef SET_INEXACT - if (!res && !reslo) { - if (!(res3 & 0xffffffffull)) { - inexact = 0; - oldinexact = 1; - } - goto retc; - } -#endif - if (ilim < 0) { - ures = 0x1000000000000000ull - res; - ureslo = 0; - if (reslo) { - ureslo = 0x100000000ull - reslo; - --ures; - } - if (eulp > 0) { - assert(eulp <= 4); - sulp = (ulp << (eulp - 1)) - rb; - if (res <= ures) { - if (res < sulp) { - if (res+rb < ures-rb) - goto retc; - } - } - else if (ures < sulp) { - if (res-rb > ures+rb) - goto Roundup; - } - goto Fast_failed1; - } - else { - zb = -(1ull << (eulp + 60)); - if (!(zb & (res + rb))) { - sres = (res - rb) << (1 - eulp); - if (sres < ulp && (!spec_case || 2*sres < ulp)) { - sres = res << (1 - eulp); - if ((j = eulp + 31) > 0) - sres += (rblo + reslo) >> j; - else - sres += (rblo + reslo) << -j; - if (sres + (rb << (1 - eulp)) >= ulp) - goto Fast_failed1; - if (sres >= ulp) - goto more96; - if (ures < res - || (ures == res && ureslo < reslo)) { - if (ures + rb >= res - rb) - goto Fast_failed1; - goto Roundup; - } - if (ures - rb <= res + rb) - goto Fast_failed1; - goto retc; - } - } - if (!(zb & ures) && (ures-rb) << (1 - eulp) < ulp) { - if ((ures + rb) << (1 - eulp) < ulp) - goto Roundup; - goto Fast_failed1; - } - } - } - else if (i == ilim) { - ures = 0x1000000000000000ull - res; - sres = ureslo = 0; - if (reslo) { - ureslo = 0x100000000ull - reslo; - --ures; - sres = (reslo + rblo) >> 31; - } - sres += 2*rb; - if (ures <= res) { - if (ures <=sres || res - ures <= sres) - goto Fast_failed1; -#ifdef Honor_FLT_ROUNDS - if (Rounding == 0) - goto retc; -#endif - goto Roundup; - } - if (res <= sres || ures - res <= sres) - goto Fast_failed1; -#ifdef Honor_FLT_ROUNDS - if (Rounding == 2) - goto Roundup; -#endif - goto retc; - } - more96: - rblo *= 10; - rb = 10*rb + (rblo >> 32); - rblo &= 0xffffffffull; - if (rb >= 0x1000000000000000ull) - goto Fast_failed1; - reslo *= 10; - res = 10*res + (reslo >> 32); - reslo &= 0xffffffffull; - ulp *= 5; - if (ulp & 0x8000000000000000ull) { - eulp += 4; - ulp >>= 3; - } - else { - eulp += 3; - ulp >>= 2; - } - } - Fast_failed1: - Debug(++dtoa_stats[6]); - S = mhi = mlo = 0; -#ifdef USE_BF96 - b = d2b(&u, &be, &bbits MTb); -#endif - s = buf; - i = (int)(word0(&u) >> Exp_shift1 & (Exp_mask>>Exp_shift1)); - i -= Bias; - if (ulpadj) - i -= ulpadj - 1; - j = bbits - i - 1; - if (j >= 0) { - b2 = 0; - s2 = j; - } - else { - b2 = -j; - s2 = 0; - } - if (k >= 0) { - b5 = 0; - s5 = k; - s2 += k; - } - else { - b2 -= k; - b5 = -k; - s5 = 0; - } -#endif /*}*/ - -#ifdef Honor_FLT_ROUNDS - if (mode > 1 && Rounding != 1) - leftright = 0; -#endif - -#ifndef USE_BF96 /*{*/ - if (ilim >= 0 && ilim <= Quick_max && try_quick) { - - /* Try to get by with floating-point arithmetic. */ - - i = 0; - dval(&d2) = dval(&u); - j1 = -(k0 = k); - ilim0 = ilim; - ieps = 2; /* conservative */ - if (k > 0) { - ds = tens[k&0xf]; - j = k >> 4; - if (j & Bletch) { - /* prevent overflows */ - j &= Bletch - 1; - dval(&u) /= bigtens[n_bigtens-1]; - ieps++; - } - for(; j; j >>= 1, i++) - if (j & 1) { - ieps++; - ds *= bigtens[i]; - } - dval(&u) /= ds; - } - else if (j1 > 0) { - dval(&u) *= tens[j1 & 0xf]; - for(j = j1 >> 4; j; j >>= 1, i++) - if (j & 1) { - ieps++; - dval(&u) *= bigtens[i]; - } - } - if (k_check && dval(&u) < 1. && ilim > 0) { - if (ilim1 <= 0) - goto fast_failed; - ilim = ilim1; - k--; - dval(&u) *= 10.; - ieps++; - } - dval(&eps) = ieps*dval(&u) + 7.; - word0(&eps) -= (P-1)*Exp_msk1; - if (ilim == 0) { - S = mhi = 0; - dval(&u) -= 5.; - if (dval(&u) > dval(&eps)) - goto one_digit; - if (dval(&u) < -dval(&eps)) - goto no_digits; - goto fast_failed; - } -#ifndef No_leftright - if (leftright) { - /* Use Steele & White method of only - * generating digits needed. - */ - dval(&eps) = 0.5/tens[ilim-1] - dval(&eps); -#ifdef IEEE_Arith - if (j1 >= 307) { - eps1.d = 1.01e256; /* 1.01 allows roundoff in the next few lines */ - word0(&eps1) -= Exp_msk1 * (Bias+P-1); - dval(&eps1) *= tens[j1 & 0xf]; - for(i = 0, j = (j1-256) >> 4; j; j >>= 1, i++) - if (j & 1) - dval(&eps1) *= bigtens[i]; - if (eps.d < eps1.d) - eps.d = eps1.d; - if (10. - u.d < 10.*eps.d && eps.d < 1.) { - /* eps.d < 1. excludes trouble with the tiniest denormal */ - *s++ = '1'; - ++k; - goto ret1; - } - } -#endif - for(i = 0;;) { - L = dval(&u); - dval(&u) -= L; - *s++ = '0' + (int)L; - if (1. - dval(&u) < dval(&eps)) - goto bump_up; - if (dval(&u) < dval(&eps)) - goto retc; - if (++i >= ilim) - break; - dval(&eps) *= 10.; - dval(&u) *= 10.; - } - } - else { -#endif - /* Generate ilim digits, then fix them up. */ - dval(&eps) *= tens[ilim-1]; - for(i = 1;; i++, dval(&u) *= 10.) { - L = (Long)(dval(&u)); - if (!(dval(&u) -= L)) - ilim = i; - *s++ = '0' + (int)L; - if (i == ilim) { - if (dval(&u) > 0.5 + dval(&eps)) - goto bump_up; - else if (dval(&u) < 0.5 - dval(&eps)) - goto retc; - break; - } - } -#ifndef No_leftright - } -#endif - fast_failed: - s = buf; - dval(&u) = dval(&d2); - k = k0; - ilim = ilim0; - } - - /* Do we have a "small" integer? */ - - if (be >= 0 && k <= Int_max) { - /* Yes. */ - ds = tens[k]; - if (ndigits < 0 && ilim <= 0) { - S = mhi = 0; - if (ilim < 0 || dval(&u) <= 5*ds) - goto no_digits; - goto one_digit; - } - for(i = 1;; i++, dval(&u) *= 10.) { - L = (Long)(dval(&u) / ds); - dval(&u) -= L*ds; -#ifdef Check_FLT_ROUNDS - /* If FLT_ROUNDS == 2, L will usually be high by 1 */ - if (dval(&u) < 0) { - L--; - dval(&u) += ds; - } -#endif - *s++ = '0' + (int)L; - if (!dval(&u)) { -#ifdef SET_INEXACT - inexact = 0; -#endif - break; - } - if (i == ilim) { -#ifdef Honor_FLT_ROUNDS - if (mode > 1) - switch(Rounding) { - case 0: goto retc; - case 2: goto bump_up; - } -#endif - dval(&u) += dval(&u); -#ifdef ROUND_BIASED - if (dval(&u) >= ds) -#else - if (dval(&u) > ds || (dval(&u) == ds && L & 1)) -#endif - { - bump_up: - while(*--s == '9') - if (s == buf) { - k++; - *s = '0'; - break; - } - ++*s++; - } - break; - } - } - goto retc; - } - -#endif /*}*/ - m2 = b2; - m5 = b5; - mhi = mlo = 0; - if (leftright) { - i = -#ifndef Sudden_Underflow - denorm ? be + (Bias + (P-1) - 1 + 1) : -#endif -#ifdef IBM - 1 + 4*P - 3 - bbits + ((bbits + be - 1) & 3); -#else - 1 + P - bbits; -#endif - b2 += i; - s2 += i; - mhi = i2b(1 MTb); - } - if (m2 > 0 && s2 > 0) { - i = m2 < s2 ? m2 : s2; - b2 -= i; - m2 -= i; - s2 -= i; - } - if (b5 > 0) { - if (leftright) { - if (m5 > 0) { - mhi = pow5mult(mhi, m5 MTb); - b1 = mult(mhi, b MTb); - Bfree(b MTb); - b = b1; - } - if ((j = b5 - m5)) - b = pow5mult(b, j MTb); - } - else - b = pow5mult(b, b5 MTb); - } - S = i2b(1 MTb); - if (s5 > 0) - S = pow5mult(S, s5 MTb); - - if (spec_case) { - b2 += Log2P; - s2 += Log2P; - } - - /* Arrange for convenient computation of quotients: - * shift left if necessary so divisor has 4 leading 0 bits. - * - * Perhaps we should just compute leading 28 bits of S once - * and for all and pass them and a shift to quorem, so it - * can do shifts and ors to compute the numerator for q. - */ - i = dshift(S, s2); - b2 += i; - m2 += i; - s2 += i; - if (b2 > 0) - b = lshift(b, b2 MTb); - if (s2 > 0) - S = lshift(S, s2 MTb); -#ifndef USE_BF96 - if (k_check) { - if (cmp(b,S) < 0) { - k--; - b = multadd(b, 10, 0 MTb); /* we botched the k estimate */ - if (leftright) - mhi = multadd(mhi, 10, 0 MTb); - ilim = ilim1; - } - } -#endif - if (ilim <= 0 && (mode == 3 || mode == 5)) { - if (ilim < 0 || cmp(b,S = multadd(S,5,0 MTb)) <= 0) { - /* no digits, fcvt style */ - no_digits: - k = -1 - ndigits; - goto ret; - } - one_digit: - *s++ = '1'; - ++k; - goto ret; - } - if (leftright) { - if (m2 > 0) - mhi = lshift(mhi, m2 MTb); - - /* Compute mlo -- check for special case - * that d is a normalized power of 2. - */ - - mlo = mhi; - if (spec_case) { - mhi = Balloc(mhi->k MTb); - Bcopy(mhi, mlo); - mhi = lshift(mhi, Log2P MTb); - } - - for(i = 1;;i++) { - dig = quorem(b,S) + '0'; - /* Do we yet have the shortest decimal string - * that will round to d? - */ - j = cmp(b, mlo); - delta = diff(S, mhi MTb); - j1 = delta->sign ? 1 : cmp(b, delta); - Bfree(delta MTb); -#ifndef ROUND_BIASED - if (j1 == 0 && mode != 1 && !(word1(&u) & 1) -#ifdef Honor_FLT_ROUNDS - && (mode <= 1 || Rounding >= 1) -#endif - ) { - if (dig == '9') - goto round_9_up; - if (j > 0) - dig++; -#ifdef SET_INEXACT - else if (!b->x[0] && b->wds <= 1) - inexact = 0; -#endif - *s++ = dig; - goto ret; - } -#endif - if (j < 0 || (j == 0 && mode != 1 -#ifndef ROUND_BIASED - && !(word1(&u) & 1) -#endif - )) { - if (!b->x[0] && b->wds <= 1) { -#ifdef SET_INEXACT - inexact = 0; -#endif - goto accept_dig; - } -#ifdef Honor_FLT_ROUNDS - if (mode > 1) - switch(Rounding) { - case 0: goto accept_dig; - case 2: goto keep_dig; - } -#endif /*Honor_FLT_ROUNDS*/ - if (j1 > 0) { - b = lshift(b, 1 MTb); - j1 = cmp(b, S); -#ifdef ROUND_BIASED - if (j1 >= 0 /*)*/ -#else - if ((j1 > 0 || (j1 == 0 && dig & 1)) -#endif - && dig++ == '9') - goto round_9_up; - } - accept_dig: - *s++ = dig; - goto ret; - } - if (j1 > 0) { -#ifdef Honor_FLT_ROUNDS - if (!Rounding && mode > 1) - goto accept_dig; -#endif - if (dig == '9') { /* possible if i == 1 */ - round_9_up: - *s++ = '9'; - goto roundoff; - } - *s++ = dig + 1; - goto ret; - } -#ifdef Honor_FLT_ROUNDS - keep_dig: -#endif - *s++ = dig; - if (i == ilim) - break; - b = multadd(b, 10, 0 MTb); - if (mlo == mhi) - mlo = mhi = multadd(mhi, 10, 0 MTb); - else { - mlo = multadd(mlo, 10, 0 MTb); - mhi = multadd(mhi, 10, 0 MTb); - } - } - } - else - for(i = 1;; i++) { - dig = quorem(b,S) + '0'; - *s++ = dig; - if (!b->x[0] && b->wds <= 1) { -#ifdef SET_INEXACT - inexact = 0; -#endif - goto ret; - } - if (i >= ilim) - break; - b = multadd(b, 10, 0 MTb); - } - - /* Round off last digit */ - -#ifdef Honor_FLT_ROUNDS - if (mode > 1) - switch(Rounding) { - case 0: goto ret; - case 2: goto roundoff; - } -#endif - b = lshift(b, 1 MTb); - j = cmp(b, S); -#ifdef ROUND_BIASED - if (j >= 0) -#else - if (j > 0 || (j == 0 && dig & 1)) -#endif - { - roundoff: - while(*--s == '9') - if (s == buf) { - k++; - *s++ = '1'; - goto ret; - } - ++*s++; - } - ret: - Bfree(S MTb); - if (mhi) { - if (mlo && mlo != mhi) - Bfree(mlo MTb); - Bfree(mhi MTb); - } - retc: - while(s > buf && s[-1] == '0') - --s; - ret1: - if (b) - Bfree(b MTb); - *s = 0; - *decpt = k + 1; - if (rve) - *rve = s; -#ifdef SET_INEXACT - if (inexact) { - if (!oldinexact) { - word0(&u) = Exp_1 + (70 << Exp_shift); - word1(&u) = 0; - dval(&u) += 1.; - } - } - else if (!oldinexact) - clear_inexact(); -#endif - return buf; - } - - char * -dtoa(double dd, int mode, int ndigits, int *decpt, int *sign, char **rve) -{ - /* Sufficient space is allocated to the return value - to hold the suppressed trailing zeros. - See dtoa_r() above for details on the other arguments. - */ -#ifndef MULTIPLE_THREADS - if (dtoa_result) - freedtoa(dtoa_result); -#endif - return dtoa_r(dd, mode, ndigits, decpt, sign, rve, 0, 0); - } - -#ifdef __cplusplus -} -#endif \ No newline at end of file diff --git a/source/daemon/src/filehandler.cpp b/source/daemon/src/filehandler.cpp deleted file mode 100644 index c08c322b..00000000 --- a/source/daemon/src/filehandler.cpp +++ /dev/null @@ -1,514 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -//#include -#include -#include -#include - -using namespace CryptoPP; - -const unsigned long int lftpUploadTimeout = MuonPi::Config::Upload::timeout/*MUONPI_UPLOAD_TIMEOUT_MS*/; // in msecs -const int uploadReminderInterval = MuonPi::Config::Upload::reminder/*MUONPI_UPLOAD_REMINDER_MINUTES*/; // in minutes -const int logReminderInterval = MuonPi::Config::Log::interval/*MUONPI_LOG_INTERVAL_MINUTES*/; // in minutes - -static std::string SHA256HashString(std::string aString){ - std::string digest; - CryptoPP::SHA256 hash; - - CryptoPP::StringSource foo(aString, true, - new CryptoPP::HashFilter(hash, new CryptoPP::StringSink(digest))); - return digest; -} - -static QString getMacAddress(){ - QNetworkConfiguration nc; - QNetworkConfigurationManager ncm; - QList configsForEth,configsForWLAN,allConfigs; - // getting all the configs we can - foreach (nc,ncm.allConfigurations(QNetworkConfiguration::Active)) - { - if(nc.type() == QNetworkConfiguration::InternetAccessPoint) - { - // selecting the bearer type here - if(nc.bearerType() == QNetworkConfiguration::BearerWLAN) - { - configsForWLAN.append(nc); - } - if(nc.bearerType() == QNetworkConfiguration::BearerEthernet) - { - configsForEth.append(nc); - } - } - } - // further in the code WLAN's and Eth's were treated differently - allConfigs.append(configsForWLAN); - allConfigs.append(configsForEth); - QString MAC; - foreach(nc,allConfigs) - { - QNetworkSession networkSession(nc); - QNetworkInterface netInterface = networkSession.interface(); - // these last two conditions are for omiting the virtual machines' MAC - // works pretty good since no one changes their adapter name - if(!(netInterface.flags() & QNetworkInterface::IsLoopBack) - && !netInterface.humanReadableName().toLower().contains("vmware") - && !netInterface.humanReadableName().toLower().contains("virtual")) - { - MAC = QString(netInterface.hardwareAddress()); - break; - } - } - return MAC; -} - -static QByteArray getMacAddressByteArray(){ - //QString::fromLocal8Bit(temp.data()).toStdString(); - //return QByteArray(getMacAddress().toStdString().c_str()); -// return QByteArray::fromStdString(getMacAddress().toStdString()); - QString mac=getMacAddress(); - //qDebug()<<"MAC address: "<= 0x050a00 -// qint64 difftime=-now.secsTo(dataFile->fileTime(QFileDevice::FileMetadataChangeTime)); - qint64 difftime=-now.secsTo(dataFile->fileTime(QFileDevice::FileBirthTime)); -#else - qint64 difftime=-now.secsTo(fi.created()); -#endif - - return difftime; -} - -void FileHandler::start(){ - // set upload reminder - //qInfo() << this->thread()->objectName() << " thread id (pid): " << syscall(SYS_gettid); - QTimer *uploadReminder = new QTimer(this); - uploadReminder->setInterval(60*1000*uploadReminderInterval); // every 5 minutes or so - uploadReminder->setSingleShot(false); - connect(uploadReminder, &QTimer::timeout, this, &FileHandler::onUploadRemind); - uploadReminder->start(); - // open files that are currently written - openFiles(); - emit mqttConnect(username,password); - qDebug() << "sent mqttConnect"; -} - -// SLOTS -void FileHandler::onUploadRemind(){ - if (dataFile==nullptr){ - return; - } - QDateTime todaysRegularUploadTime = QDateTime(QDate::currentDate(),dailyUploadTime,Qt::TimeSpec::UTC); - if (dataFile->size()>(1024*1024*fileSize)){ - switchFiles(); - } - if (lastUploadDateTimetodaysRegularUploadTime){ - switchFiles(); - if (password.size() != 0 || username.size() != 0){ - //uploadRecentDataFiles(); // commented out because the upload server is not online - } - lastUploadDateTime = QDateTime::currentDateTimeUtc(); - } -} - -// DATA SAVING -bool FileHandler::openFiles(bool writeHeader){ - if (dataFile != nullptr || logFile != nullptr){ - closeFiles(); - } - if (currentWorkingFilePath==""||currentWorkingLogPath==""){ - readFileInformation(); - } - if (currentWorkingFilePath==""||currentWorkingLogPath==""){ - writeHeader=true; - QString fileNamePart = createFileName(); - currentWorkingFilePath = dataFolderPath+"data_"+fileNamePart; - currentWorkingLogPath = dataFolderPath+"log_"+fileNamePart; - while (notUploadedFilesNames.contains(QFileInfo(currentWorkingFilePath).fileName())){ - fileNamePart = createFileName(); - currentWorkingFilePath = dataFolderPath+"data_"+fileNamePart; - currentWorkingLogPath = dataFolderPath+"log_"+fileNamePart; - } - writeConfigFile(); - } - dataFile = new QFile(currentWorkingFilePath); - dataFile->setPermissions(defaultPermissions); - if (!dataFile->open(QIODevice::ReadWrite | QIODevice::Append)) { - qDebug() << "file open failed in 'ReadWrite' mode at location " << currentWorkingFilePath; - // the following return statement induced wrong behavior: - // in case the data file couldn't be opened, the log file QFile object would never be instantiated - // this would prevent local logging - //return false; - } - logFile = new QFile(currentWorkingLogPath); - logFile->setPermissions(defaultPermissions); - if (!logFile->open(QIODevice::ReadWrite | QIODevice::Append)) { - qDebug() << "file open failed in 'ReadWrite' mode at location " << currentWorkingLogPath; - //return false; - } - if (!dataFile->isOpen() || !logFile->isOpen()) return false; - // write header - if (writeHeader){ - QTextStream dataOut(dataFile); - dataOut << "#unix_timestamp_rising(s) unix_timestamp_trailing(s) time_accuracy(ns) valid timebase(0=gps,2=utc) utc_available\n"; - QTextStream logOut(logFile); - logOut << "#log parameters: time parname value unit\n"; - //onceLogFlag=true; - } - emit logRotateSignal(); - return true; -} - -void FileHandler::closeFiles(){ - if (dataFile!=nullptr){ - if (dataFile->isOpen()){ - dataFile->close(); - } - delete dataFile; - dataFile = nullptr; - } - if (logFile != nullptr){ - if (logFile->isOpen()){ - logFile->close(); - } - delete logFile; - logFile = nullptr; - } -} - -bool FileHandler::writeConfigFile(){ - QFile configFile(configFilePath); - if (!configFile.open(QIODevice::ReadWrite | QIODevice::Truncate)){ - qDebug() << "file open failed in 'ReadWrite' mode at location " << configFilePath; - return false; - } - configFile.resize(0); - QTextStream out(&configFile); - out << currentWorkingFilePath << endl << currentWorkingLogPath << endl; - return true; -} - -bool FileHandler::switchFiles(QString fileName){ - closeFiles(); - currentWorkingFilePath = "data_"+fileName; - currentWorkingLogPath = "log_"+fileName; - if (fileName==""){ - QString fileNamePart = createFileName(); - currentWorkingFilePath = dataFolderPath+"data_"+fileNamePart; - currentWorkingLogPath = dataFolderPath+"log_"+fileNamePart; - } - writeConfigFile(); - if (!openFiles(true)){ - closeFiles(); - return false; - } - return true; -} - -bool FileHandler::readFileInformation(){ - QDir directory(dataFolderPath); - notUploadedFilesNames = directory.entryList(QStringList() << "*.dat",QDir::Files); - QFile configFile(configFilePath); - if (!configFile.open(QIODevice::ReadWrite)){ - qDebug() << "file open failed in 'ReadWrite' mode at location " << configFilePath; - return false; - } - QTextStream in(&configFile); - if(configFile.size()==0){ - return true; - } - if (!in.atEnd()){ - currentWorkingFilePath = in.readLine(); - } - if (!in.atEnd()){ - currentWorkingLogPath = in.readLine(); - } - return true; -} - -void FileHandler::writeToDataFile(const QString &data){ - if (dataFile == nullptr){ - return; - } - QTextStream out(dataFile); - out << data << "\n"; -} - -void FileHandler::writeToLogFile(const QString& log) { - if (logFile == nullptr){ - return; - } - QTextStream out(logFile); - out << log << "\n"; -} - -QString FileHandler::createFileName(){ - // creates a fileName based on date time and mac address - if (dataFolderPath==""){ - qDebug() << "could not open data folder"; - return ""; - } - QString fileName = dateStringNow(); - fileName = fileName+".dat"; - return fileName; -} - -// upload related stuff - -bool FileHandler::uploadDataFile(QString fileName){ - char envName[] = "LFTP_PASSWORD"; - if (setenv(envName, password.toStdString().c_str(), 1)!=0){ - qDebug() << "setenv returned not 0"; - } - QProcess lftpProcess(this); - lftpProcess.setProgram("lftp"); - QStringList arguments; - arguments << "--env-password"; - arguments << "-p" << QString::number(MuonPi::Config::Upload::port/*MUONPI_UPLOAD_PORT*/); - arguments << "-u" << QString(username); - arguments << MuonPi::Config::Upload::url/*MUONPI_UPLOAD_URL*/; - arguments << "-e" << QString("mkdir "+hashedMacAddress+" ; cd "+hashedMacAddress+" && put "+fileName+" ; exit"); - lftpProcess.setArguments(arguments); - //qDebug() << lftpProcess.arguments(); - lftpProcess.start(); - //qDebug() << "started upload of " << fileName << "user:" << username << ";pw:" << password <<";"; - if (!lftpProcess.waitForFinished(lftpUploadTimeout)){ - qDebug() << lftpProcess.readAllStandardOutput(); - qDebug() << lftpProcess.readAllStandardError(); - qDebug() << "lftp not installed or timed out after "<< lftpUploadTimeout/1000<< " s"; - system("unset LFTP_PASSWORD"); - return false; - } - //qDebug() << "standard output" << lftpProcess.readAllStandardOutput(); - //qDebug() << "standard error:" << lftpProcess.readAllStandardError(); - //qDebug() << "exit status:" << lftpProcess.exitStatus(); - if (lftpProcess.exitStatus()!=0){ - qDebug() << "lftp returned exit status other than 0"; - unsetenv(envName); - return false; - } - unsetenv(envName); - return true; -} - -bool FileHandler::uploadRecentDataFiles(){ - readFileInformation(); - QDir lftpDir; - lftpDir.setPath(lftpDir.homePath()+"/.lftp"); - if (!lftpDir.exists()){ - lftpDir.mkpath("."); - } - QFile lftp_rc_file(lftpDir.path()+"/rc"); - if (!lftp_rc_file.exists()||lftp_rc_file.size()<10){ - if (!lftp_rc_file.open(QIODevice::ReadWrite)){ - qDebug() << "could not open .lftp/rc file"; - return false; - } - lftp_rc_file.write("set ssl:verify-certificate no\n"); - lftp_rc_file.close(); - } - for (auto &fileName : notUploadedFilesNames){ - QString filePath = dataFolderPath+fileName; - //qDebug() << "checking for upload: " << filePath; - if (filePath!=currentWorkingFilePath&&filePath!=currentWorkingLogPath){ - //qDebug() << "attempt to upload " << filePath; - if (!uploadDataFile(filePath)){ - qDebug() << "failed to upload recent files"; - return false; - } - //qDebug() << "success uploading recent files"; - QFile::rename(filePath,QString(configPath+"uploadedFiles/"+fileName)); - } - } - return true; -} - -// crypto related stuff - -bool FileHandler::saveLoginData(QString username, QString password){ - QFile loginDataFile(loginDataFilePath); - loginDataFile.setPermissions(QFileDevice::ReadOwner|QFileDevice::WriteOwner); - if(!loginDataFile.open(QIODevice::ReadWrite)){ - qDebug() << "could not open login data save file"; - return false; - } - loginDataFile.resize(0); - - AutoSeededRandomPool rnd; - std::string plainText = QString(username+";"+password).toStdString(); - std::string keyText; - std::string encrypted; - - keyText = SHA256HashString(getMacAddress().toStdString()); - SecByteBlock key((const byte*)keyText.data(),keyText.size()); - - // Generate a random IV - SecByteBlock iv(AES::BLOCKSIZE); - rnd.GenerateBlock(iv, iv.size()); - - //qDebug() << "key length = " << keyText.size(); - //qDebug() << "macAddressHashed = " << QByteArray::fromStdString(keyText).toHex(); - //qDebug() << "plainText = " << QString::fromStdString(plainText); - - ////////////////////////////////////////////////////////////////////////// - // Encrypt - - CFB_Mode::Encryption cfbEncryption; - cfbEncryption.SetKeyWithIV(key, key.size(), iv, iv.size()); - //cfbEncryption.ProcessData(cypheredText, plainText, messageLen); - - StringSource encryptor(plainText, true, - new StreamTransformationFilter(cfbEncryption, - new StringSink(encrypted))); - //qDebug() << "encrypted = " << QByteArray::fromStdString(encrypted).toHex(); - // write encrypted message and IV to file - loginDataFile.write((const char*)iv.data(),iv.size()); - loginDataFile.write(encrypted.c_str()); - return true; -} - -bool FileHandler::readLoginData(){ - QFile loginDataFile(loginDataFilePath); - if(!loginDataFile.open(QIODevice::ReadWrite)){ - qDebug() << "could not open login data save file"; - return false; - } - - std::string keyText; - std::string encrypted; - std::string recovered; - - keyText = SHA256HashString(getMacAddress().toStdString()); - SecByteBlock key((const byte*)keyText.data(),keyText.size()); - - // read encrypted message and IV from file - SecByteBlock iv(AES::BLOCKSIZE); - char ivData[AES::BLOCKSIZE]; - if (int read = loginDataFile.read(ivData,AES::BLOCKSIZE)!=AES::BLOCKSIZE){ - qDebug() << "read " << read << " bytes but should read " << AES::BLOCKSIZE << " bytes"; - return false; - } - iv.Assign((byte*)ivData, AES::BLOCKSIZE); - QByteArray data = loginDataFile.readAll(); - encrypted = std::string(data.constData(), data.length()); // <-- right :) - //QString::fromLocal8Bit(temp.data()).toStdString() <-- wrong!! - - ////////////////////////////////////////////////////////////////////////// - // Decrypt - CFB_Mode::Decryption cfbDecryption; - cfbDecryption.SetKeyWithIV(key, key.size(), iv, iv.size()); - //cfbDecryption.ProcessData(plainText, cypheredText, messageLen); - - StringSource decryptor(encrypted, true, - new StreamTransformationFilter(cfbDecryption, - new StringSink(recovered))); - QString recoverdQString = QString::fromStdString(recovered); - QStringList loginData = recoverdQString.split(';',QString::SkipEmptyParts); - if (loginData.size() < 2){ - return false; - } - username = loginData.at(0); - password = loginData.at(1); - return true; -} diff --git a/source/daemon/src/g_fmt.c b/source/daemon/src/g_fmt.c deleted file mode 100644 index 62c01cfb..00000000 --- a/source/daemon/src/g_fmt.c +++ /dev/null @@ -1,104 +0,0 @@ -/**************************************************************** - * - * The author of this software is David M. Gay. - * - * Copyright (c) 1991, 1996 by Lucent Technologies. - * - * Permission to use, copy, modify, and distribute this software for any - * purpose without fee is hereby granted, provided that this entire notice - * is included in all copies of any software which is or includes a copy - * or modification of this software and in all copies of the supporting - * documentation for such software. - * - * THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED - * WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR LUCENT MAKES ANY - * REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY - * OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE. - * - ***************************************************************/ - -/* g_fmt(buf,x) stores the closest decimal approximation to x in buf; - * it suffices to declare buf - * char buf[32]; - */ - -#ifdef __cplusplus -extern "C" { -#endif - extern char *dtoa(double, int, int, int *, int *, char **); - extern char *g_fmt(char *, double); - extern void freedtoa(char*); -#ifdef __cplusplus - } -#endif - - char * -g_fmt(register char *b, double x) -{ - register int i, k; - register char *s; - int decpt, j, sign; - char *b0, *s0, *se; - - b0 = b; -#ifdef IGNORE_ZERO_SIGN - if (!x) { - *b++ = '0'; - *b = 0; - goto done; - } -#endif - s = s0 = dtoa(x, 0, 0, &decpt, &sign, &se); - if (sign) - *b++ = '-'; - if (decpt == 9999) /* Infinity or Nan */ { - while(*b++ = *s++); - goto done0; - } - if (decpt <= -4 || decpt > se - s + 5) { - *b++ = *s++; - if (*s) { - *b++ = '.'; - while(*b = *s++) - b++; - } - *b++ = 'e'; - /* sprintf(b, "%+.2d", decpt - 1); */ - if (--decpt < 0) { - *b++ = '-'; - decpt = -decpt; - } - else - *b++ = '+'; - for(j = 2, k = 10; 10*k <= decpt; j++, k *= 10); - for(;;) { - i = decpt / k; - *b++ = i + '0'; - if (--j <= 0) - break; - decpt -= i*k; - decpt *= 10; - } - *b = 0; - } - else if (decpt <= 0) { - *b++ = '.'; - for(; decpt < 0; decpt++) - *b++ = '0'; - while(*b++ = *s++); - } - else { - while(*b = *s++) { - b++; - if (--decpt == 0 && *s) - *b++ = '.'; - } - for(; decpt > 0; decpt--) - *b++ = '0'; - *b = 0; - } - done0: - freedtoa(s0); - done: - return b0; - } \ No newline at end of file diff --git a/source/daemon/src/geohash.cpp b/source/daemon/src/geohash.cpp deleted file mode 100644 index a55e347e..00000000 --- a/source/daemon/src/geohash.cpp +++ /dev/null @@ -1,58 +0,0 @@ -#include -#include - -static const QString base32 = "0123456789bcdefghjkmnpqrstuvwxyz"; // (geohash-specific) Base32 map - -/** - * Geohash: Gustavo Niemeyer’s geocoding system. - */ -QString GeoHash::hashFromCoordinates(double lon, double lat, int precision) -{ - if (precision<0 || precision>12) precision=12; - - uint8_t idx = 0; // index into base32 map - uint8_t bit = 0; // each char holds 5 bits - bool evenBit = true; - QString geohash = ""; - - double latMin = -90., latMax = 90.; - double lonMin = -180., lonMax = 180.; - - if (lonlonMax) return geohash; - if (latlatMax) return geohash; - - while (geohash.size() < precision) { - if (evenBit) { - // bisect E-W longitude - const double lonMid = (lonMin + lonMax) / 2.; - if (lon >= lonMid) { - idx = idx*2 + 1; - lonMin = lonMid; - } else { - idx = idx*2; - lonMax = lonMid; - } - } else { - // bisect N-S latitude - const double latMid = (latMin + latMax) / 2.; - if (lat >= latMid) { - idx = idx*2 + 1; - latMin = latMid; - } else { - idx = idx*2; - latMax = latMid; - } - } - evenBit = !evenBit; - - if (++bit == 5) { - // 5 bits gives us a character: append it and start over - geohash += base32.at(idx); - //qDebug()<<"hashstr="< last) { - if (outputAllAddresses) { - printf(" "); - } - continue; - } - - /* Set slave address */ - if (ioctl(file, I2C_SLAVE, i + j) < 0) { - if (errno == EBUSY) { - printf("UU "); - continue; - } - else { - fprintf(stderr, "Error: Could not set " - "address to 0x%02x: %s\n", i + j, - strerror(errno)); - return -1; - } - } - - /* Probe this address */ - /*switch (mode) { - default:*/ - if ((i + j >= 0x30 && i + j <= 0x37) - || (i + j >= 0x50 && i + j <= 0x5F)) { - res = i2c_smbus_read_byte(file); - } - else { - res = i2c_smbus_write_quick(file, - I2C_SMBUS_WRITE); - } - //} - - if (outputAllAddresses) { - if (res < 0) { - printf("-- "); - /* there is no device at this address (address is j+i) - so switch j+i and if the address matches one of the expected - addresses used by one of the components on the board - the program should exit with an error - */ - - } - else { - printf("%02x ", i + j); - } - } - } - if (outputAllAddresses) { - printf("\n"); - } - } - if (deviceError) - { - // print missing devices if there are any - // and exit with error which is meant by "return 1" - printf("\n Following addresses are not connected: \n"); - for (int k = 0; k < 8; k++) - { - if (deviceStatus[k] != 0) - { - switch (deviceStatus[k]) - { - case ADC1_ADDR: - printf("ADC1_ADDR"); - break; - case ADC2_ADDR: - printf("ADC2_ADDR"); - break; - case LM75_ADDR: - printf("LM75_ADDR"); - break; - case POTI1_ADDR: - printf("POTI1_ADDR"); - break; - case POTI2_ADDR: - printf("POTI2_ADDR"); - break; - case POTI3_ADDR: - printf("POTI3_ADDR"); - break; - case POTI4_ADDR: - printf("POTI4_ADDR"); - break; - case EEP_ADDR: - printf("EEP_ADDR"); - break; - default: - break; - } - printf(" = %0x \n", +deviceStatus[k]); - } - } - return 1; - } - return 0; -} - -//struct func -//{ -// // from original i2cdetect code, not important -// long value; -// const char* name; -//}; - - -//static const struct func all_func[] = { -// // from original i2cdetect code, not important -// // from original i2cdetect code, not important -// { .value = I2C_FUNC_I2C, -// .name = "I2C" }, -// { .value = I2C_FUNC_SMBUS_QUICK, -// .name = "SMBus Quick Command" }, -// { .value = I2C_FUNC_SMBUS_WRITE_BYTE, -// .name = "SMBus Send Byte" }, -// { .value = I2C_FUNC_SMBUS_READ_BYTE, -// .name = "SMBus Receive Byte" }, -// { .value = I2C_FUNC_SMBUS_WRITE_BYTE_DATA, -// .name = "SMBus Write Byte" }, -// { .value = I2C_FUNC_SMBUS_READ_BYTE_DATA, -// .name = "SMBus Read Byte" }, -// { .value = I2C_FUNC_SMBUS_WRITE_WORD_DATA, -// .name = "SMBus Write Word" }, -// { .value = I2C_FUNC_SMBUS_READ_WORD_DATA, -// .name = "SMBus Read Word" }, -// { .value = I2C_FUNC_SMBUS_PROC_CALL, -// .name = "SMBus Process Call" }, -// { .value = I2C_FUNC_SMBUS_WRITE_BLOCK_DATA, -// .name = "SMBus Block Write" }, -// { .value = I2C_FUNC_SMBUS_READ_BLOCK_DATA, -// .name = "SMBus Block Read" }, -// { .value = I2C_FUNC_SMBUS_BLOCK_PROC_CALL, -// .name = "SMBus Block Process Call" }, -// { .value = I2C_FUNC_SMBUS_PEC, -// .name = "SMBus PEC" }, -// { .value = I2C_FUNC_SMBUS_WRITE_I2C_BLOCK, -// .name = "I2C Block Write" }, -// { .value = I2C_FUNC_SMBUS_READ_I2C_BLOCK, -// .name = "I2C Block Read" }, -// { .value = 0, .name = "" } -//}; - -//static void print_functionality(unsigned long funcs) -//{ -// // from original i2cdetect code, not important -// int i; -// for (i = 0; all_func[i].value; i++) { -// printf("%-32s %s\n", all_func[i].name, -// (funcs & all_func[i].value) ? "yes" : "no"); -// } -//} - -/* - * Print the installed i2c busses. The format is those of Linux 2.4's - * /proc/bus/i2c for historical compatibility reasons. - -static void print_i2c_busses(void) -{ - struct i2c_adap *adapters; - int count; - - adapters = gather_i2c_busses(); - if (adapters == NULL) { - fprintf(stderr, "Error: Out of memory!\n"); - return; - } - - for (count = 0; adapters[count].name; count++) { - printf("i2c-%d\t%-10s\t%-32s\t%s\n", - adapters[count].nr, adapters[count].funcs, - adapters[count].name, adapters[count].algo); - } - - free_adapters(adapters); -} -// from original i2cdetect code, not important - -*/ -//int i2cdetect(){ -// int expectedAddresses[] = {}; -// return i2cdetect(true,expectedAddresses); -//} -//int i2cdetect(int expectedAddresses[]){ -// return i2cdetect(false,expectedAddresses); -//} -// c does not like overloading .... -int i2cdetect(bool outputAllAddresses, int expectedAddresses[]) -{ - // can be called by main program, used to check devices (are all connected devices in place?). Soon to be further improved! - //char *end; - int /*i2cbus,*/ file, res; - char filename[20]; - unsigned long funcs; - //int mode = MODE_AUTO; - int first = 0x03, last = 0x77; - //int flags = 0; - //int yes = 1, version = 0, list = 0; - - if (I2C_BUS < 0) { - //help(); - printf("set I2C_BUS not possible (<0)"); - exit(1); - } - - file = open_i2c_dev(I2C_BUS, filename, sizeof(filename), 0); - if (file < 0) { - exit(1); - } - - if (ioctl(file, I2C_FUNCS, &funcs) < 0) { - fprintf(stderr, "Error: Could not get the adapter " - "functionality matrix: %s\n", strerror(errno)); - close(file); - exit(1); - } - - /* - if (!yes) { - char s[2]; - - fprintf(stderr, "WARNING! This program can confuse your I2C " - "bus, cause data loss and worse!\n"); - - fprintf(stderr, "I will probe file %s%s.\n", filename, - mode==MODE_QUICK?" using quick write commands": - mode==MODE_READ?" using read byte commands":""); - fprintf(stderr, "I will probe address range 0x%02x-0x%02x.\n", - first, last); - - fprintf(stderr, "Continue? [Y/n] "); - fflush(stderr); - if (!fgets(s, 2, stdin) - || (s[0] != '\n' && s[0] != 'y' && s[0] != 'Y')) { - fprintf(stderr, "Aborting on user request.\n"); - exit(0); - } - } - // from original i2cdetect code, not important - */ - res = scan_i2c_bus(file, /*mode,*/ first, last, - outputAllAddresses, expectedAddresses); - // res will be either 1 or 0 - // 0 means all ok - // 1 means there are missing devices - close(file); - - return(res ? 1 : 0); -} diff --git a/source/daemon/src/i2c/i2cbusses.c b/source/daemon/src/i2c/i2cbusses.c deleted file mode 100644 index 7651fc57..00000000 --- a/source/daemon/src/i2c/i2cbusses.c +++ /dev/null @@ -1,377 +0,0 @@ -#include "i2c/i2cbusses.h" - -enum adt { adt_dummy, adt_isa, adt_i2c, adt_smbus, adt_unknown }; - -struct adap_type { - const char *funcs; - const char* algo; -}; - -static struct adap_type adap_types[5] = { - {.funcs = "dummy", - .algo = "Dummy bus", }, - {.funcs = "isa", - .algo = "ISA bus", }, - {.funcs = "i2c", - .algo = "I2C adapter", }, - {.funcs = "smbus", - .algo = "SMBus adapter", }, - {.funcs = "unknown", - .algo = "N/A", }, -}; - -static enum adt i2c_get_funcs(int i2cbus) -{ - unsigned long funcs; - int file; - char filename[20]; - enum adt ret; - - file = open_i2c_dev(i2cbus, filename, sizeof(filename), 1); - if (file < 0) - return adt_unknown; - - if (ioctl(file, I2C_FUNCS, &funcs) < 0) - ret = adt_unknown; - else if (funcs & I2C_FUNC_I2C) - ret = adt_i2c; - else if (funcs & (I2C_FUNC_SMBUS_BYTE | - I2C_FUNC_SMBUS_BYTE_DATA | - I2C_FUNC_SMBUS_WORD_DATA)) - ret = adt_smbus; - else - ret = adt_dummy; - - close(file); - return ret; -} - -/* Remove trailing spaces from a string - Return the new string length including the trailing NUL */ -static int rtrim(char *s) -{ - int i; - - for (i = strlen(s) - 1; i >= 0 && (s[i] == ' ' || s[i] == '\n'); i--) - s[i] = '\0'; - return i + 2; -} - -void free_adapters(struct i2c_adap *adapters) -{ - int i; - - for (i = 0; adapters[i].name; i++) - free(adapters[i].name); - free(adapters); -} - -/* We allocate space for the adapters in bunches. The last item is a - terminator, so here we start with room for 7 adapters, which should - be enough in most cases. If not, we allocate more later as needed. */ -#define BUNCH 8 - - /* n must match the size of adapters at calling time */ -static struct i2c_adap *more_adapters(struct i2c_adap *adapters, int n) -{ - struct i2c_adap *new_adapters; - - new_adapters = realloc(adapters, (n + BUNCH) * sizeof(struct i2c_adap)); - if (!new_adapters) { - free_adapters(adapters); - return NULL; - } - memset(new_adapters + n, 0, BUNCH * sizeof(struct i2c_adap)); - - return new_adapters; -} - -struct i2c_adap *gather_i2c_busses(void) -{ - char s[120]; - struct dirent *de, *dde; - DIR *dir, *ddir; - FILE *f; - char fstype[NAME_MAX], sysfs[NAME_MAX], n[NAME_MAX]; - int foundsysfs = 0; - int count = 0; - struct i2c_adap *adapters; - - adapters = calloc(BUNCH, sizeof(struct i2c_adap)); - if (!adapters) - return NULL; - - /* look in /proc/bus/i2c */ - if ((f = fopen("/proc/bus/i2c", "r"))) { - while (fgets(s, 120, f)) { - char *algo, *name, *type, *all; - int len_algo, len_name, len_type; - int i2cbus; - - algo = strrchr(s, '\t'); - *(algo++) = '\0'; - len_algo = rtrim(algo); - - name = strrchr(s, '\t'); - *(name++) = '\0'; - len_name = rtrim(name); - - type = strrchr(s, '\t'); - *(type++) = '\0'; - len_type = rtrim(type); - - sscanf(s, "i2c-%d", &i2cbus); - - if ((count + 1) % BUNCH == 0) { - /* We need more space */ - adapters = more_adapters(adapters, count + 1); - if (!adapters) - return NULL; - } - - all = malloc(len_name + len_type + len_algo); - if (all == NULL) { - free_adapters(adapters); - return NULL; - } - adapters[count].nr = i2cbus; - adapters[count].name = strcpy(all, name); - adapters[count].funcs = strcpy(all + len_name, type); - adapters[count].algo = strcpy(all + len_name + len_type, - algo); - count++; - } - fclose(f); - goto done; - } - - /* look in sysfs */ - /* First figure out where sysfs was mounted */ - if ((f = fopen("/proc/mounts", "r")) == NULL) { - goto done; - } - while (fgets(n, NAME_MAX, f)) { - sscanf(n, "%*[^ ] %[^ ] %[^ ] %*s\n", sysfs, fstype); - if (strcasecmp(fstype, "sysfs") == 0) { - foundsysfs++; - break; - } - } - fclose(f); - if (!foundsysfs) { - goto done; - } - - /* Bus numbers in i2c-adapter don't necessarily match those in - i2c-dev and what we really care about are the i2c-dev numbers. - Unfortunately the names are harder to get in i2c-dev */ - strcat(sysfs, "/class/i2c-dev"); - if (!(dir = opendir(sysfs))) - goto done; - /* go through the busses */ - while ((de = readdir(dir)) != NULL) { - if (!strcmp(de->d_name, ".")) - continue; - if (!strcmp(de->d_name, "..")) - continue; - - /* this should work for kernels 2.6.5 or higher and */ - /* is preferred because is unambiguous */ - sprintf(n, "%s/%s/name", sysfs, de->d_name); - f = fopen(n, "r"); - /* this seems to work for ISA */ - if (f == NULL) { - sprintf(n, "%s/%s/device/name", sysfs, de->d_name); - f = fopen(n, "r"); - } - /* non-ISA is much harder */ - /* and this won't find the correct bus name if a driver - has more than one bus */ - if (f == NULL) { - sprintf(n, "%s/%s/device", sysfs, de->d_name); - if (!(ddir = opendir(n))) - continue; - while ((dde = readdir(ddir)) != NULL) { - if (!strcmp(dde->d_name, ".")) - continue; - if (!strcmp(dde->d_name, "..")) - continue; - if ((!strncmp(dde->d_name, "i2c-", 4))) { - sprintf(n, "%s/%s/device/%s/name", - sysfs, de->d_name, dde->d_name); - if ((f = fopen(n, "r"))) - goto found; - } - } - } - - found: - if (f != NULL) { - int i2cbus; - enum adt type; - char *px; - - px = fgets(s, 120, f); - fclose(f); - if (!px) { - fprintf(stderr, "%s: read error\n", n); - continue; - } - if ((px = strchr(s, '\n')) != NULL) - *px = 0; - if (!sscanf(de->d_name, "i2c-%d", &i2cbus)) - continue; - if (!strncmp(s, "ISA ", 4)) { - type = adt_isa; - } - else { - /* Attempt to probe for adapter capabilities */ - type = i2c_get_funcs(i2cbus); - } - - if ((count + 1) % BUNCH == 0) { - /* We need more space */ - adapters = more_adapters(adapters, count + 1); - if (!adapters) - return NULL; - } - - adapters[count].nr = i2cbus; - adapters[count].name = strdup(s); - if (adapters[count].name == NULL) { - free_adapters(adapters); - return NULL; - } - adapters[count].funcs = adap_types[type].funcs; - adapters[count].algo = adap_types[type].algo; - count++; - } - } - closedir(dir); - -done: - return adapters; -} - -static int lookup_i2c_bus_by_name(const char *bus_name) -{ - struct i2c_adap *adapters; - int i, i2cbus = -1; - - adapters = gather_i2c_busses(); - if (adapters == NULL) { - fprintf(stderr, "Error: Out of memory!\n"); - return -3; - } - - /* Walk the list of i2c busses, looking for the one with the - right name */ - for (i = 0; adapters[i].name; i++) { - if (strcmp(adapters[i].name, bus_name) == 0) { - if (i2cbus >= 0) { - fprintf(stderr, - "Error: I2C bus name is not unique!\n"); - i2cbus = -4; - goto done; - } - i2cbus = adapters[i].nr; - } - } - - if (i2cbus == -1) - fprintf(stderr, "Error: I2C bus name doesn't match any " - "bus present!\n"); - -done: - free_adapters(adapters); - return i2cbus; -} - -/* - * Parse an I2CBUS command line argument and return the corresponding - * bus number, or a negative value if the bus is invalid. - */ -int lookup_i2c_bus(const char *i2cbus_arg) -{ - unsigned long i2cbus; - char *end; - - i2cbus = strtoul(i2cbus_arg, &end, 0); - if (*end || !*i2cbus_arg) { - /* Not a number, maybe a name? */ - return lookup_i2c_bus_by_name(i2cbus_arg); - } - if (i2cbus > 0xFFFFF) { - fprintf(stderr, "Error: I2C bus out of range!\n"); - return -2; - } - - return i2cbus; -} - -/* - * Parse a CHIP-ADDRESS command line argument and return the corresponding - * chip address, or a negative value if the address is invalid. - */ -int parse_i2c_address(const char *address_arg) -{ - long address; - char *end; - - address = strtol(address_arg, &end, 0); - if (*end || !*address_arg) { - fprintf(stderr, "Error: Chip address is not a number!\n"); - return -1; - } - if (address < 0x03 || address > 0x77) { - fprintf(stderr, "Error: Chip address out of range " - "(0x03-0x77)!\n"); - return -2; - } - - return address; -} - -int open_i2c_dev(int i2cbus, char *filename, size_t size, int quiet) -{ - int file; - - snprintf(filename, size, "/dev/i2c/%d", i2cbus); - filename[size - 1] = '\0'; - file = open(filename, O_RDWR); - - if (file < 0 && (errno == ENOENT || errno == ENOTDIR)) { - sprintf(filename, "/dev/i2c-%d", i2cbus); - file = open(filename, O_RDWR); - } - - if (file < 0 && !quiet) { - if (errno == ENOENT) { - fprintf(stderr, "Error: Could not open file " - "`/dev/i2c-%d' or `/dev/i2c/%d': %s\n", - i2cbus, i2cbus, strerror(ENOENT)); - } - else { - fprintf(stderr, "Error: Could not open file " - "`%s': %s\n", filename, strerror(errno)); - if (errno == EACCES) - fprintf(stderr, "Run as root?\n"); - } - } - - return file; -} - -int set_slave_addr(int file, int address, int force) -{ - /* With force, let the user read from/write to the registers - even when a driver is also running */ - if (ioctl(file, force ? I2C_SLAVE_FORCE : I2C_SLAVE, address) < 0) { - fprintf(stderr, - "Error: Could not set address to 0x%02x: %s\n", - address, strerror(errno)); - return -errno; - } - - return 0; -} diff --git a/source/daemon/src/i2c/i2cdevices/Adafruit_GFX.cpp b/source/daemon/src/i2c/i2cdevices/Adafruit_GFX.cpp deleted file mode 100644 index fcb34413..00000000 --- a/source/daemon/src/i2c/i2cdevices/Adafruit_GFX.cpp +++ /dev/null @@ -1,616 +0,0 @@ -/****************************************************************** - This is the core graphics library for all our displays, providing - basic graphics primitives (points, lines, circles, etc.). It needs - to be paired with a hardware-specific library for each display - device we carry (handling the lower-level functions). - - Adafruit invests time and resources providing this open - source code, please support Adafruit and open-source hardware - by purchasing products from Adafruit! - - Written by Limor Fried/Ladyada for Adafruit Industries. - BSD license, check license.txt for more information. - All text above must be included in any redistribution. - -02/18/2013 Charles-Henri Hallard (http://hallard.me) - Modified for compiling and use on Raspberry ArduiPi Board - LCD size and connection are now passed as arguments on - the command line (no more #define on compilation needed) - ArduiPi project documentation http://hallard.me/arduipi -07/01/2013 Charles-Henri Hallard (http://hallard.me) - Created Draw Bargraph feature - Added printf feature - - ******************************************************************/ - -#include "i2c/i2cdevices/Adafruit_GFX.h" -#include "glcdfont.c" -#include -#include - -void Adafruit_GFX::constructor(int16_t w, int16_t h) -{ - _width = WIDTH = w; - _height = HEIGHT = h; - - rotation = 0; - cursor_y = cursor_x = 0; - textsize = 1; - textcolor = textbgcolor = 0xFFFF; - wrap = true; -} - -// the printf function -void Adafruit_GFX::printf( const char * format, ...) -{ - - char buffer[64]; - char * p = buffer; - int n; - va_list args; - va_start (args, format); - vsnprintf (buffer, sizeof(buffer)-1, format, args); - n = strlen(buffer); - - while (*p != 0 && n-->0) - { - write ( (uint8_t) *p++); - } - - va_end (args); -} - -// the print function -void Adafruit_GFX::print( const char * string) -{ - - const char * p = string; - int n = strlen(string); - - while (*p != 0 && n-->0) - { - write ( (uint8_t) *p++); - } - -} - - -// draw a circle outline -void Adafruit_GFX::drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color) -{ - int16_t f = 1 - r; - int16_t ddF_x = 1; - int16_t ddF_y = -2 * r; - int16_t x = 0; - int16_t y = r; - - drawPixel(x0, y0+r, color); - drawPixel(x0, y0-r, color); - drawPixel(x0+r, y0, color); - drawPixel(x0-r, y0, color); - - while (x= 0) - { - y--; - ddF_y += 2; - f += ddF_y; - } - - x++; - ddF_x += 2; - f += ddF_x; - - drawPixel(x0 + x, y0 + y, color); - drawPixel(x0 - x, y0 + y, color); - drawPixel(x0 + x, y0 - y, color); - drawPixel(x0 - x, y0 - y, color); - drawPixel(x0 + y, y0 + x, color); - drawPixel(x0 - y, y0 + x, color); - drawPixel(x0 + y, y0 - x, color); - drawPixel(x0 - y, y0 - x, color); - - } -} - -void Adafruit_GFX::drawCircleHelper( int16_t x0, int16_t y0, int16_t r, uint8_t cornername, uint16_t color) -{ - int16_t f = 1 - r; - int16_t ddF_x = 1; - int16_t ddF_y = -2 * r; - int16_t x = 0; - int16_t y = r; - - while (x= 0) - { - y--; - ddF_y += 2; - f += ddF_y; - } - - x++; - ddF_x += 2; - f += ddF_x; - if (cornername & 0x4) - { - drawPixel(x0 + x, y0 + y, color); - drawPixel(x0 + y, y0 + x, color); - } - if (cornername & 0x2) - { - drawPixel(x0 + x, y0 - y, color); - drawPixel(x0 + y, y0 - x, color); - } - if (cornername & 0x8) - { - drawPixel(x0 - y, y0 + x, color); - drawPixel(x0 - x, y0 + y, color); - } - if (cornername & 0x1) - { - drawPixel(x0 - y, y0 - x, color); - drawPixel(x0 - x, y0 - y, color); - } - } -} - -void Adafruit_GFX::fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color) -{ - drawFastVLine(x0, y0-r, 2*r+1, color); - fillCircleHelper(x0, y0, r, 3, 0, color); -} - -// used to do circles and roundrects! -void Adafruit_GFX::fillCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername, int16_t delta, uint16_t color) -{ - int16_t f = 1 - r; - int16_t ddF_x = 1; - int16_t ddF_y = -2 * r; - int16_t x = 0; - int16_t y = r; - - while (x= 0) - { - y--; - ddF_y += 2; - f += ddF_y; - } - - x++; - ddF_x += 2; - f += ddF_x; - - if (cornername & 0x1) - { - drawFastVLine(x0+x, y0-y, 2*y+1+delta, color); - drawFastVLine(x0+y, y0-x, 2*x+1+delta, color); - } - - if (cornername & 0x2) - { - drawFastVLine(x0-x, y0-y, 2*y+1+delta, color); - drawFastVLine(x0-y, y0-x, 2*x+1+delta, color); - } - } -} - -// bresenham's algorithm - thx wikpedia -void Adafruit_GFX::drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint16_t color) -{ - int16_t steep = abs(y1 - y0) > abs(x1 - x0); - - if (steep) - { - swap(x0, y0); - swap(x1, y1); - } - - if (x0 > x1) - { - swap(x0, x1); - swap(y0, y1); - } - - int16_t dx, dy; - dx = x1 - x0; - dy = abs(y1 - y0); - - int16_t err = dx / 2; - int16_t ystep; - - if (y0 < y1) - { - ystep = 1; - } - else - { - ystep = -1; - } - - for (; x0<=x1; x0++) - { - if (steep) - { - drawPixel(y0, x0, color); - } - else - { - drawPixel(x0, y0, color); - } - err -= dy; - - if (err < 0) - { - y0 += ystep; - err += dx; - } - } -} - - -// draw a rectangle -void Adafruit_GFX::drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) -{ - drawFastHLine(x, y, w, color); - drawFastHLine(x, y+h-1, w, color); - drawFastVLine(x, y, h, color); - drawFastVLine(x+w-1, y, h, color); -} - -void Adafruit_GFX::drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color) -{ - // stupidest version - update in subclasses if desired! - drawLine(x, y, x, y+h-1, color); -} - - -void Adafruit_GFX::drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color) -{ - // stupidest version - update in subclasses if desired! - drawLine(x, y, x+w-1, y, color); -} - -void Adafruit_GFX::fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) -{ - // stupidest version - update in subclasses if desired! - for (int16_t i=x; i2 && w>2 ) - { - // calculate pixel size of bargraph - vsize = ( ( h - 2) * percent ) / 100 ; - - // Fill it from bottom (0%) to top (100%) - fillRect(x+1,y+1 + (( h-2)-vsize), w - 2, vsize, color); - } -} - -// draw a horizontal bargraph and fill it with percent value (0%..100%) -void Adafruit_GFX::drawHorizontalBargraph(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color, uint16_t percent) -{ - uint16_t hsize; - - // Create rectangle - drawRect(x,y, w, h, color) ; - - // Do not do stupid job - if ( h>2 && w>2 ) - { - // calculate pixel size of bargraph - hsize = ( ( w - 2) * percent ) / 100 ; - - // Fill it from left (0%) to right (100%) - fillRect(x+1 , y+1 , hsize, h - 2, color); - } -} - - -void Adafruit_GFX::fillScreen(uint16_t color) -{ - fillRect(0, 0, _width, _height, color); -} - -// draw a rounded rectangle! -void Adafruit_GFX::drawRoundRect(int16_t x, int16_t y, int16_t w, int16_t h, int16_t r, uint16_t color) -{ - - // smarter version - drawFastHLine(x+r , y , w-2*r, color); // Top - drawFastHLine(x+r , y+h-1, w-2*r, color); // Bottom - drawFastVLine( x , y+r , h-2*r, color); // Left - drawFastVLine( x+w-1, y+r , h-2*r, color); // Right - - // draw four corners - drawCircleHelper(x+r , y+r , r, 1, color); - drawCircleHelper(x+w-r-1, y+r , r, 2, color); - drawCircleHelper(x+w-r-1, y+h-r-1, r, 4, color); - drawCircleHelper(x+r , y+h-r-1, r, 8, color); -} - -// fill a rounded rectangle! -void Adafruit_GFX::fillRoundRect(int16_t x, int16_t y, int16_t w, int16_t h, int16_t r, uint16_t color) -{ - // smarter version - fillRect(x+r, y, w-2*r, h, color); - - // draw four corners - fillCircleHelper(x+w-r-1, y+r, r, 1, h-2*r-1, color); - fillCircleHelper(x+r , y+r, r, 2, h-2*r-1, color); -} - -// draw a triangle! -void Adafruit_GFX::drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t x2, int16_t y2, uint16_t color) -{ - drawLine(x0, y0, x1, y1, color); - drawLine(x1, y1, x2, y2, color); - drawLine(x2, y2, x0, y0, color); -} - -// fill a triangle! -void Adafruit_GFX::fillTriangle ( int16_t x0, int16_t y0, int16_t x1, int16_t y1, int16_t x2, int16_t y2, uint16_t color) -{ - - int16_t a, b, y, last; - - // Sort coordinates by Y order (y2 >= y1 >= y0) - if (y0 > y1) - { - swap(y0, y1); swap(x0, x1); - } - if (y1 > y2) - { - swap(y2, y1); swap(x2, x1); - } - if (y0 > y1) - { - swap(y0, y1); swap(x0, x1); - } - - if(y0 == y2) - { // Handle awkward all-on-same-line case as its own thing - a = b = x0; - if(x1 < a) a = x1; - else if(x1 > b) b = x1; - if(x2 < a) a = x2; - else if(x2 > b) b = x2; - drawFastHLine(a, y0, b-a+1, color); - return; - } - - int16_t - dx01 = x1 - x0, - dy01 = y1 - y0, - dx02 = x2 - x0, - dy02 = y2 - y0, - dx12 = x2 - x1, - dy12 = y2 - y1, - sa = 0, - sb = 0; - - // For upper part of triangle, find scanline crossings for segments - // 0-1 and 0-2. If y1=y2 (flat-bottomed triangle), the scanline y1 - // is included here (and second loop will be skipped, avoiding a /0 - // error there), otherwise scanline y1 is skipped here and handled - // in the second loop...which also avoids a /0 error here if y0=y1 - // (flat-topped triangle). - if(y1 == y2) - last = y1; // Include y1 scanline - else - last = y1-1; // Skip it - - for(y=y0; y<=last; y++) - { - a = x0 + sa / dy01; - b = x0 + sb / dy02; - sa += dx01; - sb += dx02; - /* longhand: - a = x0 + (x1 - x0) * (y - y0) / (y1 - y0); - b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); - */ - if(a > b) - swap(a,b); - - drawFastHLine(a, y, b-a+1, color); - } - - // For lower part of triangle, find scanline crossings for segments - // 0-2 and 1-2. This loop is skipped if y1=y2. - sa = dx12 * (y - y1); - sb = dx02 * (y - y0); - for(; y<=y2; y++) - { - a = x1 + sa / dy12; - b = x0 + sb / dy02; - sa += dx12; - sb += dx02; - /* longhand: - a = x1 + (x2 - x1) * (y - y1) / (y2 - y1); - b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); - */ - if(a > b) - swap(a,b); - - drawFastHLine(a, y, b-a+1, color); - } -} - -void Adafruit_GFX::drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color) -{ - - int16_t i, j, byteWidth = (w + 7) / 8; - - for(j=0; j> (i & 7))) - { - drawPixel(x+i, y+j, color); - } - } - } -} - - -size_t Adafruit_GFX::write(uint8_t c) -{ - if (c == '\n') - { - cursor_y += textsize*8; - cursor_x = 0; - } - else if (c == '\r') - { - // skip em - } - else - { - drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); - cursor_x += textsize*6; - - if (wrap && (cursor_x > (_width - textsize*6))) - { - cursor_y += textsize*8; - cursor_x = 0; - } - } - return 1; -} - -// draw a character -void Adafruit_GFX::drawChar(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t bg, uint8_t size) -{ - - if((x >= _width) || // Clip right - (y >= _height) || // Clip bottom - ((x + 5 * size - 1) < 0) || // Clip left - ((y + 8 * size - 1) < 0)) // Clip top - return; - - for (int8_t i=0; i<6; i++ ) - { - uint8_t line; - if (i == 5) - line = 0x0; - else - //line = pgm_read_byte(font+(c*5)+i); - line = font[(c*5)+i]; - for (int8_t j = 0; j<8; j++) - { - if (line & 0x1) - { - if (size == 1) // default size - drawPixel(x+i, y+j, color); - else - { // big size - fillRect(x+(i*size), y+(j*size), size, size, color); - } - } - else if (bg != color) - { - if (size == 1) // default size - drawPixel(x+i, y+j, bg); - else - { // big size - fillRect(x+i*size, y+j*size, size, size, bg); - } - } - - line >>= 1; - } - } -} - -void Adafruit_GFX::setCursor(int16_t x, int16_t y) -{ - cursor_x = x; - cursor_y = y; -} - - -void Adafruit_GFX::setTextSize(uint8_t s) -{ - textsize = (s > 0) ? s : 1; -} - - -void Adafruit_GFX::setTextColor(uint16_t c) -{ - textcolor = c; - textbgcolor = c; - // for 'transparent' background, we'll set the bg - // to the same as fg instead of using a flag -} - -void Adafruit_GFX::setTextColor(uint16_t c, uint16_t b) -{ - textcolor = c; - textbgcolor = b; - } - -void Adafruit_GFX::setTextWrap(bool w) -{ - wrap = w; -} - -uint8_t Adafruit_GFX::getRotation(void) -{ - rotation %= 4; - return rotation; -} - -void Adafruit_GFX::setRotation(uint8_t x) -{ - x %= 4; // cant be higher than 3 - rotation = x; - switch (x) - { - case 0: - case 2: - _width = WIDTH; - _height = HEIGHT; - break; - - case 1: - case 3: - _width = HEIGHT; - _height = WIDTH; - break; - } -} - -void Adafruit_GFX::invertDisplay(bool i) -{ - // do nothing, can be subclassed -} - - -// return the size of the display which depends on the rotation! -int16_t Adafruit_GFX::width(void) -{ - return _width; -} - -int16_t Adafruit_GFX::height(void) -{ - return _height; -} diff --git a/source/daemon/src/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp b/source/daemon/src/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp deleted file mode 100644 index 82f28528..00000000 --- a/source/daemon/src/i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.cpp +++ /dev/null @@ -1,518 +0,0 @@ -#include "i2c/i2cdevices/adafruit_ssd1306/adafruit_ssd1306.h" -//#include -#include -#include - -using namespace std; - -/********************************************************************* -This is a library for our Monochrome OLEDs based on SSD1306 drivers - -Pick one up today in the adafruit shop! -------> http://www.adafruit.com/category/63_98 - -These displays use SPI to communicate, 4 or 5 pins are required to -interface - -Adafruit invests time and resources providing this open source code, -please support Adafruit and open-source hardware by purchasing -products from Adafruit! - -Written by Limor Fried/Ladyada for Adafruit Industries. -BSD license, check license.txt for more information -All text above, and the splash screen below must be included in any redistribution - -02/18/2013 Charles-Henri Hallard (http://hallard.me) -Modified for compiling and use on Raspberry ArduiPi Board -LCD size and connection are now passed as arguments on -the command line (no more #define on compilation needed) -ArduiPi project documentation http://hallard.me/arduipi -07/01/2013 Charles-Henri Hallard -Reduced code size removed the Adafruit Logo (sorry guys) -Buffer for OLED is now dynamic to LCD size -Added support of Seeed OLED 64x64 Display - -*********************************************************************/ - -//#include "./ArduiPi_SSD1306.h" -//#include "./Adafruit_GFX.h" -//#include "./Adafruit_SSD1306.h" - -/*========================================================================= -SSDxxxx Common Displays ------------------------------------------------------------------------ -Common values to all displays -=========================================================================*/ - -//#define SSD_Command_Mode 0x80 /* DC bit is 0 */ Seeed set C0 to 1 why ? -#define SSD_Command_Mode 0x00 /* C0 and DC bit are 0 */ -#define SSD_Data_Mode 0x40 /* C0 bit is 0 and DC bit is 1 */ - -#define SSD_Inverse_Display 0xA7 - -#define SSD_Display_Off 0xAE -#define SSD_Display_On 0xAF - -#define SSD_Set_ContrastLevel 0x81 - -#define SSD_External_Vcc 0x01 -#define SSD_Internal_Vcc 0x02 - - -#define SSD_Activate_Scroll 0x2F -#define SSD_Deactivate_Scroll 0x2E - -#define Scroll_Left 0x00 -#define Scroll_Right 0x01 - -#define Scroll_2Frames 0x07 -#define Scroll_3Frames 0x04 -#define Scroll_4Frames 0x05 -#define Scroll_5Frames 0x00 -#define Scroll_25Frames 0x06 -#define Scroll_64Frames 0x01 -#define Scroll_128Frames 0x02 -#define Scroll_256Frames 0x03 - -#define VERTICAL_MODE 01 -#define PAGE_MODE 01 -#define HORIZONTAL_MODE 02 - - -/*========================================================================= -SSD1306 Displays ------------------------------------------------------------------------ -The driver is used in multiple displays (128x64, 128x32, etc.). -=========================================================================*/ -#define SSD1306_DISPLAYALLON_RESUME 0xA4 -#define SSD1306_DISPLAYALLON 0xA5 - -#define SSD1306_Normal_Display 0xA6 - -#define SSD1306_SETDISPLAYOFFSET 0xD3 -#define SSD1306_SETCOMPINS 0xDA -#define SSD1306_SETVCOMDETECT 0xDB -#define SSD1306_SETDISPLAYCLOCKDIV 0xD5 -#define SSD1306_SETPRECHARGE 0xD9 -#define SSD1306_SETMULTIPLEX 0xA8 -#define SSD1306_SETLOWCOLUMN 0x00 -#define SSD1306_SETHIGHCOLUMN 0x10 -#define SSD1306_SETSTARTLINE 0x40 -#define SSD1306_MEMORYMODE 0x20 -#define SSD1306_COMSCANINC 0xC0 -#define SSD1306_COMSCANDEC 0xC8 -#define SSD1306_SEGREMAP 0xA0 -#define SSD1306_CHARGEPUMP 0x8D - -// Scrolling #defines -#define SSD1306_SET_VERTICAL_SCROLL_AREA 0xA3 -#define SSD1306_RIGHT_HORIZONTAL_SCROLL 0x26 -#define SSD1306_LEFT_HORIZONTAL_SCROLL 0x27 -#define SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL 0x29 -#define SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL 0x2A - -/*========================================================================= -SSD1308 Displays ------------------------------------------------------------------------ -The driver is used in multiple displays (128x64, 128x32, etc.). -=========================================================================*/ -#define SSD1308_Normal_Display 0xA6 - -/*========================================================================= -SSD1327 Displays ------------------------------------------------------------------------ -The driver is used in Seeed 96x96 display -=========================================================================*/ -#define SSD1327_Normal_Display 0xA4 - - -//#define BLACK 0 -//#define WHITE 1 - - -// Low level I2C Write function -inline void Adafruit_SSD1306::fastI2Cwrite(uint8_t d) { - //bcm2835_i2c_transfer(d); - i2cDevice::write(&d, 1); -} -inline void Adafruit_SSD1306::fastI2Cwrite(char* tbuf, uint32_t len) { - //bcm2835_i2c_write(tbuf, len); - i2cDevice::write((uint8_t*)tbuf, len); -} - -#define _BV(bit) (1 << (bit)) -// the most basic function, set a single pixel -void Adafruit_SSD1306::drawPixel(int16_t x, int16_t y, uint16_t color) -{ - uint8_t * p = poledbuff; - - if ((x < 0) || (x >= width()) || (y < 0) || (y >= height())) - return; - - // check rotation, move pixel around if necessary - switch (getRotation()) - { - case 1: - swap(x, y); - x = WIDTH - x - 1; - break; - - case 2: - x = WIDTH - x - 1; - y = HEIGHT - y - 1; - break; - - case 3: - swap(x, y); - y = HEIGHT - y - 1; - break; - } - - // Get where to do the change in the buffer - p = poledbuff + (x + (y / 8)*ssd1306_lcdwidth); - - // x is which column - if (color == WHITE) - *p |= _BV((y % 8)); - else - *p &= ~_BV((y % 8)); -} - -/* -// Display instantiation -Adafruit_SSD1306::Adafruit_SSD1306() -: i2cDevice(0x3c) -{ -// Init all var, and clean -// Command I/O -rst = 0 ; -fTitle = "SSD1306 OLED"; - -// Lcd size -ssd1306_lcdwidth = 0; -ssd1306_lcdheight = 0; - -// Empty pointer to OLED buffer -poledbuff = NULL; -} -*/ - -// initializer for OLED Type -void Adafruit_SSD1306::select_oled(uint8_t OLED_TYPE) -{ - // Default type - ssd1306_lcdwidth = 128; - ssd1306_lcdheight = 64; - - // default OLED are using internal boost VCC converter - vcc_type = SSD_Internal_Vcc; - - // Oled supported display - // Setup size and I2C address - switch (OLED_TYPE) - { - case OLED_ADAFRUIT_I2C_128x32: - ssd1306_lcdheight = 32; - break; - - case OLED_ADAFRUIT_I2C_128x64: - break; - - case OLED_SEEED_I2C_128x64: - vcc_type = SSD_External_Vcc; - break; - - case OLED_SEEED_I2C_96x96: - ssd1306_lcdwidth = 96; - ssd1306_lcdheight = 96; - break; - - // houston, we have a problem - default: - return; - break; - } -} - -// initializer for I2C - we only indicate the reset pin and OLED type ! -bool Adafruit_SSD1306::init(uint8_t OLED_TYPE, int8_t RST) -{ - rst = RST; - - // Select OLED parameters - select_oled(OLED_TYPE); - - // Setup reset pin direction as output - //bcm2835_gpio_fsel(rst, BCM2835_GPIO_FSEL_OUTP); - - // De-Allocate memory for OLED buffer if any - if (poledbuff) - free(poledbuff); - - // Allocate memory for OLED buffer - poledbuff = (uint8_t *)malloc((ssd1306_lcdwidth * ssd1306_lcdheight / 8)); - if (!poledbuff) return false; - - return (true); -} - -void Adafruit_SSD1306::close(void) -{ - // De-Allocate memory for OLED buffer if any - if (poledbuff) - free(poledbuff); - - poledbuff = NULL; -} - - -void Adafruit_SSD1306::begin(void) -{ - uint8_t multiplex; - uint8_t chargepump; - uint8_t compins; - uint8_t contrast; - uint8_t precharge; - - constructor(ssd1306_lcdwidth, ssd1306_lcdheight); - - // Reset handling, todo - - /* - // Setup reset pin direction (used by both SPI and I2C) - bcm2835_gpio_fsel(rst, BCM2835_GPIO_FSEL_OUTP); - bcm2835_gpio_write(rst, HIGH); - - // VDD (3.3V) goes high at start, lets just chill for a ms - usleep(1000); - - // bring reset low - bcm2835_gpio_write(rst, LOW); - - // wait 10ms - usleep(10000); - - // bring out of reset - bcm2835_gpio_write(rst, HIGH); - */ - - // depends on OLED type configuration - if (ssd1306_lcdheight == 32) - { - multiplex = 0x1F; - compins = 0x02; - contrast = 0x8F; - } - else - { - multiplex = 0x3F; - compins = 0x12; - contrast = (vcc_type == SSD_External_Vcc ? 0x9F : 0xCF); - } - - if (vcc_type == SSD_External_Vcc) - { - chargepump = 0x10; - precharge = 0x22; - } - else - { - chargepump = 0x14; - precharge = 0xF1; - } - - ssd1306_command(SSD_Display_Off); // 0xAE - ssd1306_command(SSD1306_SETDISPLAYCLOCKDIV, 0x80); // 0xD5 + the suggested ratio 0x80 - ssd1306_command(SSD1306_SETMULTIPLEX, multiplex); - ssd1306_command(SSD1306_SETDISPLAYOFFSET, 0x00); // 0xD3 + no offset - ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 - ssd1306_command(SSD1306_CHARGEPUMP, chargepump); - ssd1306_command(SSD1306_MEMORYMODE, 0x00); // 0x20 0x0 act like ks0108 - ssd1306_command(SSD1306_SEGREMAP | 0x1); - ssd1306_command(SSD1306_COMSCANDEC); - ssd1306_command(SSD1306_SETCOMPINS, compins); // 0xDA - ssd1306_command(SSD_Set_ContrastLevel, contrast); - ssd1306_command(SSD1306_SETPRECHARGE, precharge); // 0xd9 - ssd1306_command(SSD1306_SETVCOMDETECT, 0x40); // 0xDB - ssd1306_command(SSD1306_DISPLAYALLON_RESUME); // 0xA4 - ssd1306_command(SSD1306_Normal_Display); // 0xA6 - - // Reset to default value in case of - // no reset pin available on OLED - ssd1306_command(0x21, 0, 127); - ssd1306_command(0x22, 0, 7); - stopscroll(); - - // Empty uninitialized buffer - clearDisplay(); - ssd1306_command(SSD_Display_On); //--turn on oled panel -} - - -void Adafruit_SSD1306::invertDisplay(bool inv) -{ - if (inv) - ssd1306_command(SSD_Inverse_Display); - else - ssd1306_command(SSD1306_Normal_Display); -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c) -{ - char buff[2]; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode; - buff[1] = c; - - // Write Data on I2C - fastI2Cwrite(buff, sizeof(buff)); -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1) -{ - char buff[3]; - buff[1] = c0; - buff[2] = c1; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode; - - // Write Data on I2C - fastI2Cwrite(buff, 3); -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2) -{ - char buff[4]; - - buff[1] = c0; - buff[2] = c1; - buff[3] = c2; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode; - - // Write Data on I2C - fastI2Cwrite(buff, sizeof(buff)); -} - - -// startscrollright -// Activate a right handed scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrollright(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_RIGHT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(0XFF); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrollleft -// Activate a right handed scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrollleft(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_LEFT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(0XFF); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrolldiagright -// Activate a diagonal scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrolldiagright(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); - ssd1306_command(0X00); - ssd1306_command(ssd1306_lcdheight); - ssd1306_command(SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrolldiagleft -// Activate a diagonal scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrolldiagleft(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); - ssd1306_command(0X00); - ssd1306_command(ssd1306_lcdheight); - ssd1306_command(SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(SSD_Activate_Scroll); -} - -void Adafruit_SSD1306::stopscroll(void) -{ - ssd1306_command(SSD_Deactivate_Scroll); -} - -void Adafruit_SSD1306::ssd1306_data(uint8_t c) -{ - char buff[2]; - - // Setup D/C to switch to data mode - buff[0] = SSD_Data_Mode; - buff[1] = c; - - // Write on i2c - fastI2Cwrite(buff, sizeof(buff)); -} - -void Adafruit_SSD1306::display(void) -{ - ssd1306_command(SSD1306_SETLOWCOLUMN | 0x0); // low col = 0 - ssd1306_command(SSD1306_SETHIGHCOLUMN | 0x0); // hi col = 0 - ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 - - uint16_t i = 0; - - // pointer to OLED data buffer - uint8_t * p = poledbuff; - - char buff[17]; - uint8_t x; - - // Setup D/C to switch to data mode - buff[0] = SSD_Data_Mode; - - // loop trough all OLED buffer and - // send a bunch of 16 data byte in one xmission - for (i = 0; i<(ssd1306_lcdwidth*ssd1306_lcdheight / 8); i += 16) - { - for (x = 1; x <= 16; x++) - buff[x] = *p++; - - fastI2Cwrite(buff, 17); - } -} - -// clear everything (in the buffer) -void Adafruit_SSD1306::clearDisplay(void) -{ - memset(poledbuff, 0, (ssd1306_lcdwidth*ssd1306_lcdheight / 8)); -} diff --git a/source/daemon/src/i2c/i2cdevices/ads1115/ads1115.cpp b/source/daemon/src/i2c/i2cdevices/ads1115/ads1115.cpp deleted file mode 100644 index 38531437..00000000 --- a/source/daemon/src/i2c/i2cdevices/ads1115/ads1115.cpp +++ /dev/null @@ -1,185 +0,0 @@ -#include "i2c/i2cdevices/ads1115/ads1115.h" -/* -* ADS1115 4ch 16 bit ADC -*/ -const double ADS1115::PGAGAINS[6] = { 6.144, 4.096, 2.048, 1.024, 0.512, 0.256 }; - -int16_t ADS1115::readADC(unsigned int channel) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - // uint8_t fDataRate = 0x07; // 860 SPS - // uint8_t fDataRate = 0x01; // 16 SPS - uint8_t fDataRate = fRate & 0x07; - - startTimer(); - - // These three bytes are written to the ADS1115 to set the config register and start a conversion - writeBuf[0] = 0x01; // This sets the pointer register so that the following two bytes write to the config register - writeBuf[1] = 0x80; // OS bit - if (!fDiffMode) writeBuf[1] |= 0x40; // single ended mode channels - writeBuf[1] |= (channel & 0x03) << 4; // channel select - writeBuf[1] |= 0x01; // single shot mode - writeBuf[1] |= ((uint8_t)fPga[channel]) << 1; // PGA gain select - - // This sets the 8 LSBs of the config register (bits 7-0) -// writeBuf[2] = 0x03; // disable ALERT/RDY pin - writeBuf[2] = 0x00; // enable ALERT/RDY pin - writeBuf[2] |= ((uint8_t)fDataRate) << 5; - - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this begins a single conversion - write(writeBuf, 3); - - // Wait for the conversion to complete, this requires bit 15 to change from 0->1 - int nloops = 0; - while ((readBuf[0] & 0x80) == 0 && nloops*fReadWaitDelay / 1000 < 1000) // readBuf[0] contains 8 MSBs of config register, AND with 10000000 to select bit 15 - { - usleep(fReadWaitDelay); - read(readBuf, 2); // Read the config register into readBuf - nloops++; - } - if (nloops*fReadWaitDelay / 1000 >= 1000) { - if (fDebugLevel > 1) - printf("timeout!\n"); - return INT16_MIN; - } - if (fDebugLevel > 2) - printf(" nr of busy adc loops: %d \n", nloops); - if (nloops > 1) { - fReadWaitDelay += (nloops - 1)*fReadWaitDelay / 10; - if (fDebugLevel > 1) { - printf(" read wait delay: %6.2f ms\n", fReadWaitDelay / 1000.); - } - } - // else if (nloops==2) { - // fReadWaitDelay*=2.1; - // } - //else fReadWaitDelay--; - - // Set pointer register to 0 to read from the conversion register - readReg(0x00, readBuf, 2); // Read the contents of the conversion register into readBuf - - val = readBuf[0] << 8 | readBuf[1]; // Combine the two bytes of readBuf into a single 16 bit result - fLastADCValue = val; - - stopTimer(); - fLastConvTime = fLastTimeInterval; - - return val; -} - -bool ADS1115::setLowThreshold(int16_t thr) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - startTimer(); - - // These three bytes are written to the ADS1115 to set the Lo_thresh register - writeBuf[0] = 0x02; // This sets the pointer register to Lo_thresh register - writeBuf[1] = (thr & 0xff00) >> 8; - writeBuf[2] |= (thr & 0x00ff); - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this sets the Lo_thresh register - int n = write(writeBuf, 3); - if (n != 3) return false; - n = read(readBuf, 2); // Read the same register into readBuf for verification - if (n != 2) return false; - - if ((readBuf[0] != writeBuf[1]) || (readBuf[1] != writeBuf[2])) return false; - stopTimer(); - return true; -} - -bool ADS1115::setHighThreshold(int16_t thr) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - startTimer(); - - // These three bytes are written to the ADS1115 to set the Hi_thresh register - writeBuf[0] = 0x03; // This sets the pointer register to Hi_thresh register - writeBuf[1] = (thr & 0xff00) >> 8; - writeBuf[2] |= (thr & 0x00ff); - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this sets the Hi_thresh register - int n = write(writeBuf, 3); - if (n != 3) return false; - - n = read(readBuf, 2); // Read the same register into readBuf for verification - if (n != 2) return false; - - if ((readBuf[0] != writeBuf[1]) || (readBuf[1] != writeBuf[2])) return false; - stopTimer(); - return true; -} - -bool ADS1115::setDataReadyPinMode() -{ - // c.f. datasheet, par. 9.3.8, p. 19 - // set MSB of Lo_thresh reg to 0 - // set MSB of Hi_thresh reg to 1 - // set COMP_QUE[1:0] to any value other than '11' (default value) - bool ok = setLowThreshold(0b00000000); - ok = ok && setHighThreshold(0b11111111); - return ok; -} - -bool ADS1115::devicePresent() -{ - uint8_t buf[2]; - return (read(buf, 2) == 2); // Read the currently selected register into readBuf -} - -double ADS1115::readVoltage(unsigned int channel) -{ - double voltage = 0.; - readVoltage(channel, voltage); - return voltage; -} - -void ADS1115::readVoltage(unsigned int channel, double& voltage) -{ - int16_t adc = 0; - readVoltage(channel, adc, voltage); -} - -void ADS1115::readVoltage(unsigned int channel, int16_t& adc, double& voltage) -{ - adc = readADC(channel); - voltage = PGAGAINS[fPga[channel]] * adc / 32767.0; - - if (fAGC) { - int eadc = abs(adc); - if (eadc > 0.8 * 32767 && (unsigned int)fPga[channel] > 0) { - fPga[channel] = CFG_PGA((unsigned int)fPga[channel] - 1); - if (fDebugLevel > 1) - printf("ADC input high...setting PGA to level %d\n", fPga[channel]); - } - else if (eadc < 0.2 * 32767 && (unsigned int)fPga[channel] < 5) { - fPga[channel] = CFG_PGA((unsigned int)fPga[channel] + 1); - if (fDebugLevel > 1) - printf("ADC input low...setting PGA to level %d\n", fPga[channel]); - - } - } - fLastVoltage = voltage; - return; -} - diff --git a/source/daemon/src/i2c/i2cdevices/bme280/bme280.cpp b/source/daemon/src/i2c/i2cdevices/bme280/bme280.cpp deleted file mode 100644 index 3f5826fd..00000000 --- a/source/daemon/src/i2c/i2cdevices/bme280/bme280.cpp +++ /dev/null @@ -1,520 +0,0 @@ -#include "i2c/i2cdevices/bme280/bme280.h" -#include -#include -#include -/* -*BME280 HumidityTemperaturePressuresensor -* -*/ -bool BME280::init() -{ - fTitle = "BME280"; - - uint8_t val = 0; - fCalibrationValid = false; - - // chip id reg - int n = readReg(0xd0, &val, 1); // Read the id register into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("chip id: 0x%x \n", val); - } - - if (val == 0x60) readCalibParameters(); - return (val == 0x60); -} - -bool BME280::status() { - uint8_t status = 0; - int n = readReg(0xf3, &status, 1); - if (fDebugLevel > 1){ - printf("%d bytes read\n", n); - } - status &= 0b1001; - return (status==0 && n==1); -} - -uint8_t BME280::readConfig() { - uint8_t config[1]; - config[0] = 0; - int n = readReg(0xf5, config, 1); - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - return (unsigned int)config[0]; -} - -uint8_t BME280::read_CtrlMeasReg() { - uint8_t ctrl_meas[1]; - ctrl_meas[0] = 0; - int n = readReg(0xf4, ctrl_meas, 1); - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - return (uint8_t)ctrl_meas[0]; -} - -bool BME280::writeConfig(uint8_t config) { - uint8_t buf[1]; - // check for bit 1 because datasheet says: "do not change" - int n = readReg(0xf5, buf, 1); - buf[0] = buf[0] & 0b10; - config = config & 0b11111101; - buf[0] = buf[0] | config; - n += writeReg(0xf5, buf, 1); - if (fDebugLevel > 1) - printf("%d bytes written\n", n); - return (n == 2); -} - -bool BME280::write_CtrlMeasReg(uint8_t config) { - uint8_t buf[1]; - buf[0] = config; - int n = writeReg(0xf4, buf, 1); - if (fDebugLevel > 1) - printf("%d bytes written\n", n); - return (n == 1); -} - -bool BME280::setMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b11) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0xfc; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setTSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b00011111; - mode = mode << 5; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setPSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b11100011; - mode = mode << 2; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setHSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf2, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b11111000; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf2, buf, 1); - n += readReg(0xf4, buf, 1); - writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setDefaultSettings() { - uint8_t buf[1]; - readReg(0xf2, buf, 1); - buf[0] &= 0b11111000; - buf[0] |= 0b010; - writeReg(0xf2, buf, 1); // enabling humidity measurement (oversampling x2) - write_CtrlMeasReg(0b01001000); // enabling temperature and pressure measurement (oversampling x2), set sleep mode - return true; -} - -bool BME280::measure() { - // calculate t_max [ms] from settings: - uint8_t readBuf[1]; - double t_max = 1.25; - readReg(0xf2, readBuf, 1); - unsigned int val = readBuf[0] & 0b111; - if (fDebugLevel > 1) - printf("osrs_h: %u\n", val); - if (val > 5) - val = 5; - unsigned int add = 1; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add + 0.575; - } - - readBuf[0] = 0; - add = 1; - readReg(0xf4, readBuf, 1); - val = readBuf[0] & 0b00011100; - val = val >> 2; - if (fDebugLevel > 1) - printf("osrs_p: %u\n", val); - if (val > 5) - val = 5; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add + 0.575; - } - - add = 1; - val = readBuf[0] & 0b11100000; - val = val >> 5; - if (fDebugLevel > 1) - printf("osrs_t: %u\n", val); - if (val > 5) - val = 5; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add; - } - // t_max corresponds to the maximum time that a measurement can take with given - // settings read out from registers f2 and f4 - - // wait while status not ready: - for (int i = 0; i < 10; i++) { - usleep(5000); - } - setMode(0x2); // set mode to "forced measurement" (single-shot) - // it will now perform a measurement as configured in 0xf4, 0xf2 and 0xf5 registers - - // wait at least 112.8 ms for a full accuracy measurement of all 3 values - // or ask for status to be 0 - usleep((int)(t_max * 1000 + 0.5) + 200); - if (fDebugLevel > 1) - printf("measurement took about %.1f ms\n", t_max + 0.2); - for (int i = 0; i < 10; i++) { - if (status()){ - break; - } - usleep(5000); - if (i == 9){ - return false; - } - } - return true; -} - -int32_t BME280::readUT() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - uint32_t val; // Stores the 20 bit value of our ADC conversion - - if (!measure()){ - std::cerr << "error: measurement invalid"; - return INT32_MIN; - } - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - int n = readReg(0xfa, readBuf, 3); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read: 0x%02x 0x%02x 0x%02x\n", n, readBuf[0], readBuf[1], readBuf[2]); - - val = ((uint32_t)readBuf[0]) << 12; // <-------///// should the lower 4 bits or the higher 4 bits of the 24 bits of registers be left 0 ??? - val |= ((uint32_t)readBuf[1]) << 4; // (look datasheet page 25) - val |= ((uint32_t)readBuf[2]) >> 4; - - return (int32_t)val; -} - -int32_t BME280::readUP() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - uint32_t val; // Stores the 20 bit value of our ADC conversion - - if (!measure()){ - std::cerr << "error: measurement invalid"; - return INT32_MIN; - } - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - int n = readReg(0xf7, readBuf, 3); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = ((uint32_t)readBuf[0]) << 12; - val |= ((uint32_t)readBuf[1]) << 4; - val |= ((uint32_t)readBuf[2]) >> 4; - - return (int32_t)val; -} - -int32_t BME280::readUH() -{ - uint8_t readBuf[2]; - uint16_t val; - - if (!measure()){ - std::cerr << "error: measurement invalid"; - return INT32_MIN; - } - - readBuf[0] = 0; - readBuf[1] = 0; - - // adc reg - int n = readReg(0xfd, readBuf, 2); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = ((uint32_t)readBuf[0]) << 8; - val |= ((uint32_t)readBuf[1]); // (look datasheet page 25) - - return (int32_t)val; -} - -TPH BME280::readTPCU() -{ - uint8_t readBuf[8]; - for (int i = 0; i < 8; i++) { - readBuf[i] = 0; - } - - TPH val; - if (!measure()){ - std::cerr << "error: measurement invalid"; - val.adc_P = INT32_MIN; - val.adc_T = INT32_MIN; - val.adc_H = INT32_MIN; - return val; - } - - int n = readReg(0xf7, readBuf, 8); // read T, P and H registers; - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - uint32_t adc_P = ((uint32_t)readBuf[0]) << 12; - adc_P |= ((uint32_t)readBuf[1]) << 4; - adc_P |= ((uint32_t)readBuf[2]) >> 4; - uint32_t adc_T = ((uint32_t)readBuf[3]) << 12; - adc_T |= ((uint32_t)readBuf[4]) << 4; - adc_T |= ((uint32_t)readBuf[5]) >> 4; - uint32_t adc_H = ((uint32_t)readBuf[6]) << 8; - adc_H |= ((uint32_t)readBuf[7]); // (look datasheet page 25) - - val.adc_P = (int32_t)adc_P; - val.adc_T = (int32_t)adc_T; - val.adc_H = (int32_t)adc_H; - return val; -} - -bool BME280::softReset() { - uint8_t resetWord[1]; - resetWord[0] = 0xb6; - int val = writeReg(0xe0, resetWord, 1); - return(val == 1); -} - -uint16_t BME280::getCalibParameter(unsigned int param) const -{ - if (param < 18) return fCalibParameters[param]; - return 0xffff; -} - -void BME280::readCalibParameters() -{ - uint8_t readBuf[32]; - uint8_t readBufPart1[26]; - uint8_t readBufPart2[7]; - // register address first byte eeprom - int n = readReg(0x88, readBufPart1, 26); // Read the 26 eeprom word values into readBuf - n = n + readReg(0xe1, readBufPart2, 7); // from two different locations - - for (int i = 0; i < 24; i++){ - readBuf[i] = readBufPart1[i]; - } - readBuf[24] = readBufPart1[25]; - for (int i = 0; i < 7; i++) { - readBuf[i + 25] = readBufPart2[i]; - } - for(int i = 0; i < 32; i++){ - if (fDebugLevel > 1){ - printf("readBuf %d\n", n); - } - } - if (fDebugLevel > 1){ - printf("%d bytes read\n", n); - } - if (fDebugLevel > 1){ - printf("BME280 eeprom calib data:\n"); - } - - bool ok = true; - for (int i = 0; i < 12; i++) { - fCalibParameters[i] = ((uint16_t)readBuf[2 * i]) | (((uint16_t)readBuf[2 * i + 1]) << 8); // 2x 8-Bit ergibt 16-Bit Wort - if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) ok = false; - if (fDebugLevel > 1) - printf("calib%d: %d \n", i, fCalibParameters[i]); - } - fCalibParameters[12] = (uint16_t)readBuf[24]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 12, fCalibParameters[12]); - fCalibParameters[13] = ((uint16_t)readBuf[25]) | (((uint16_t)readBuf[26]) << 8); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 13, fCalibParameters[13]); - fCalibParameters[14] = (uint16_t)readBuf[27]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 14, fCalibParameters[14]); - fCalibParameters[15] = (((uint16_t)readBuf[28]) << 4) | (((uint16_t)readBuf[29]) & 0b1111); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 15, fCalibParameters[15]); - fCalibParameters[16] = (((uint16_t)readBuf[29] & 0xf0) >> 4) | (((uint16_t)readBuf[30]) << 4); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 16, fCalibParameters[16]); - fCalibParameters[17] = (uint16_t)readBuf[31]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 17, fCalibParameters[17]); - - if (fDebugLevel > 1) { - if (ok){ - printf("calib data is valid.\n"); - }else{ - printf("calib data NOT valid!\n"); - } - } - fCalibrationValid = ok; - setDefaultSettings(); -} - -TPH BME280::getTPHValues() { - TPH vals = readTPCU(); - vals.T = getTemperature(vals.adc_T); - vals.P = getPressure(vals.adc_P); - vals.H = getHumidity(vals.adc_H); - return vals; -} - -double BME280::getTemperature(int32_t adc_T) { - if (!fCalibrationValid) return -999.; - int32_t dig_T1 = (int32_t)fCalibParameters[0]; - int32_t dig_T2 = (int32_t)((int16_t)fCalibParameters[1]); - int32_t dig_T3 = (int32_t)((int16_t)fCalibParameters[2]); - int32_t X1 = (((adc_T >> 3) - (dig_T1 << 1))*dig_T2) >> 11; - int32_t X2 = (((((adc_T >> 4) - dig_T1)*((adc_T >> 4) - dig_T1)) >> 12)*dig_T3) >> 14; - fT_fine = X1 + X2; - int32_t t = (fT_fine * 5 + 128) >> 8; - double T = t / 100.0; - if (fDebugLevel > 1) { - printf("adc_T=%d\n", adc_T); - printf("X1=%d\n", X1); - printf("X2=%d\n", X2); - printf("t_fine=%d\n", fT_fine); - printf("temp=%d\n", t); - } - return T; -} - -double BME280::getHumidity(int32_t adc_H) { // please only do this if "getTemperature()" has been executed before - return getHumidity(adc_H, fT_fine); -} -double BME280::getHumidity(int32_t adc_H, int32_t t_fine) { - if (!fCalibrationValid) return -999.; - if (t_fine == 0) return -999.; - int32_t dig_H1 = (int32_t)fCalibParameters[12]; - int32_t dig_H2 = (int32_t)((int16_t)fCalibParameters[13]); - int32_t dig_H3 = (int32_t)fCalibParameters[14]; - int32_t dig_H4 = (int32_t)((int16_t)fCalibParameters[15]); - int32_t dig_H5 = (int32_t)((int16_t)fCalibParameters[16]); - int32_t dig_H6 = (int32_t)((int8_t)((uint8_t)fCalibParameters[17])); - int32_t X1 = 0; - X1 = (t_fine - ((int32_t)76800)); - X1 = (((((adc_H << 14) - (dig_H4 << 20) - (dig_H5* X1)) + - ((int32_t)16384)) >> 15) * (((((((X1 * dig_H6) >> 10) * (((X1 * - dig_H3) >> 11) + ((int32_t)32768))) >> 10) + ((int32_t)2097152)) * - dig_H2 + 8192) >> 14)); - X1 = (X1 - (((((X1 >> 15) * (X1 >> 15)) >> 7) * dig_H1) >> 4)); - X1 = (X1 < 0 ? 0 : X1); - X1 = (X1 > 419430400 ? 419430400 : X1); - uint32_t h = (uint32_t)(X1 >> 12); - double H = h / 1024.0; - if (fDebugLevel > 1) { - printf("adc_H=%d\n", adc_H); - printf("X1=%d\n", X1); - printf("t_fine=%d\n", t_fine); - printf("Humidity=%u\n", h); - } - return H; -} - -double BME280::getPressure(signed int adc_P) { - return getPressure(adc_P, fT_fine); -} -double BME280::getPressure(signed int adc_P, signed int t_fine) { - if (!fCalibrationValid) return -999.0; - if (fT_fine == 0) return -999.0; - uint16_t dig_P1 = fCalibParameters[3]; - int16_t dig_P2 = (int16_t)fCalibParameters[4]; - int16_t dig_P3 = (int16_t)fCalibParameters[5]; - int16_t dig_P4 = (int16_t)fCalibParameters[6]; - int16_t dig_P5 = (int16_t)fCalibParameters[7]; - int16_t dig_P6 = (int16_t)fCalibParameters[8]; - int16_t dig_P7 = (int16_t)fCalibParameters[9]; - int16_t dig_P8 = (int16_t)fCalibParameters[10]; - int16_t dig_P9 = (int16_t)fCalibParameters[11]; - - int64_t X1, X2, p; - X1 = ((int64_t)t_fine) - 128000; - X2 = X1 * X1 * (int64_t)dig_P6; - X2 = X2 + ((X1*(int64_t)dig_P5) << 17); - X2 = X2 + (((int64_t)dig_P4) << 35); - X1 = ((X1 * X1 * (int64_t)dig_P3) >> 8) + ((X1 * (int64_t)dig_P2) << 12); - X1 = (((((int64_t)1) << 47) + X1))*((int64_t)dig_P1) >> 33; - if (X1 == 0) - { - return 0; // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p << 31) - X2) * 3125) / X1; - X1 = (((int64_t)dig_P9) * (p >> 13) * (p >> 13)) >> 25; - X2 = (((int64_t)dig_P8) * p) >> 19; - p = ((p + X1 + X2) >> 8) + (((int64_t)dig_P7) << 4); - - double P = ((uint32_t)p) / 256.; - if (fDebugLevel > 1) { - printf("adc_P=%d\n", adc_P); - printf("X1=%lld\n", X1); - printf("X2=%lld\n", X2); - printf("p=%lld\n", p); - printf("P=%.3f\n", P); - } - return P; -} diff --git a/source/daemon/src/i2c/i2cdevices/bmp180/bmp180.cpp b/source/daemon/src/i2c/i2cdevices/bmp180/bmp180.cpp deleted file mode 100644 index 8d19e901..00000000 --- a/source/daemon/src/i2c/i2cdevices/bmp180/bmp180.cpp +++ /dev/null @@ -1,205 +0,0 @@ -#include "i2c/i2cdevices/bmp180/bmp180.h" -#include -#include - -/* -* BMP180 Pressure Sensor -*/ - -bool BMP180::init() -{ - uint8_t val = 0; - - fCalibrationValid = false; - - // chip id reg - int n = readReg(0xd0, &val, 1); // Read the id register into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("chip id: 0x%x \n", val); - } - if (val == 0x55) readCalibParameters(); - return (val == 0x55); -} - - -unsigned int BMP180::readUT() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - unsigned int val; // Stores the 16 bit value of our ADC conversion - - // start temp measurement: CR -> 0x2e - uint8_t cr_val = 0x2e; - // register address control reg - int n = writeReg(0xf4, &cr_val, 1); - - // wait at least 4.5 ms - usleep(4500); - - readBuf[0] = 0; - readBuf[1] = 0; - - // adc reg - n = readReg(0xf6, readBuf, 2); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = (readBuf[0]) << 8 | readBuf[1]; - - return val; -} - -unsigned int BMP180::readUP(uint8_t oss) -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - unsigned int val; // Stores the 16 bit value of our ADC conversion - static const int delay[4] = { 4500, 7500, 13500, 25500 }; - - // start pressure measurement: CR -> 0x34 | oss<<6 - uint8_t cr_val = 0x34 | (oss & 0x03) << 6; - // register address control reg - int n = writeReg(0xf4, &cr_val, 1); - usleep(delay[oss & 0x03]); - - // writeBuf[0] = 0xf6; // adc reg - // write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - n = readReg(0xf6, readBuf, 3); // Read the conversion result into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = (readBuf[0] << 16 | readBuf[1] << 8 | readBuf[2]) >> (8 - (oss & 0x03)); - - return val; -} - -signed int BMP180::getCalibParameter(unsigned int param) const -{ - if (param < 11) return fCalibParameters[param]; - return 0xffff; -} - -void BMP180::readCalibParameters() -{ - uint8_t readBuf[22]; - // register address first byte eeprom - int n = readReg(0xaa, readBuf, 22); // Read the 11 eeprom word values into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - if (fDebugLevel > 1) - printf("BMP180 eeprom calib data:\n"); - - bool ok = true; - for (int i = 0; i < 11; i++) { - if (i > 2 && i < 6) - fCalibParameters[i] = (uint16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); - else - fCalibParameters[i] = (int16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); - if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) ok = false; - if (fDebugLevel > 1) - // printf( "calib%d: 0x%4x \n",i,fCalibParameters[i]); - printf("calib%d: %d \n", i, fCalibParameters[i]); - } - if (fDebugLevel > 1) { - if (ok) - printf("calib data is valid.\n"); - else printf("calib data NOT valid!\n"); - } - - fCalibrationValid = ok; -} - -double BMP180::getTemperature() { - if (!fCalibrationValid) return -999.; - signed int UT = readUT(); - signed int X1 = ((UT - fCalibParameters[5])*fCalibParameters[4]) >> 15; - signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); - signed int B5 = X1 + X2; - double T = (B5 + 8) / 160.; - if (fDebugLevel > 1) { - printf("UT=%d\n", UT); - printf("X1=%d\n", X1); - printf("X2=%d\n", X2); - printf("B5=%d\n", B5); - printf("Temp=%f\n", T); - } - return T; -} - - -double BMP180::getPressure(uint8_t oss) { - if (!fCalibrationValid) return 0.; - signed int UT = readUT(); - if (fDebugLevel > 1) - printf("UT=%d\n", UT); - signed int UP = readUP(oss); - if (fDebugLevel > 1) - printf("UP=%d\n", UP); - signed int X1 = ((UT - fCalibParameters[5])*fCalibParameters[4]) >> 15; - signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); - signed int B5 = X1 + X2; - signed int B6 = B5 - 4000; - if (fDebugLevel > 1) - printf("B6=%d\n", B6); - X1 = (fCalibParameters[7] * ((B6*B6) >> 12)) >> 11; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (fCalibParameters[1] * B6) >> 11; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - signed int X3 = X1 + X2; - signed int B3 = ((fCalibParameters[0] * 4 + X3) << (oss & 0x03)) + 2; - B3 = B3 / 4; - if (fDebugLevel > 1) - printf("B3=%d\n", B3); - X1 = (fCalibParameters[2] * B6) >> 13; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (fCalibParameters[6] * (B6*B6) / 4096); - X2 = X2 >> 16; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - X3 = (X1 + X2 + 2) / 4; - if (fDebugLevel > 1) - printf("X3=%d\n", X3); - unsigned long B4 = (fCalibParameters[3] * (unsigned long)(X3 + 32768)) >> 15; - if (fDebugLevel > 1) - printf("B4=%ld\n", B4); - unsigned long B7 = ((unsigned long)UP - B3)*(50000 >> (oss & 0x03)); - if (fDebugLevel > 1) - printf("B7=%ld\n", B7); - int p = 0; - if (B7 < 0x80000000) p = (B7 * 2) / B4; - else p = (B7 / B4) * 2; - if (fDebugLevel > 1) - printf("p=%d\n", p); - - X1 = p >> 8; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X1 = X1 * X1; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X1 = (X1 * 3038) >> 16; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (-7357 * p) >> 16; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - p = 16 * p + (X1 + X2 + 3791); - double press = p / 16.; - - if (fDebugLevel > 1) { - printf("pressure=%f\n", press); - } - return press; -} diff --git a/source/daemon/src/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.cpp b/source/daemon/src/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.cpp deleted file mode 100644 index 8eb839a5..00000000 --- a/source/daemon/src/i2c/i2cdevices/eeprom24aa02/eeprom24aa02.cpp +++ /dev/null @@ -1,78 +0,0 @@ -#include "i2c/i2cdevices/eeprom24aa02/eeprom24aa02.h" -#include -#include - -/* -* 24AA02 EEPROM -*/ - -uint8_t EEPROM24AA02::readByte(uint8_t addr) -{ - uint8_t val = 0; - startTimer(); - /*int n=*/readReg(addr, &val, 1); // Read the data at address location - // printf( "%d bytes read\n",n); - stopTimer(); - return val; -} - -bool EEPROM24AA02::readByte(uint8_t addr, uint8_t* value) -{ - startTimer(); - int n = readReg(addr, value, 1); // Read the data at address location - // printf( "%d bytes read\n",n); - stopTimer(); - return (n == 1); -} - -/* -bool EEPROM24AA02::devicePresent() -{ -uint8_t dummy; -return readByte(0,&dummy); -} -*/ - -void EEPROM24AA02::writeByte(uint8_t addr, uint8_t data) -{ - uint8_t writeBuf[2]; // Buffer to store the 2 bytes that we write to the I2C device - - writeBuf[0] = addr; // address of data byte - writeBuf[1] = data; // data byte - - startTimer(); - - // Write address first - write(writeBuf, 2); - - usleep(5000); - stopTimer(); -} - -/** Write multiple bytes to starting from given address into EEPROM memory. -* @param addr First register address to write to -* @param length Number of bytes to write -* @param data Buffer to copy new data from -* @return Status of operation (true = success) -* @note this is an overloaded function to the one from the i2cdevice base class in order to -* prevent sequential write operations crossing page boundaries of the EEPROM. This function conforms to -* the page-wise sequential write (c.f. http://ww1.microchip.com/downloads/en/devicedoc/21709c.pdf p.7). -*/ -bool EEPROM24AA02::writeBytes(uint8_t addr, uint16_t length, uint8_t* data) { - - static const uint8_t PAGESIZE = 8; - bool success = true; - startTimer(); - for (uint16_t i = 0; i= length) pageRemainder = length - currAddr; - int n = writeReg(currAddr, &data[i], pageRemainder); - usleep(5000); - i += pageRemainder; - success = success && (n == pageRemainder); - } - stopTimer(); - return success; -} diff --git a/source/daemon/src/i2c/i2cdevices/glcdfont.c b/source/daemon/src/i2c/i2cdevices/glcdfont.c deleted file mode 100644 index b4809edf..00000000 --- a/source/daemon/src/i2c/i2cdevices/glcdfont.c +++ /dev/null @@ -1,264 +0,0 @@ - -#ifndef FONT5X7_H -#define FONT5X7_H - -// standard ascii 5x7 font - -static unsigned char font[] = { - 0x00, 0x00, 0x00, 0x00, 0x00, - 0x3E, 0x5B, 0x4F, 0x5B, 0x3E, - 0x3E, 0x6B, 0x4F, 0x6B, 0x3E, - 0x1C, 0x3E, 0x7C, 0x3E, 0x1C, - 0x18, 0x3C, 0x7E, 0x3C, 0x18, - 0x1C, 0x57, 0x7D, 0x57, 0x1C, - 0x1C, 0x5E, 0x7F, 0x5E, 0x1C, - 0x00, 0x18, 0x3C, 0x18, 0x00, - 0xFF, 0xE7, 0xC3, 0xE7, 0xFF, - 0x00, 0x18, 0x24, 0x18, 0x00, - 0xFF, 0xE7, 0xDB, 0xE7, 0xFF, - 0x30, 0x48, 0x3A, 0x06, 0x0E, - 0x26, 0x29, 0x79, 0x29, 0x26, - 0x40, 0x7F, 0x05, 0x05, 0x07, - 0x40, 0x7F, 0x05, 0x25, 0x3F, - 0x5A, 0x3C, 0xE7, 0x3C, 0x5A, - 0x7F, 0x3E, 0x1C, 0x1C, 0x08, - 0x08, 0x1C, 0x1C, 0x3E, 0x7F, - 0x14, 0x22, 0x7F, 0x22, 0x14, - 0x5F, 0x5F, 0x00, 0x5F, 0x5F, - 0x06, 0x09, 0x7F, 0x01, 0x7F, - 0x00, 0x66, 0x89, 0x95, 0x6A, - 0x60, 0x60, 0x60, 0x60, 0x60, - 0x94, 0xA2, 0xFF, 0xA2, 0x94, - 0x08, 0x04, 0x7E, 0x04, 0x08, - 0x10, 0x20, 0x7E, 0x20, 0x10, - 0x08, 0x08, 0x2A, 0x1C, 0x08, - 0x08, 0x1C, 0x2A, 0x08, 0x08, - 0x1E, 0x10, 0x10, 0x10, 0x10, - 0x0C, 0x1E, 0x0C, 0x1E, 0x0C, - 0x30, 0x38, 0x3E, 0x38, 0x30, - 0x06, 0x0E, 0x3E, 0x0E, 0x06, - 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x5F, 0x00, 0x00, - 0x00, 0x07, 0x00, 0x07, 0x00, - 0x14, 0x7F, 0x14, 0x7F, 0x14, - 0x24, 0x2A, 0x7F, 0x2A, 0x12, - 0x23, 0x13, 0x08, 0x64, 0x62, - 0x36, 0x49, 0x56, 0x20, 0x50, - 0x00, 0x08, 0x07, 0x03, 0x00, - 0x00, 0x1C, 0x22, 0x41, 0x00, - 0x00, 0x41, 0x22, 0x1C, 0x00, - 0x2A, 0x1C, 0x7F, 0x1C, 0x2A, - 0x08, 0x08, 0x3E, 0x08, 0x08, - 0x00, 0x80, 0x70, 0x30, 0x00, - 0x08, 0x08, 0x08, 0x08, 0x08, - 0x00, 0x00, 0x60, 0x60, 0x00, - 0x20, 0x10, 0x08, 0x04, 0x02, - 0x3E, 0x51, 0x49, 0x45, 0x3E, - 0x00, 0x42, 0x7F, 0x40, 0x00, - 0x72, 0x49, 0x49, 0x49, 0x46, - 0x21, 0x41, 0x49, 0x4D, 0x33, - 0x18, 0x14, 0x12, 0x7F, 0x10, - 0x27, 0x45, 0x45, 0x45, 0x39, - 0x3C, 0x4A, 0x49, 0x49, 0x31, - 0x41, 0x21, 0x11, 0x09, 0x07, - 0x36, 0x49, 0x49, 0x49, 0x36, - 0x46, 0x49, 0x49, 0x29, 0x1E, - 0x00, 0x00, 0x14, 0x00, 0x00, - 0x00, 0x40, 0x34, 0x00, 0x00, - 0x00, 0x08, 0x14, 0x22, 0x41, - 0x14, 0x14, 0x14, 0x14, 0x14, - 0x00, 0x41, 0x22, 0x14, 0x08, - 0x02, 0x01, 0x59, 0x09, 0x06, - 0x3E, 0x41, 0x5D, 0x59, 0x4E, - 0x7C, 0x12, 0x11, 0x12, 0x7C, - 0x7F, 0x49, 0x49, 0x49, 0x36, - 0x3E, 0x41, 0x41, 0x41, 0x22, - 0x7F, 0x41, 0x41, 0x41, 0x3E, - 0x7F, 0x49, 0x49, 0x49, 0x41, - 0x7F, 0x09, 0x09, 0x09, 0x01, - 0x3E, 0x41, 0x41, 0x51, 0x73, - 0x7F, 0x08, 0x08, 0x08, 0x7F, - 0x00, 0x41, 0x7F, 0x41, 0x00, - 0x20, 0x40, 0x41, 0x3F, 0x01, - 0x7F, 0x08, 0x14, 0x22, 0x41, - 0x7F, 0x40, 0x40, 0x40, 0x40, - 0x7F, 0x02, 0x1C, 0x02, 0x7F, - 0x7F, 0x04, 0x08, 0x10, 0x7F, - 0x3E, 0x41, 0x41, 0x41, 0x3E, - 0x7F, 0x09, 0x09, 0x09, 0x06, - 0x3E, 0x41, 0x51, 0x21, 0x5E, - 0x7F, 0x09, 0x19, 0x29, 0x46, - 0x26, 0x49, 0x49, 0x49, 0x32, - 0x03, 0x01, 0x7F, 0x01, 0x03, - 0x3F, 0x40, 0x40, 0x40, 0x3F, - 0x1F, 0x20, 0x40, 0x20, 0x1F, - 0x3F, 0x40, 0x38, 0x40, 0x3F, - 0x63, 0x14, 0x08, 0x14, 0x63, - 0x03, 0x04, 0x78, 0x04, 0x03, - 0x61, 0x59, 0x49, 0x4D, 0x43, - 0x00, 0x7F, 0x41, 0x41, 0x41, - 0x02, 0x04, 0x08, 0x10, 0x20, - 0x00, 0x41, 0x41, 0x41, 0x7F, - 0x04, 0x02, 0x01, 0x02, 0x04, - 0x40, 0x40, 0x40, 0x40, 0x40, - 0x00, 0x03, 0x07, 0x08, 0x00, - 0x20, 0x54, 0x54, 0x78, 0x40, - 0x7F, 0x28, 0x44, 0x44, 0x38, - 0x38, 0x44, 0x44, 0x44, 0x28, - 0x38, 0x44, 0x44, 0x28, 0x7F, - 0x38, 0x54, 0x54, 0x54, 0x18, - 0x00, 0x08, 0x7E, 0x09, 0x02, - 0x18, 0xA4, 0xA4, 0x9C, 0x78, - 0x7F, 0x08, 0x04, 0x04, 0x78, - 0x00, 0x44, 0x7D, 0x40, 0x00, - 0x20, 0x40, 0x40, 0x3D, 0x00, - 0x7F, 0x10, 0x28, 0x44, 0x00, - 0x00, 0x41, 0x7F, 0x40, 0x00, - 0x7C, 0x04, 0x78, 0x04, 0x78, - 0x7C, 0x08, 0x04, 0x04, 0x78, - 0x38, 0x44, 0x44, 0x44, 0x38, - 0xFC, 0x18, 0x24, 0x24, 0x18, - 0x18, 0x24, 0x24, 0x18, 0xFC, - 0x7C, 0x08, 0x04, 0x04, 0x08, - 0x48, 0x54, 0x54, 0x54, 0x24, - 0x04, 0x04, 0x3F, 0x44, 0x24, - 0x3C, 0x40, 0x40, 0x20, 0x7C, - 0x1C, 0x20, 0x40, 0x20, 0x1C, - 0x3C, 0x40, 0x30, 0x40, 0x3C, - 0x44, 0x28, 0x10, 0x28, 0x44, - 0x4C, 0x90, 0x90, 0x90, 0x7C, - 0x44, 0x64, 0x54, 0x4C, 0x44, - 0x00, 0x08, 0x36, 0x41, 0x00, - 0x00, 0x00, 0x77, 0x00, 0x00, - 0x00, 0x41, 0x36, 0x08, 0x00, - 0x02, 0x01, 0x02, 0x04, 0x02, - 0x3C, 0x26, 0x23, 0x26, 0x3C, - 0x1E, 0xA1, 0xA1, 0x61, 0x12, - 0x3A, 0x40, 0x40, 0x20, 0x7A, - 0x38, 0x54, 0x54, 0x55, 0x59, - 0x21, 0x55, 0x55, 0x79, 0x41, - 0x21, 0x54, 0x54, 0x78, 0x41, - 0x21, 0x55, 0x54, 0x78, 0x40, - 0x20, 0x54, 0x55, 0x79, 0x40, - 0x0C, 0x1E, 0x52, 0x72, 0x12, - 0x39, 0x55, 0x55, 0x55, 0x59, - 0x39, 0x54, 0x54, 0x54, 0x59, - 0x39, 0x55, 0x54, 0x54, 0x58, - 0x00, 0x00, 0x45, 0x7C, 0x41, - 0x00, 0x02, 0x45, 0x7D, 0x42, - 0x00, 0x01, 0x45, 0x7C, 0x40, - 0xF0, 0x29, 0x24, 0x29, 0xF0, - 0xF0, 0x28, 0x25, 0x28, 0xF0, - 0x7C, 0x54, 0x55, 0x45, 0x00, - 0x20, 0x54, 0x54, 0x7C, 0x54, - 0x7C, 0x0A, 0x09, 0x7F, 0x49, - 0x32, 0x49, 0x49, 0x49, 0x32, - 0x32, 0x48, 0x48, 0x48, 0x32, - 0x32, 0x4A, 0x48, 0x48, 0x30, - 0x3A, 0x41, 0x41, 0x21, 0x7A, - 0x3A, 0x42, 0x40, 0x20, 0x78, - 0x00, 0x9D, 0xA0, 0xA0, 0x7D, - 0x39, 0x44, 0x44, 0x44, 0x39, - 0x3D, 0x40, 0x40, 0x40, 0x3D, - 0x3C, 0x24, 0xFF, 0x24, 0x24, - 0x48, 0x7E, 0x49, 0x43, 0x66, - 0x2B, 0x2F, 0xFC, 0x2F, 0x2B, - 0xFF, 0x09, 0x29, 0xF6, 0x20, - 0xC0, 0x88, 0x7E, 0x09, 0x03, - 0x20, 0x54, 0x54, 0x79, 0x41, - 0x00, 0x00, 0x44, 0x7D, 0x41, - 0x30, 0x48, 0x48, 0x4A, 0x32, - 0x38, 0x40, 0x40, 0x22, 0x7A, - 0x00, 0x7A, 0x0A, 0x0A, 0x72, - 0x7D, 0x0D, 0x19, 0x31, 0x7D, - 0x26, 0x29, 0x29, 0x2F, 0x28, - 0x26, 0x29, 0x29, 0x29, 0x26, - 0x30, 0x48, 0x4D, 0x40, 0x20, - 0x38, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x08, 0x08, 0x08, 0x38, - 0x2F, 0x10, 0xC8, 0xAC, 0xBA, - 0x2F, 0x10, 0x28, 0x34, 0xFA, - 0x00, 0x00, 0x7B, 0x00, 0x00, - 0x08, 0x14, 0x2A, 0x14, 0x22, - 0x22, 0x14, 0x2A, 0x14, 0x08, - 0xAA, 0x00, 0x55, 0x00, 0xAA, - 0xAA, 0x55, 0xAA, 0x55, 0xAA, - 0x00, 0x00, 0x00, 0xFF, 0x00, - 0x10, 0x10, 0x10, 0xFF, 0x00, - 0x14, 0x14, 0x14, 0xFF, 0x00, - 0x10, 0x10, 0xFF, 0x00, 0xFF, - 0x10, 0x10, 0xF0, 0x10, 0xF0, - 0x14, 0x14, 0x14, 0xFC, 0x00, - 0x14, 0x14, 0xF7, 0x00, 0xFF, - 0x00, 0x00, 0xFF, 0x00, 0xFF, - 0x14, 0x14, 0xF4, 0x04, 0xFC, - 0x14, 0x14, 0x17, 0x10, 0x1F, - 0x10, 0x10, 0x1F, 0x10, 0x1F, - 0x14, 0x14, 0x14, 0x1F, 0x00, - 0x10, 0x10, 0x10, 0xF0, 0x00, - 0x00, 0x00, 0x00, 0x1F, 0x10, - 0x10, 0x10, 0x10, 0x1F, 0x10, - 0x10, 0x10, 0x10, 0xF0, 0x10, - 0x00, 0x00, 0x00, 0xFF, 0x10, - 0x10, 0x10, 0x10, 0x10, 0x10, - 0x10, 0x10, 0x10, 0xFF, 0x10, - 0x00, 0x00, 0x00, 0xFF, 0x14, - 0x00, 0x00, 0xFF, 0x00, 0xFF, - 0x00, 0x00, 0x1F, 0x10, 0x17, - 0x00, 0x00, 0xFC, 0x04, 0xF4, - 0x14, 0x14, 0x17, 0x10, 0x17, - 0x14, 0x14, 0xF4, 0x04, 0xF4, - 0x00, 0x00, 0xFF, 0x00, 0xF7, - 0x14, 0x14, 0x14, 0x14, 0x14, - 0x14, 0x14, 0xF7, 0x00, 0xF7, - 0x14, 0x14, 0x14, 0x17, 0x14, - 0x10, 0x10, 0x1F, 0x10, 0x1F, - 0x14, 0x14, 0x14, 0xF4, 0x14, - 0x10, 0x10, 0xF0, 0x10, 0xF0, - 0x00, 0x00, 0x1F, 0x10, 0x1F, - 0x00, 0x00, 0x00, 0x1F, 0x14, - 0x00, 0x00, 0x00, 0xFC, 0x14, - 0x00, 0x00, 0xF0, 0x10, 0xF0, - 0x10, 0x10, 0xFF, 0x10, 0xFF, - 0x14, 0x14, 0x14, 0xFF, 0x14, - 0x10, 0x10, 0x10, 0x1F, 0x00, - 0x00, 0x00, 0x00, 0xF0, 0x10, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, - 0xFF, 0xFF, 0xFF, 0x00, 0x00, - 0x00, 0x00, 0x00, 0xFF, 0xFF, - 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, - 0x38, 0x44, 0x44, 0x38, 0x44, - 0x7C, 0x2A, 0x2A, 0x3E, 0x14, - 0x7E, 0x02, 0x02, 0x06, 0x06, - 0x02, 0x7E, 0x02, 0x7E, 0x02, - 0x63, 0x55, 0x49, 0x41, 0x63, - 0x38, 0x44, 0x44, 0x3C, 0x04, - 0x40, 0x7E, 0x20, 0x1E, 0x20, - 0x06, 0x02, 0x7E, 0x02, 0x02, - 0x99, 0xA5, 0xE7, 0xA5, 0x99, - 0x1C, 0x2A, 0x49, 0x2A, 0x1C, - 0x4C, 0x72, 0x01, 0x72, 0x4C, - 0x30, 0x4A, 0x4D, 0x4D, 0x30, - 0x30, 0x48, 0x78, 0x48, 0x30, - 0xBC, 0x62, 0x5A, 0x46, 0x3D, - 0x3E, 0x49, 0x49, 0x49, 0x00, - 0x7E, 0x01, 0x01, 0x01, 0x7E, - 0x2A, 0x2A, 0x2A, 0x2A, 0x2A, - 0x44, 0x44, 0x5F, 0x44, 0x44, - 0x40, 0x51, 0x4A, 0x44, 0x40, - 0x40, 0x44, 0x4A, 0x51, 0x40, - 0x00, 0x00, 0xFF, 0x01, 0x03, - 0xE0, 0x80, 0xFF, 0x00, 0x00, - 0x08, 0x08, 0x6B, 0x6B, 0x08, - 0x36, 0x12, 0x36, 0x24, 0x36, - 0x06, 0x0F, 0x09, 0x0F, 0x06, - 0x00, 0x00, 0x18, 0x18, 0x00, - 0x00, 0x00, 0x10, 0x10, 0x00, - 0x30, 0x40, 0xFF, 0x01, 0x01, - 0x00, 0x1F, 0x01, 0x01, 0x1E, - 0x00, 0x19, 0x1D, 0x17, 0x12, - 0x00, 0x3C, 0x3C, 0x3C, 0x3C, - 0x00, 0x00, 0x00, 0x00, 0x00, -}; -#endif diff --git a/source/daemon/src/i2c/i2cdevices/hmc5883/hmc5883.cpp b/source/daemon/src/i2c/i2cdevices/hmc5883/hmc5883.cpp deleted file mode 100644 index 7e9a1474..00000000 --- a/source/daemon/src/i2c/i2cdevices/hmc5883/hmc5883.cpp +++ /dev/null @@ -1,223 +0,0 @@ -#include "i2c/i2cdevices/hmc5883/hmc5883.h" -#include -#include -#include - -/* -* HMC5883 3 axis magnetic field sensor (Honeywell) -*/ - -const double HMC5883::GAIN[8] = { 0.73, 0.92, 1.22, 1.52, 2.27, 2.56, 3.03, 4.35 }; - -bool HMC5883::init() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // init value 0 for gain - fGain = 0; - - // writeBuf[0] = 0x0a; // chip id reg A - // write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // int n=read(readBuf, 3); // Read the id registers into readBuf - // chip id reg A: 0x0a - int n = readReg(0x0a, readBuf, 3); // Read the id registers into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("id reg A: 0x%x \n", readBuf[0]); - printf("id reg B: 0x%x \n", readBuf[1]); - printf("id reg C: 0x%x \n", readBuf[2]); - } - - if (readBuf[0] != 0x48) return false; - - // set CRA - // writeBuf[0] = 0x00; // addr config reg A (CRA) - // writeBuf[1] = 0x70; // 8 average, 15 Hz, single measurement - - // addr config reg A (CRA) - // 8 average, 15 Hz, single measurement: 0x70 - uint8_t cmd = 0x70; - n = writeReg(0x00, &cmd, 1); - - setGain(fGain); - return true; -} - -void HMC5883::setGain(uint8_t gain) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - // set CRB - writeBuf[0] = 0x01; // addr config reg B (CRB) - writeBuf[1] = (gain & 0x07) << 5; // gain=xx - write(writeBuf, 2); - fGain = gain & 0x07; -} - -// uint8_t HMC5883::readGain() -// { -// uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device -// uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device -// -// // set CRB -// writeBuf[0] = 0x01; // addr config reg B (CRB) -// write(writeBuf, 1); -// -// int n=read(readBuf, 1); // Read the config register into readBuf -// -// if (n!=1) return 0; -// uint8_t gain = readBuf[0]>>5; -// if (fDebugLevel>1) -// { -// printf( "%d bytes read\n",n); -// printf( "gain (read from device): 0x%x\n",gain); -// } -// //fGain = gain & 0x07; -// return gain; -// } - -uint8_t HMC5883::readGain() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - int n = readReg(0x01, readBuf, 1); // Read the config register into readBuf - - if (n != 1) return 0; - uint8_t gain = readBuf[0] >> 5; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("gain (read from device): 0x%x\n", gain); - } - //fGain = gain & 0x07; - return gain; -} - -bool HMC5883::readRDYBit() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // addr status reg (SR) - int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf - - if (n != 1) return 0; - uint8_t sr = readBuf[0]; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("status (read from device): 0x%x\n", sr); - } - if ((sr & 0x01) == 0x01) return true; - return false; -} - -bool HMC5883::readLockBit() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // addr status reg (SR) - int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf - - if (n != 1) return 0; - uint8_t sr = readBuf[0]; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("status (read from device): 0x%x\n", sr); - } - if ((sr & 0x02) == 0x02) return true; - return false; -} - -bool HMC5883::getXYZRawValues(int &x, int &y, int &z) -{ - uint8_t readBuf[6]; - - uint8_t cmd = 0x01; // start single measurement - int n = writeReg(0x02, &cmd, 1); // addr mode reg (MR) - usleep(6000); - - // Read the 3 data registers into readBuf starting from addr 0x03 - n = readReg(0x03, readBuf, 6); - int16_t xreg = (int16_t)(readBuf[0] << 8 | readBuf[1]); - int16_t yreg = (int16_t)(readBuf[2] << 8 | readBuf[3]); - int16_t zreg = (int16_t)(readBuf[4] << 8 | readBuf[5]); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - // printf( "xreg: %2x %2x %d\n",readBuf[0], readBuf[1], xreg); - printf("xreg: %d\n", xreg); - printf("yreg: %d\n", yreg); - printf("zreg: %d\n", zreg); - - - } - - x = xreg; y = yreg; z = zreg; - - if (xreg >= -2048 && xreg < 2048 && - yreg >= -2048 && yreg < 2048 && - zreg >= -2048 && zreg < 2048) - return true; - - return false; -} - - -bool HMC5883::getXYZMagneticFields(double &x, double &y, double &z) -{ - int xreg, yreg, zreg; - bool ok = getXYZRawValues(xreg, yreg, zreg); - double lsbgain = GAIN[fGain]; - x = lsbgain * xreg / 1000.; - y = lsbgain * yreg / 1000.; - z = lsbgain * zreg / 1000.; - - if (fDebugLevel > 1) - { - printf("x field: %f G\n", x); - printf("y field: %f G\n", y); - printf("z field: %f G\n", z); - } - - return ok; -} - -bool HMC5883::calibrate(int &x, int &y, int &z) -{ - - // addr config reg A (CRA) - // 8 average, 15 Hz, positive self test measurement: 0x71 - uint8_t cmd = 0x71; - /*int n=*/writeReg(0x00, &cmd, 1); - - uint8_t oldGain = fGain; - setGain(5); - - int xr, yr, zr; - // one dummy measurement - getXYZRawValues(xr, yr, zr); - // measurement - getXYZRawValues(xr, yr, zr); - - x = xr; y = yr; z = zr; - - setGain(oldGain); - // one dummy measurement - getXYZRawValues(xr, yr, zr); - - - // set normal measurement mode in CRA again - cmd = 0x70; - /*n=*/writeReg(0x00, &cmd, 1); - return true; -} diff --git a/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp b/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp deleted file mode 100644 index 1dc94ddf..00000000 --- a/source/daemon/src/i2c/i2cdevices/i2cdevice.cpp +++ /dev/null @@ -1,391 +0,0 @@ -#include "i2c/i2cdevices/i2cdevice.h" -#include -#include -#include -#include // open - -using namespace std; - -unsigned int i2cDevice::fNrDevices = 0; -unsigned long int i2cDevice::fGlobalNrBytesRead = 0; -unsigned long int i2cDevice::fGlobalNrBytesWritten = 0; -std::vector i2cDevice::fGlobalDeviceList; - -i2cDevice::i2cDevice() { - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fNrBytesRead = 0; - fNrBytesWritten = 0; - fAddress = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - fHandle = open("/dev/i2c-1", O_RDWR); - if (fHandle > 0) { - fNrDevices++; - fGlobalDeviceList.push_back(this); - } - else fMode = MODE_FAILED; -} - -i2cDevice::i2cDevice(const char* busAddress) { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open(busAddress, O_RDWR); - if (fHandle > 0) { - fNrDevices++; - fGlobalDeviceList.push_back(this); - } - else fMode = MODE_FAILED; -} - -i2cDevice::i2cDevice(uint8_t slaveAddress) : fAddress(slaveAddress) { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open("/dev/i2c-1", O_RDWR); - if (fHandle > 0) { - //ioctl(fHandle, I2C_SLAVE, fAddress); - setAddress(slaveAddress); - fNrDevices++; - fGlobalDeviceList.push_back(this); - } - else fMode = MODE_FAILED; -} - -i2cDevice::i2cDevice(const char* busAddress, uint8_t slaveAddress) : fAddress(slaveAddress) { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open(busAddress, O_RDWR); - if (fHandle > 0) { - //ioctl(fHandle, I2C_SLAVE, fAddress); - setAddress(slaveAddress); - fNrDevices++; - fGlobalDeviceList.push_back(this); - } - else fMode = MODE_FAILED; -} - -i2cDevice::~i2cDevice() { - //destructor of the opening part from above - if (fHandle > 0) fNrDevices--; - close(fHandle); - std::vector::iterator it; - it = std::find(fGlobalDeviceList.begin(), fGlobalDeviceList.end(), this); - if (it != fGlobalDeviceList.end()) fGlobalDeviceList.erase(it); -} - -void i2cDevice::getCapabilities() -{ - unsigned long funcs; - int res = ioctl(fHandle, I2C_FUNCS, &funcs); - if (res<0) cerr << "error retrieving function capabilities from I2C interface." << endl; - else { - cout << "I2C adapter capabilities: 0x" << hex << funcs << dec << endl; - } -} - -bool i2cDevice::devicePresent() -{ - uint8_t dummy; - return (read(&dummy, 1) == 1); -} - -void i2cDevice::setAddress(uint8_t address) { //pointer to our device on the i2c-bus - fAddress = address; - int res = ioctl(fHandle, I2C_SLAVE, fAddress); //i.g. Specify the address of the I2C Slave to communicate with - if (res<0) { - res = ioctl(fHandle, I2C_SLAVE_FORCE, fAddress); - if (res<0) { - fMode = MODE_FAILED; - fIOErrors++; - } - else fMode = MODE_FORCE; - } - else { - fMode = MODE_NORMAL; - } - // if (ioctl(fd, I2C_SLAVE, devAddr) < 0) { - // fprintf(stderr, "Failed to select device: %s\n", strerror(errno)); - // close(fd); - // return(-1); - // } - -} - -int i2cDevice::read(uint8_t* buf, int nBytes) { //defines a function with a pointer buf as buffer and the number of bytes which - //we want to read. - if (fHandle <= 0 || (fMode & MODE_LOCKED)) return 0; - int nread = ::read(fHandle, buf, nBytes); //"::" declares that the functions does not call itself again, but instead - if (nread > 0) { - fNrBytesRead += nread; - fGlobalNrBytesRead += nread; - fMode &= ~((uint8_t)MODE_UNREACHABLE); - } - else if (nread <= 0) { - fIOErrors++; - fMode |= MODE_UNREACHABLE; - } - return nread; //uses the read funktion with the set parameters of the bool function -} - -int i2cDevice::write(uint8_t* buf, int nBytes) { - if (fHandle <= 0 || (fMode & MODE_LOCKED)) return 0; - int nwritten = ::write(fHandle, buf, nBytes); - if (nwritten > 0) { - fNrBytesWritten += nwritten; - fGlobalNrBytesWritten += nwritten; - fMode &= ~((uint8_t)MODE_UNREACHABLE); - } - else if (nwritten <= 0) { - fIOErrors++; - fMode |= MODE_UNREACHABLE; - } - return nwritten; -} - -int i2cDevice::writeReg(uint8_t reg, uint8_t* buf, int nBytes) -{ - // the i2c_smbus_*_i2c_block_data functions are better but allow - // block sizes of up to 32 bytes only - //i2c_smbus_write_i2c_block_data(int file, reg, nBytes, buf); - - uint8_t writeBuf[nBytes + 1]; - - writeBuf[0] = reg; // first byte is register address - for (int i = 0; i < nBytes; i++) writeBuf[i + 1] = buf[i]; - int n = write(writeBuf, nBytes + 1); - return n - 1; - - // if (length > 127) { - // fprintf(stderr, "Byte write count (%d) > 127\n", length); - // return(FALSE); - // } - // - // fd = open("/dev/i2c-1", O_RDWR); - // if (fd < 0) { - // fprintf(stderr, "Failed to open device: %s\n", strerror(errno)); - // return(FALSE); - // } - // if (ioctl(fd, I2C_SLAVE, devAddr) < 0) { - // fprintf(stderr, "Failed to select device: %s\n", strerror(errno)); - // close(fd); - // return(FALSE); - // } - // buf[0] = regAddr; - // memcpy(buf+1,data,length); - // count = write(fd, buf, length+1); - // if (count < 0) { - // fprintf(stderr, "Failed to write device(%d): %s\n", count, ::strerror(errno)); - // close(fd); - // return(FALSE); - // } else if (count != length+1) { - // fprintf(stderr, "Short write to device, expected %d, got %d\n", length+1, count); - // close(fd); - // return(FALSE); - // } - // close(fd); - -} - -int i2cDevice::readReg(uint8_t reg, uint8_t* buf, int nBytes) -{ - // the i2c_smbus_*_i2c_block_data functions are better but allow - // block sizes of up to 32 bytes only - //i2c_smbus_write_i2c_block_data(int file, reg, nBytes, buf); - //int _n = i2c_smbus_read_i2c_block_data(fHandle, reg, (uint8_t)nBytes, buf); - //return _n; - - int n = write(®, 1); - if (n != 1) return -1; - n = read(buf, nBytes); - return n; -} - -/** Read a single bit from an 8-bit device register. -* @param regAddr Register regAddr to read from -* @param bitNum Bit position to read (0-7) -* @param data Container for single bit value -* @return Status of read operation (true = success) -*/ -int8_t i2cDevice::readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data) { - uint8_t b; - uint8_t count = readReg(regAddr, &b, 1); - *data = b & (1 << bitNum); - return count; -} - -/** Read multiple bits from an 8-bit device register. -* @param regAddr Register regAddr to read from -* @param bitStart First bit position to read (0-7) -* @param length Number of bits to read (not more than 8) -* @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) -* @return Status of read operation (true = success) -*/ -int8_t i2cDevice::readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data) { - // 01101001 read byte - // 76543210 bit numbers - // xxx args: bitStart=4, length=3 - // 010 masked - // -> 010 shifted - uint8_t count, b; - if ((count = readReg(regAddr, &b, 1)) != 0) { - uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); - b &= mask; - b >>= (bitStart - length + 1); - *data = b; - } - return count; -} - -/** Read single byte from an 8-bit device register. -* @param regAddr Register regAddr to read from -* @param data Container for byte value read from device -* @return Status of read operation (true = success) -*/ -bool i2cDevice::readByte(uint8_t regAddr, uint8_t *data) { - return (readBytes(regAddr, 1, data) == 1); -} - -/** Read multiple bytes from an 8-bit device register. -* @param regAddr First register regAddr to read from -* @param length Number of bytes to read -* @param data Buffer to store read data in -* @return Number of bytes read (-1 indicates failure) -*/ -int16_t i2cDevice::readBytes(uint8_t regAddr, uint16_t length, uint8_t *data) { - // not used?! int8_t count = 0; - // int fd = open("/dev/i2c-1", O_RDWR); - return readReg(regAddr, data, length); -} - -/** write a single bit in an 8-bit device register. -* @param regAddr Register regAddr to write to -* @param bitNum Bit position to write (0-7) -* @param data New bit value to write -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data) { - uint8_t b; - int n = readByte(regAddr, &b); - if (n != 1) return false; - b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); - return writeByte(regAddr, b); -} - -/** Write multiple bits in an 8-bit device register. -* @param regAddr Register regAddr to write to -* @param bitStart First bit position to write (0-7) -* @param length Number of bits to write (not more than 8) -* @param data Right-aligned value to write -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) { - // 010 value to write - // 76543210 bit numbers - // xxx args: bitStart=4, length=3 - // 00011100 mask byte - // 10101111 original value (sample) - // 10100011 original & ~mask - // 10101011 masked | value - uint8_t b; - if (readByte(regAddr, &b) != 0) { - uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); - data <<= (bitStart - length + 1); // shift data into correct position - data &= mask; // zero all non-important bits in data - b &= ~(mask); // zero all important bits in existing byte - b |= data; // combine data with existing byte - return writeByte(regAddr, b); - } - else { - return false; - } -} - -/** Write single byte to an 8-bit device register. -* @param regAddr Register address to write to -* @param data New byte value to write -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeByte(uint8_t regAddr, uint8_t data) { - return writeBytes(regAddr, 1, &data); -} - -/** Write multiple bytes to an 8-bit device register. -* @param devAddr I2C slave device address -* @param regAddr First register address to write to -* @param length Number of bytes to write -* @param data Buffer to copy new data from -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data) { - // int8_t count = 0; - // uint8_t buf[128]; - // int fd; - - int n = writeReg(regAddr, data, length); - return (n == length); -} - -/** Write multiple words to a 16-bit device register. -* @param regAddr First register address to write to -* @param length Number of words to write -* @param data Buffer to copy new data from -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeWords(uint8_t regAddr, uint16_t length, uint16_t* data) { - int8_t count = 0; - uint8_t buf[512]; - - // Should do potential byteswap and call writeBytes() really, but that - // messes with the callers buffer - - for (int i = 0; i < length; i++) { - buf[i * 2] = data[i] >> 8; - buf[i * 2 + 1] = data[i]; - } - - count = writeReg(regAddr, buf, length * 2); - // count = write(fd, buf, length*2+1); - if (count < 0) { - fprintf(stderr, "Failed to write device(%d): %s\n", count, ::strerror(errno)); - // close(fd); - return(false); - } - else if (count != length * 2) { - fprintf(stderr, "Short write to device, expected %d, got %d\n", length + 1, count); - // close(fd); - return(false); - } - // close(fd); - return true; -} - -/** Write single word to a 16-bit device register. -* @param regAddr Register address to write to -* @param data New word value to write -* @return Status of operation (true = success) -*/ -bool i2cDevice::writeWord(uint8_t regAddr, uint16_t data) { - return writeWords(regAddr, 1, &data); -} - -void i2cDevice::startTimer() { - gettimeofday(&fT1, NULL); -} - -void i2cDevice::stopTimer() { - gettimeofday(&fT2, NULL); - // compute and print the elapsed time in millisec - double elapsedTime = (fT2.tv_sec - fT1.tv_sec) * 1000.0; // sec to ms - elapsedTime += (fT2.tv_usec - fT1.tv_usec) / 1000.0; // us to ms - fLastTimeInterval = elapsedTime; - if (fDebugLevel > 1) - printf(" last transaction took: %6.2f ms\n", fLastTimeInterval); -} diff --git a/source/daemon/src/i2c/i2cdevices/lm75/lm75.cpp b/source/daemon/src/i2c/i2cdevices/lm75/lm75.cpp deleted file mode 100644 index 3fdf981c..00000000 --- a/source/daemon/src/i2c/i2cdevices/lm75/lm75.cpp +++ /dev/null @@ -1,53 +0,0 @@ -#include "i2c/i2cdevices/lm75/lm75.h" -#include - -/* -* LM75 Temperature Sensor -*/ - -int16_t LM75::readRaw() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - - startTimer(); - - readBuf[0] = 0; - readBuf[1] = 0; - - read(readBuf, 2); // Read the config register into readBuf - - //int8_t temperature0 = (int8_t)readBuf[0]; - - // We extract the first bit and right shift 7 seven bit positions. - // Why? Because we don't care about the bits 6,5,4,3,2,1 and 0. - // int8_t temperature1 = (readBuf[1] & 0x80) >> 7; // is either zero or one - // int8_t temperature1 = (readBuf[1] & 0xf8) >> 3; - //int8_t temperature1 = (readBuf[1] & 0xff); - - //val = (temperature0 << 8) | temperature1; - //val = readBuf[0] << 1 | (readBuf[1] >> 7); // Combine the two bytes of readBuf into a single 16 bit result - val = ((int16_t)readBuf[0] << 8) | readBuf[1]; - fLastRawValue = val; - - stopTimer(); - - return val; -} - -bool LM75::devicePresent() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - readBuf[0] = 0; - readBuf[1] = 0; - int n = read(readBuf, 2); // Read the data register into readBuf - return (n == 2); -} - -double LM75::getTemperature() -{ - fLastTemp=(double)readRaw() / 256.; - return fLastTemp; -} - diff --git a/source/daemon/src/i2c/i2cdevices/mcp4728/mcp4728.cpp b/source/daemon/src/i2c/i2cdevices/mcp4728/mcp4728.cpp deleted file mode 100644 index b41ecdad..00000000 --- a/source/daemon/src/i2c/i2cdevices/mcp4728/mcp4728.cpp +++ /dev/null @@ -1,130 +0,0 @@ -#include "i2c/i2cdevices/mcp4728/mcp4728.h" -#include - -/* -* MCP4728 4 ch 12 bit DAC -*/ - -const float MCP4728::VDD = 3.3; // change, if device powered with different voltage - -bool MCP4728::setVoltage(uint8_t channel, float voltage, bool toEEPROM) { - // Vout = (2.048V * Dn) / 4096 * Gx <= VDD - if (voltage < 0) { - return false; - } - uint8_t gain = 0; - unsigned int value = (int)(voltage * 2000 + 0.5); - if (value > 0xfff) { - value = value >> 1; - gain = 1; - } - if (value > 0xfff) { - // error message - return false; - } - return setValue(channel, value, gain, toEEPROM); -} - -bool MCP4728::setValue(uint8_t channel, uint16_t value, uint8_t gain, bool toEEPROM) { - if (value > 0xfff) { - value = 0xfff; - // error number of bits exceeding 12 - return false; - } - startTimer(); - channel = channel & 0x03; - uint8_t buf[3]; - if (toEEPROM) { - buf[0] = 0b01011001; - } - else { - buf[0] = 0b01000001; - } - buf[0] = buf[0] | (channel << 1); // 01000/01011 (multiwrite/singlewrite command) DAC1 DAC0 (channel) UDAC bit =1 - buf[1] = 0b10000000 | (uint8_t)((value & 0xf00) >> 8); // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 - buf[1] = buf[1] | (gain << 4); - buf[2] = (uint8_t)(value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 - if (write(buf, 3) != 3) { - // somehow did not write exact same amount of bytes as it should - return false; - } - stopTimer(); - fLastConvTime = fLastTimeInterval; - return true; -} - -bool MCP4728::writeChannel(uint8_t channel, const DacChannel& channelData) -{ - if (channelData.value > 0xfff) { - //channelData.value = 0xfff; - // error number of bits exceeding 12 - return false; - } - startTimer(); - channel = channel & 0x03; - uint8_t buf[3]; - if (channelData.eeprom) { - buf[0] = 0b01011001; - } - else { - buf[0] = 0b01000001; - } - buf[0] |= (channel << 1); // 01000/01011 (multiwrite/singlewrite command) DAC1 DAC0 (channel) UDAC bit =1 - buf[1] = ((uint8_t)channelData.vref) << 7; // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 - buf[1] |= (channelData.pd & 0x03) << 5; - buf[1] |= (uint8_t)((channelData.value & 0xf00) >> 8); - buf[1] |= (uint8_t)(channelData.gain & 0x01) << 4; - buf[2] = (uint8_t)(channelData.value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 - if (write(buf, 3) != 3) { - // somehow did not write exact same amount of bytes as it should - return false; - } - stopTimer(); - return true; -} - -bool MCP4728::devicePresent() -{ - uint8_t buf[24]; - startTimer(); - // perform a read sequence of all registers as described in datasheet - int n = read(buf, 24); - stopTimer(); - return (n == 24); - -} - -bool MCP4728::readChannel(uint8_t channel, DacChannel& channelData) -{ - if (channel > 3) { - // error: channel index exceeding 3 - return false; - } - - startTimer(); - - uint8_t buf[24]; - if (read(buf, 24) != 24) { - // somehow did not read exact same amount of bytes as it should - stopTimer(); - return false; - } - uint8_t offs = (channelData.eeprom == false) ? 1 : 4; - channelData.vref = (buf[channel * 6 + offs] & 0x80) ? VREF_2V : VREF_VDD; - channelData.pd = (buf[channel * 6 + offs] & 0x60) >> 5; - channelData.gain = (buf[channel * 6 + offs] & 0x10) ? GAIN2 : GAIN1; - channelData.value = (uint16_t)(buf[channel * 6 + offs] & 0x0f) << 8; - channelData.value |= (uint16_t)(buf[channel * 6 + offs + 1] & 0xff); - - stopTimer(); - - return true; -} - -float MCP4728::code2voltage(const DacChannel& channelData) -{ - float vref = (channelData.vref == VREF_2V) ? 2.048 : VDD; - float voltage = vref * channelData.value / 4096; - if (channelData.gain == GAIN2 && channelData.vref != VREF_VDD) voltage *= 2.; - return voltage; -} diff --git a/source/daemon/src/i2c/i2cdevices/pca9536/pca9536.cpp b/source/daemon/src/i2c/i2cdevices/pca9536/pca9536.cpp deleted file mode 100644 index 27488a30..00000000 --- a/source/daemon/src/i2c/i2cdevices/pca9536/pca9536.cpp +++ /dev/null @@ -1,39 +0,0 @@ -#include "i2c/i2cdevices/pca9536/pca9536.h" -#include - -/* -* PCA9536 4 pin I/O expander -*/ - -bool PCA9536::setOutputPorts(uint8_t portMask) { - unsigned char data = ~portMask; - startTimer(); - if (1 != writeReg(CONFIG_REG, &data, 1)) { - return false; - } - stopTimer(); - return true; -} - -bool PCA9536::setOutputState(uint8_t portMask) { - startTimer(); - if (1 != writeReg(OUTPUT_REG, &portMask, 1)) { - return false; - } - stopTimer(); - return true; -} - -uint8_t PCA9536::getInputState() { - uint8_t inport = 0x00; - startTimer(); - readReg(INPUT_REG, &inport, 1); - stopTimer(); - return inport & 0x0f; -} - -bool PCA9536::devicePresent() { - uint8_t inport = 0x00; - // read input port - return (1 == readReg(INPUT_REG, &inport, 1)); -} diff --git a/source/daemon/src/i2c/i2cdevices/sht21/sht21.cpp b/source/daemon/src/i2c/i2cdevices/sht21/sht21.cpp deleted file mode 100644 index c0c21b8b..00000000 --- a/source/daemon/src/i2c/i2cdevices/sht21/sht21.cpp +++ /dev/null @@ -1,175 +0,0 @@ -#include "i2c/i2cdevices/sht21/sht21.h" -#include -#include - -/* -* SHT21 Temperature&Humidity Sensor -* Prefered option is the no hold mastermode -*/ - -bool SHT21::checksumCorrect(uint8_t data[]) // expects data to be greater or equal 3 (expecting 3) -{ - const uint16_t Polynom = 0x131; - uint8_t crc = 0; - uint8_t byteCtr; - uint8_t bit; - try { - for (byteCtr = 0; byteCtr < 2; ++byteCtr) - { - crc ^= (data[byteCtr]); - for (bit = 8; bit > 0; --bit) - { - if (crc & 0x80) - { - crc = (crc << 1) ^ Polynom; - } - else - { - crc = (crc << 1); - } - } - } - if (crc != data[2]) - { - return false; - } - else - { - return true; - } - } - catch (int i) { - printf("Error, Array too small in function: checksumCorrect\n"); - return false; - } -} - -float SHT21::getHumidity() -{ - uint16_t data_hum = readUH(); - float fhum; //end calculation -> Humidity - fhum = -6.0 + 125.0 * (((float)(data_hum)) / 65536.0); - return (fhum); -} - -float SHT21::getTemperature() -{ - uint16_t data_temp = readUT(); - float ftemp; //endl calculation -> Temperature - ftemp = -46.85 + 175.72 * (((float)(data_temp)) / 65536.0); - return (ftemp); -} - - -uint16_t SHT21::readUT() // von unsigned int auf float geändert -{ - uint8_t writeBuf[1]; - uint8_t readBuf[3]; - uint16_t data_temp; - - writeBuf[0] = 0; - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - data_temp = 0; - - writeReg(0xF3, writeBuf, 0); - usleep(85000); - while (read(readBuf, 3) != 3); - - if (fDebugLevel > 1) - { - printf("Inhalt: (MSB Byte): %x\n", readBuf[0]); - printf("Inhalt: (LSB Byte): %x\n", readBuf[1]); - printf("Inhalt: (Checksum Byte): %x\n", readBuf[2]); - } - - data_temp = ((uint16_t)readBuf[0]) << 8; - data_temp |= readBuf[1]; - data_temp &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. - - if (!checksumCorrect(readBuf)) - { - printf("checksum error\n"); - } - return data_temp; -} - -uint16_t SHT21::readUH() //Hold mode -{ - uint8_t writeBuf[1]; - uint8_t readBuf[3]; //what should be read later - uint16_t data_hum; - - writeBuf[0] = 0; - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - data_hum = 0; - - writeReg(0xF5, writeBuf, 0); - usleep(30000); - while (read(readBuf, 3) != 3); - - - if (fDebugLevel>1) - { - printf("Es wurden gelesen (MSB Bytes): %x\n", readBuf[0]); - printf("Es wurden gelesen (LSB Bytes): %x\n", readBuf[1]); - printf("Es wurden gelesen (Checksum Bytes): %x\n", readBuf[2]); - } - - data_hum = ((uint16_t)readBuf[0]) << 8; - data_hum |= readBuf[1]; - data_hum &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. - - if (!checksumCorrect(readBuf)) - { - printf("checksum error\n"); - } - return data_hum; -} - - - -uint8_t SHT21::readResolutionSettings() -{ //reads the temperature and humidity resolution settings byte - uint8_t readBuf[1]; - - readBuf[0] = 0; //Initialization - - readReg(0xE7, readBuf, 1); - return readBuf[0]; -} - -void SHT21::setResolutionSettings(uint8_t settingsByte) -{ //sets the temperature and humidity resolution settings byte - uint8_t readBuf[1]; - readBuf[0] = 0; //Initialization - readReg(0xE7, readBuf, 1); - readBuf[0] &= 0b00111000; // mask, to not change reserved bits (Bit 3, 4 and 5 are reserved) - settingsByte &= 0b11000111; - uint8_t writeBuf[1]; - writeBuf[0] = settingsByte | readBuf[0]; - writeReg(0xE6, writeBuf, 1); -} - - -bool SHT21::softReset() -{ - uint8_t writeBuf[1]; - writeBuf[0] = 0xFE; - - int n = 0; - n = writeReg(0xFE, writeBuf, 0); - usleep(15000); //wait for the SHT to reset; datasheet on page 9 - - if (n == 0) - { - printf("soft_reset succesfull %i\n", n); - } - - return(n == 0); //Wenn n == 0, gibt die Funktion True zurück. Wenn nicht gibt sie False zurück. - - -} diff --git a/source/daemon/src/i2c/i2cdevices/sht31/Makefile b/source/daemon/src/i2c/i2cdevices/sht31/Makefile deleted file mode 100644 index 599bcbb4..00000000 --- a/source/daemon/src/i2c/i2cdevices/sht31/Makefile +++ /dev/null @@ -1,19 +0,0 @@ -LFLAGS = -O -CPP = g++ -std=c++11 -CFLAGS = -c -O -OBJS = sht31.o i2cdevice.o sht31_test.o - -sht31_test : $(OBJS) - $(CPP) $(OBJS) $(LFLAGS) -o sht31_test - -sht31_test.o : sht31_test.cpp sht31.h ../i2cdevice.h - $(CPP) $(CFLAGS) sht31_test.cpp - -sht31.o : sht31.cpp sht31.h ../i2cdevice.h - $(CPP) $(CFLAGS) sht31.cpp - -i2cdevice.o : ../i2cdevice.cpp ../i2cdevice.h - $(CPP) $(CFLAGS) ../i2cdevice.cpp - -clean : - \rm -f *.o *~ $(OBJS) \ No newline at end of file diff --git a/source/daemon/src/i2c/i2cdevices/sht31/sht31_test.cpp b/source/daemon/src/i2c/i2cdevices/sht31/sht31_test.cpp deleted file mode 100644 index c94e2552..00000000 --- a/source/daemon/src/i2c/i2cdevices/sht31/sht31_test.cpp +++ /dev/null @@ -1,23 +0,0 @@ -#include "sht31.h" -#include -#include - -using namespace std; - -int main() { - SHT31 sensor = SHT31(); - uint16_t UT = 0; - uint16_t UH = 0; - float temp = 0., hum = 0.; - sensor.softReset(); - sensor.breakCommand(); - for (int j = 0; j < 3; j++) { - sensor.heater(j % 2); - for (int i = 0; i < 5; i++) { - cout << sensor.readRaw(UT, UH) << " " << UT << " " << UH << " "; - cout << sensor.getValues(temp, hum) << " " << temp << " " << hum << " heater: " << j%2 << endl; - usleep(2000000); - } - } - return 0; -} \ No newline at end of file diff --git a/source/daemon/src/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp b/source/daemon/src/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp deleted file mode 100644 index ccec6709..00000000 --- a/source/daemon/src/i2c/i2cdevices/ubloxi2c/ubloxi2c.cpp +++ /dev/null @@ -1,48 +0,0 @@ -#include "i2c/i2cdevices/ubloxi2c/ubloxi2c.h" -#include -#include -#include -#include - -/* Ublox GPS receiver, I2C interface */ - -bool UbloxI2c::devicePresent() -{ - uint8_t dummy; - return (1 == readReg(0xff, &dummy, 1)); - // return getTxBufCount(dummy); -} - -std::string UbloxI2c::getData() -{ - uint16_t nrBytes = 0; - if (!getTxBufCount(nrBytes)) return ""; - if (nrBytes == 0) return ""; - uint8_t reg = 0xff; - int n = write(®, 1); - if (n != 1) return ""; - uint8_t buf[128]; - if (nrBytes>128) nrBytes = 128; - n = read(buf, nrBytes); - if (n != nrBytes) return ""; - std::string str(nrBytes, ' '); - std::transform(&buf[0], &buf[nrBytes], str.begin(), [](uint8_t c) { return (unsigned char)c; }); - return str; - // std::copy(buf[0], buf[nrBytes-1], std::back_inserter(str)); -} - -bool UbloxI2c::getTxBufCount(uint16_t& nrBytes) -{ - startTimer(); - uint8_t reg = 0xfd; - uint8_t buf[2]; - int n = write(®, 1); - if (n != 1) return false; - n = read(buf, 2); // Read the data at TX buf counter location - stopTimer(); - if (n != 2) return false; - uint16_t temp = buf[1]; - temp |= (uint16_t)buf[0] << 8; - nrBytes = temp; - return true; -} diff --git a/source/daemon/src/i2c/i2cdevices/x9119/x9119.cpp b/source/daemon/src/i2c/i2cdevices/x9119/x9119.cpp deleted file mode 100644 index 564350e1..00000000 --- a/source/daemon/src/i2c/i2cdevices/x9119/x9119.cpp +++ /dev/null @@ -1,208 +0,0 @@ -#include "i2c/i2cdevices/x9119/x9119.h" -#include -#include - -/* -* X9119 -*/ - -unsigned int X9119::readWiperReg() -{ - - // just return the locally stored last value written to WCR - // since readback doesn't work without repeated start transaction - return fWiperReg; - - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80; // op-code read WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - /*int n=*/read(readBuf, 2); // Read the config register into readBuf - // printf( "%d bytes read\n",n); - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; -} - -unsigned int X9119::readDataReg(uint8_t reg) -{ - - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80 | 0x20 | (reg & 0x03) << 2; // op-code read data reg - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - /*int n=*/read(readBuf, 2); // Read the config register into readBuf - // printf( "%d bytes read\n",n); - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - -} - - -unsigned int X9119::readWiperReg2() -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80; // op-code read WCR - - - struct i2c_msg rdwr_msgs[2]; - - rdwr_msgs[0].addr = fAddress; - rdwr_msgs[0].flags = 0; - rdwr_msgs[0].len = 1; - rdwr_msgs[0].buf = (char*)writeBuf; - - rdwr_msgs[1].addr = fAddress; - rdwr_msgs[1].flags = I2C_M_RD; - rdwr_msgs[1].len = 2; - rdwr_msgs[1].buf = (char*)readBuf; - - /* - = { - { - .addr = fAddress, - .flags = 0, // write - .len = 1, - .buf = writeBuf - }, - { // Read buffer - .addr = fAddress, - .flags = I2C_M_RD, // read - .len = 2, - .buf = readBuf - } - };*/ - - struct i2c_rdwr_ioctl_data rdwr_data; - - rdwr_data.msgs = rdwr_msgs; - rdwr_data.nmsgs = 2; - - // = { - // .msgs = rdwr_msgs, - // .nmsgs = 2 - // }; - - - //::close(fHandle); - //fHandle = ::open( "/dev/i2c-1", O_RDWR ); - - int result = ioctl(fHandle, I2C_RDWR, &rdwr_data); - - if (result < 0) { - printf("rdwr ioctl error: %d\n", errno); - perror("reason"); - } - else { - printf("rdwr ioctl OK\n"); - // for ( i = 0; i < 16; ++i ) { - // printf( "%c", buffer[i] ); - // } - // printf( "\n" ); - } - - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - - - writeBuf[0] = 0x80; // op-code read WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - read(readBuf, 2); // Read the config register into readBuf - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - -} - -unsigned int X9119::readWiperReg3() -{ - - union i2c_smbus_data data; - struct i2c_smbus_ioctl_data args; - - args.read_write = I2C_SMBUS_READ; - args.command = 0x80; - args.size = I2C_SMBUS_WORD_DATA; - args.data = &data; - int result = ioctl(fHandle, I2C_SMBUS, &args); - if (result < 0) { - printf("rdwr ioctl error: %d\n", errno); - perror("reason"); - return 0; - } - else { - printf("rdwr ioctl OK\n"); - // for ( i = 0; i < 16; ++i ) { - // printf( "%c", buffer[i] ); - // } - // printf( "\n" ); - } - return 0x0FFFF & data.word; -} - - - -void X9119::writeWiperReg(unsigned int value) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - writeBuf[0] = 0x80 | 0x20; // op-code write WCR - writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR - writeBuf[2] = (value & 0xff); // LSB of WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - int n = write(writeBuf, 3); - //printf( "%d bytes written\n",n); - if (n == 3) fWiperReg = value; - -} - -void X9119::writeDataReg(uint8_t reg, unsigned int value) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - writeBuf[0] = 0x80 | 0x40 | (reg & 0x03) << 2; // op-code write data reg - writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR - writeBuf[2] = (value & 0xff); // LSB of WCR - - // Write writeBuf to the X9119 - // this sets the write address for data register and writes dr with value - /*int n=*/write(writeBuf, 3); - // printf( "%d bytes written\n",n); - -} diff --git a/source/daemon/src/i2c/i2cdevices_old/i2cdevices.cpp b/source/daemon/src/i2c/i2cdevices_old/i2cdevices.cpp deleted file mode 100644 index d9c1bfe5..00000000 --- a/source/daemon/src/i2c/i2cdevices_old/i2cdevices.cpp +++ /dev/null @@ -1,2697 +0,0 @@ -#include -#include -#include -#include -#include // open -#include -#include -#include // ioctl -#include // uint8_t, etc -//#include // I2C bus definitions for linux like systems -//#include // I2C bus definitions for linux like systems -#include -#include -#include -#include "i2cdevices.h" - -#define DEFAULT_DEBUG_LEVEL 0 - -using namespace std; - -unsigned int i2cDevice::fNrDevices = 0; -unsigned long int i2cDevice::fGlobalNrBytesRead = 0; -unsigned long int i2cDevice::fGlobalNrBytesWritten = 0; -std::vector i2cDevice::fGlobalDeviceList; - -const double ADS1115::PGAGAINS[6] = { 6.144, 4.096, 2.048, 1.024, 0.512, 0.256 }; -const float MCP4728::VDD = 3.3; // change, if device powered with different voltage -const double HMC5883::GAIN[8] = { 0.73, 0.92, 1.22, 1.52, 2.27, 2.56, 3.03, 4.35 }; - - -i2cDevice::i2cDevice() { - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fNrBytesRead = 0; - fNrBytesWritten = 0; - fAddress = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - fHandle = open("/dev/i2c-1", O_RDWR); - if (fHandle > 0) { - fNrDevices++; - fGlobalDeviceList.push_back(this); - } else fMode=MODE_FAILED; -} - -i2cDevice::i2cDevice(const char* busAddress = "/dev/i2c-1") { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open(busAddress, O_RDWR); - if (fHandle > 0) { - fNrDevices++; - fGlobalDeviceList.push_back(this); - } else fMode=MODE_FAILED; -} - -i2cDevice::i2cDevice(uint8_t slaveAddress) : fAddress(slaveAddress) { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open("/dev/i2c-1", O_RDWR); - if (fHandle > 0) { - //ioctl(fHandle, I2C_SLAVE, fAddress); - setAddress(slaveAddress); - fNrDevices++; - fGlobalDeviceList.push_back(this); - } else fMode=MODE_FAILED; -} - -i2cDevice::i2cDevice(const char* busAddress, uint8_t slaveAddress) : fAddress(slaveAddress) { - fNrBytesRead = 0; - fNrBytesWritten = 0; - fDebugLevel = DEFAULT_DEBUG_LEVEL; - //opening the devicefile from the i2c driversection (open the device i2c) - //"/dev/i2c-0" or "../i2c-1" for linux system. In our case - fHandle = open(busAddress, O_RDWR); - if (fHandle > 0) { - //ioctl(fHandle, I2C_SLAVE, fAddress); - setAddress(slaveAddress); - fNrDevices++; - fGlobalDeviceList.push_back(this); - } else fMode=MODE_FAILED; -} - -i2cDevice::~i2cDevice() { - //destructor of the opening part from above - if (fHandle > 0) fNrDevices--; - close(fHandle); - std::vector::iterator it; - it = std::find(fGlobalDeviceList.begin(), fGlobalDeviceList.end(), this); - if (it!=fGlobalDeviceList.end()) fGlobalDeviceList.erase(it); -} - -void i2cDevice::getCapabilities() -{ - unsigned long funcs; - int res = ioctl(fHandle, I2C_FUNCS, &funcs); - if (res<0) cerr<<"error retrieving function capabilities from I2C interface."< 0) { - fNrBytesRead += nread; - fGlobalNrBytesRead += nread; - fMode &= ~((uint8_t)MODE_UNREACHABLE); - } else if (nread<=0) { - fMode |= MODE_UNREACHABLE; - } - return nread; //uses the read funktion with the set parameters of the bool function -} - -int i2cDevice::write(uint8_t* buf, int nBytes) { - if (fHandle<=0) return 0; - int nwritten = ::write(fHandle, buf, nBytes); - if (nwritten > 0) { - fNrBytesWritten += nwritten; - fGlobalNrBytesWritten += nwritten; - fMode &= ~((uint8_t)MODE_UNREACHABLE); - } else if (nwritten<=0) { - fMode |= MODE_UNREACHABLE; - } - return nwritten; -} - -int i2cDevice::writeReg(uint8_t reg, uint8_t* buf, int nBytes) -{ - // the i2c_smbus_*_i2c_block_data functions are better but allow - // block sizes of up to 32 bytes only - //i2c_smbus_write_i2c_block_data(int file, reg, nBytes, buf); - - uint8_t writeBuf[nBytes + 1]; - - writeBuf[0] = reg; // first byte is register address - for (int i = 0; i < nBytes; i++) writeBuf[i + 1] = buf[i]; - int n = write(writeBuf, nBytes + 1); - return n - 1; - - // if (length > 127) { - // fprintf(stderr, "Byte write count (%d) > 127\n", length); - // return(FALSE); - // } - // - // fd = open("/dev/i2c-1", O_RDWR); - // if (fd < 0) { - // fprintf(stderr, "Failed to open device: %s\n", strerror(errno)); - // return(FALSE); - // } - // if (ioctl(fd, I2C_SLAVE, devAddr) < 0) { - // fprintf(stderr, "Failed to select device: %s\n", strerror(errno)); - // close(fd); - // return(FALSE); - // } - // buf[0] = regAddr; - // memcpy(buf+1,data,length); - // count = write(fd, buf, length+1); - // if (count < 0) { - // fprintf(stderr, "Failed to write device(%d): %s\n", count, ::strerror(errno)); - // close(fd); - // return(FALSE); - // } else if (count != length+1) { - // fprintf(stderr, "Short write to device, expected %d, got %d\n", length+1, count); - // close(fd); - // return(FALSE); - // } - // close(fd); - -} - -int i2cDevice::readReg(uint8_t reg, uint8_t* buf, int nBytes) -{ - // the i2c_smbus_*_i2c_block_data functions are better but allow - // block sizes of up to 32 bytes only - //i2c_smbus_write_i2c_block_data(int file, reg, nBytes, buf); - //int _n = i2c_smbus_read_i2c_block_data(fHandle, reg, (uint8_t)nBytes, buf); - //return _n; - - int n = write(®, 1); - if (n != 1) return -1; - n = read(buf, nBytes); - return n; -} - -/** Read a single bit from an 8-bit device register. - * @param regAddr Register regAddr to read from - * @param bitNum Bit position to read (0-7) - * @param data Container for single bit value - * @return Status of read operation (true = success) - */ -int8_t i2cDevice::readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data) { - uint8_t b; - uint8_t count = readReg(regAddr, &b, 1); - *data = b & (1 << bitNum); - return count; -} - -/** Read multiple bits from an 8-bit device register. - * @param regAddr Register regAddr to read from - * @param bitStart First bit position to read (0-7) - * @param length Number of bits to read (not more than 8) - * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) - * @return Status of read operation (true = success) - */ -int8_t i2cDevice::readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data) { - // 01101001 read byte - // 76543210 bit numbers - // xxx args: bitStart=4, length=3 - // 010 masked - // -> 010 shifted - uint8_t count, b; - if ((count = readReg(regAddr, &b, 1)) != 0) { - uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); - b &= mask; - b >>= (bitStart - length + 1); - *data = b; - } - return count; -} - -/** Read single byte from an 8-bit device register. - * @param regAddr Register regAddr to read from - * @param data Container for byte value read from device - * @return Status of read operation (true = success) - */ -bool i2cDevice::readByte(uint8_t regAddr, uint8_t *data) { - return (readBytes(regAddr, 1, data) == 1); -} - -/** Read multiple bytes from an 8-bit device register. - * @param regAddr First register regAddr to read from - * @param length Number of bytes to read - * @param data Buffer to store read data in - * @return Number of bytes read (-1 indicates failure) - */ -int16_t i2cDevice::readBytes(uint8_t regAddr, uint16_t length, uint8_t *data) { - // not used?! int8_t count = 0; -// int fd = open("/dev/i2c-1", O_RDWR); - return readReg(regAddr, data, length); -} - -/** write a single bit in an 8-bit device register. - * @param regAddr Register regAddr to write to - * @param bitNum Bit position to write (0-7) - * @param data New bit value to write - * @return Status of operation (true = success) - */ -bool i2cDevice::writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data) { - uint8_t b; - int n = readByte(regAddr, &b); - if (n != 1) return false; - b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); - return writeByte(regAddr, b); -} - -/** Write multiple bits in an 8-bit device register. - * @param regAddr Register regAddr to write to - * @param bitStart First bit position to write (0-7) - * @param length Number of bits to write (not more than 8) - * @param data Right-aligned value to write - * @return Status of operation (true = success) - */ -bool i2cDevice::writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) { - // 010 value to write - // 76543210 bit numbers - // xxx args: bitStart=4, length=3 - // 00011100 mask byte - // 10101111 original value (sample) - // 10100011 original & ~mask - // 10101011 masked | value - uint8_t b; - if (readByte(regAddr, &b) != 0) { - uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); - data <<= (bitStart - length + 1); // shift data into correct position - data &= mask; // zero all non-important bits in data - b &= ~(mask); // zero all important bits in existing byte - b |= data; // combine data with existing byte - return writeByte(regAddr, b); - } - else { - return false; - } -} - -/** Write single byte to an 8-bit device register. - * @param regAddr Register address to write to - * @param data New byte value to write - * @return Status of operation (true = success) - */ -bool i2cDevice::writeByte(uint8_t regAddr, uint8_t data) { - return writeBytes(regAddr, 1, &data); -} - -/** Write multiple bytes to an 8-bit device register. - * @param devAddr I2C slave device address - * @param regAddr First register address to write to - * @param length Number of bytes to write - * @param data Buffer to copy new data from - * @return Status of operation (true = success) - */ -bool i2cDevice::writeBytes(uint8_t regAddr, uint16_t length, uint8_t* data) { - // int8_t count = 0; - // uint8_t buf[128]; - // int fd; - - int n = writeReg(regAddr, data, length); - return (n == length); -} - -/** Write multiple words to a 16-bit device register. - * @param regAddr First register address to write to - * @param length Number of words to write - * @param data Buffer to copy new data from - * @return Status of operation (true = success) - */ -bool i2cDevice::writeWords(uint8_t regAddr, uint16_t length, uint16_t* data) { - int8_t count = 0; - uint8_t buf[512]; - - // Should do potential byteswap and call writeBytes() really, but that - // messes with the callers buffer - - for (int i = 0; i < length; i++) { - buf[i * 2] = data[i] >> 8; - buf[i * 2 + 1] = data[i]; - } - - count = writeReg(regAddr, buf, length * 2); - // count = write(fd, buf, length*2+1); - if (count < 0) { - fprintf(stderr, "Failed to write device(%d): %s\n", count, ::strerror(errno)); - // close(fd); - return(false); - } - else if (count != length * 2) { - fprintf(stderr, "Short write to device, expected %d, got %d\n", length + 1, count); - // close(fd); - return(false); - } - // close(fd); - return true; -} - -/** Write single word to a 16-bit device register. - * @param regAddr Register address to write to - * @param data New word value to write - * @return Status of operation (true = success) - */ -bool i2cDevice::writeWord(uint8_t regAddr, uint16_t data) { - return writeWords(regAddr, 1, &data); -} - -void i2cDevice::startTimer() { - gettimeofday(&fT1, NULL); -} - -void i2cDevice::stopTimer() { - gettimeofday(&fT2, NULL); - // compute and print the elapsed time in millisec - double elapsedTime = (fT2.tv_sec - fT1.tv_sec) * 1000.0; // sec to ms - elapsedTime += (fT2.tv_usec - fT1.tv_usec) / 1000.0; // us to ms - fLastTimeInterval = elapsedTime; - if (fDebugLevel > 1) - printf(" last transaction took: %6.2f ms\n", fLastTimeInterval); -} - - -/* - * ADS1115 4ch 16 bit ADC - */ -int16_t ADS1115::readADC(unsigned int channel) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - // uint8_t fDataRate = 0x07; // 860 SPS - // uint8_t fDataRate = 0x01; // 16 SPS - uint8_t fDataRate = fRate & 0x07; - - startTimer(); - - // These three bytes are written to the ADS1115 to set the config register and start a conversion - writeBuf[0] = 0x01; // This sets the pointer register so that the following two bytes write to the config register - writeBuf[1] = 0x80; // OS bit - if (!fDiffMode) writeBuf[1] |= 0x40; // single ended mode channels - writeBuf[1] |= (channel & 0x03) << 4; // channel select - writeBuf[1] |= 0x01; // single shot mode - writeBuf[1] |= ((uint8_t)fPga[channel]) << 1; // PGA gain select - - // This sets the 8 LSBs of the config register (bits 7-0) -// writeBuf[2] = 0x03; // disable ALERT/RDY pin - writeBuf[2] = 0x00; // enable ALERT/RDY pin - writeBuf[2] |= ((uint8_t)fDataRate) << 5; - - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this begins a single conversion - write(writeBuf, 3); - - // Wait for the conversion to complete, this requires bit 15 to change from 0->1 - int nloops = 0; - while ((readBuf[0] & 0x80) == 0 && nloops*fReadWaitDelay / 1000 < 1000) // readBuf[0] contains 8 MSBs of config register, AND with 10000000 to select bit 15 - { - usleep(fReadWaitDelay); - read(readBuf, 2); // Read the config register into readBuf - nloops++; - } - if (nloops*fReadWaitDelay / 1000 >= 1000) { - if (fDebugLevel > 1) - printf("timeout!\n"); - return -32767; - } - if (fDebugLevel > 2) - printf(" nr of busy adc loops: %d \n", nloops); - if (nloops > 1) { - fReadWaitDelay += (nloops - 1)*fReadWaitDelay / 10; - if (fDebugLevel > 1) { - printf(" read wait delay: %6.2f ms\n", fReadWaitDelay / 1000.); - } - } - // else if (nloops==2) { - // fReadWaitDelay*=2.1; - // } - //else fReadWaitDelay--; - - // Set pointer register to 0 to read from the conversion register - readReg(0x00, readBuf, 2); // Read the contents of the conversion register into readBuf - - val = readBuf[0] << 8 | readBuf[1]; // Combine the two bytes of readBuf into a single 16 bit result - fLastADCValue = val; - - stopTimer(); - fLastConvTime = fLastTimeInterval; - - return val; -} - -bool ADS1115::setLowThreshold(int16_t thr) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - startTimer(); - - // These three bytes are written to the ADS1115 to set the Lo_thresh register - writeBuf[0] = 0x02; // This sets the pointer register to Lo_thresh register - writeBuf[1] = (thr & 0xff00)>>8; - writeBuf[2] |= (thr & 0x00ff); - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this sets the Lo_thresh register - int n=write(writeBuf, 3); - if (n!=3) return false; - n=read(readBuf, 2); // Read the same register into readBuf for verification - if (n!=2) return false; - - if ((readBuf[0]!=writeBuf[1]) || (readBuf[1]!=writeBuf[2])) return false; - stopTimer(); - return true; -} - -bool ADS1115::setHighThreshold(int16_t thr) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - startTimer(); - - // These three bytes are written to the ADS1115 to set the Hi_thresh register - writeBuf[0] = 0x03; // This sets the pointer register to Hi_thresh register - writeBuf[1] = (thr & 0xff00)>>8; - writeBuf[2] |= (thr & 0x00ff); - - // Initialize the buffer used to read data from the ADS1115 to 0 - readBuf[0] = 0; - readBuf[1] = 0; - - // Write writeBuf to the ADS1115, the 3 specifies the number of bytes we are writing, - // this sets the Hi_thresh register - int n=write(writeBuf, 3); - if (n!=3) return false; - - n=read(readBuf, 2); // Read the same register into readBuf for verification - if (n!=2) return false; - - if ((readBuf[0]!=writeBuf[1]) || (readBuf[1]!=writeBuf[2])) return false; - stopTimer(); - return true; -} - -bool ADS1115::setDataReadyPinMode() -{ - // c.f. datasheet, par. 9.3.8, p. 19 - // set MSB of Lo_thresh reg to 0 - // set MSB of Hi_thresh reg to 1 - // set COMP_QUE[1:0] to any value other than '11' (default value) - bool ok = setLowThreshold(0b00000000); - ok = ok && setHighThreshold(0b11111111); - return ok; -} - -bool ADS1115::devicePresent() -{ - uint8_t buf[2]; - return (read(buf, 2)==2); // Read the currently selected register into readBuf -} - -double ADS1115::readVoltage(unsigned int channel) -{ - double voltage = 0.; - readVoltage(channel, voltage); - return voltage; -} - -void ADS1115::readVoltage(unsigned int channel, double& voltage) -{ - int16_t adc = 0; - readVoltage(channel, adc, voltage); -} - -void ADS1115::readVoltage(unsigned int channel, int16_t& adc, double& voltage) -{ - adc = readADC(channel); - voltage = PGAGAINS[fPga[channel]] * adc / 32767.0; - - if (fAGC) { - int eadc = abs(adc); - if (eadc > 0.8 * 32767 && (unsigned int)fPga[channel] > 0) { - fPga[channel] = CFG_PGA((unsigned int)fPga[channel] - 1); - if (fDebugLevel > 1) - printf("ADC input high...setting PGA to level %d\n", fPga[channel]); - } - else if (eadc < 0.2 * 32767 && (unsigned int)fPga[channel] < 5) { - fPga[channel] = CFG_PGA((unsigned int)fPga[channel] + 1); - if (fDebugLevel > 1) - printf("ADC input low...setting PGA to level %d\n", fPga[channel]); - - } - } - fLastVoltage = voltage; - return; -} - - -/* - * MCP4728 4 ch 12 bit DAC - */ -bool MCP4728::setVoltage(uint8_t channel, float voltage, bool toEEPROM) { - // Vout = (2.048V * Dn) / 4096 * Gx <= VDD - if (voltage < 0) { - return false; - } - uint8_t gain = 0; - unsigned int value = (int)(voltage * 2000 + 0.5); - if (value > 0xfff) { - value = value >> 1; - gain = 1; - } - if (value > 0xfff) { - // error message - return false; - } - return setValue(channel, value, gain, toEEPROM); -} - -bool MCP4728::setValue(uint8_t channel, uint16_t value, uint8_t gain, bool toEEPROM) { - if (value > 0xfff) { - value = 0xfff; - // error number of bits exceeding 12 - return false; - } - startTimer(); - channel = channel & 0x03; - uint8_t buf[3]; - if (toEEPROM) { - buf[0] = 0b01011001; - } - else { - buf[0] = 0b01000001; - } - buf[0] = buf[0] | (channel << 1); // 01000/01011 (multiwrite/singlewrite command) DAC1 DAC0 (channel) UDAC bit =1 - buf[1] = 0b10000000 | (uint8_t)((value & 0xf00) >> 8); // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 - buf[1] = buf[1] | (gain << 4); - buf[2] = (uint8_t)(value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 - if (write(buf, 3) != 3) { - // somehow did not write exact same amount of bytes as it should - return false; - } - stopTimer(); - fLastConvTime = fLastTimeInterval; - return true; -} - -bool MCP4728::setChannel(uint8_t channel, const DacChannel& channelData) -{ - if (channelData.value > 0xfff) { - //channelData.value = 0xfff; - // error number of bits exceeding 12 - return false; - } - startTimer(); - channel = channel & 0x03; - uint8_t buf[3]; - if (channelData.eeprom) { - buf[0] = 0b01011001; - } - else { - buf[0] = 0b01000001; - } - buf[0] |= (channel << 1); // 01000/01011 (multiwrite/singlewrite command) DAC1 DAC0 (channel) UDAC bit =1 - buf[1] = ((uint8_t)channelData.vref) << 7; // Vref PD1 PD0 Gx (gain) D11 D10 D9 D8 - buf[1] |= (channelData.pd & 0x03) << 5; - buf[1] |= (uint8_t)((channelData.value & 0xf00) >> 8); - buf[1] |= (uint8_t)(channelData.gain & 0x01) << 4; - buf[2] = (uint8_t)(channelData.value & 0xff); // D7 D6 D5 D4 D3 D2 D1 D0 - if (write(buf, 3) != 3) { - // somehow did not write exact same amount of bytes as it should - return false; - } - stopTimer(); - return true; -} - -bool MCP4728::devicePresent() -{ - uint8_t buf[24]; - startTimer(); - // perform a read sequence of all registers as described in datasheet - int n=read(buf, 24); - stopTimer(); - return (n==24); - -} - -bool MCP4728::readChannel(uint8_t channel, DacChannel& channelData) -{ - if (channel > 3) { - // error: channel index exceeding 3 - return false; - } - - startTimer(); - - uint8_t buf[24]; - if (read(buf, 24) != 24) { - // somehow did not read exact same amount of bytes as it should - stopTimer(); - return false; - } - uint8_t offs=(channelData.eeprom==false)?1:4; - channelData.vref=(buf[channel*6+offs]&0x80)?VREF_2V:VREF_VDD; - channelData.pd=(buf[channel*6+offs]&0x60)>>5; - channelData.gain=(buf[channel*6+offs]&0x10)?GAIN2:GAIN1; - channelData.value=(uint16_t)(buf[channel*6+offs]&0x0f)<<8; - channelData.value|=(uint16_t)(buf[channel*6+offs+1]&0xff); - - stopTimer(); - - return true; -} - -float MCP4728::code2voltage(const DacChannel& channelData) -{ - float vref = (channelData.vref == VREF_2V)?2.048:VDD; - float voltage = vref*channelData.value/4096; - if (channelData.gain==GAIN2 && channelData.vref != VREF_VDD) voltage*=2.; - return voltage; -} - -/* - * PCA9536 4 pin I/O expander - */ -bool PCA9536::setOutputPorts(uint8_t portMask) { - unsigned char data = ~portMask; - startTimer(); - if (1 != writeReg(CONFIG_REG, &data, 1)) { - return false; - } - stopTimer(); - return true; -} - -bool PCA9536::setOutputState(uint8_t portMask) { - startTimer(); - if (1 != writeReg(OUTPUT_REG, &portMask, 1)) { - return false; - } - stopTimer(); - return true; -} - -uint8_t PCA9536::getInputState() { - uint8_t inport=0x00; - startTimer(); - readReg(INPUT_REG, &inport, 1); - stopTimer(); - return inport & 0x0f; -} - -bool PCA9536::devicePresent() { - uint8_t inport=0x00; - // read input port - return (1==readReg(INPUT_REG, &inport, 1)); -} - -/* - * LM75 Temperature Sensor - */ - -int16_t LM75::readRaw() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - - startTimer(); - - readBuf[0] = 0; - readBuf[1] = 0; - - read(readBuf, 2); // Read the config register into readBuf - - //int8_t temperature0 = (int8_t)readBuf[0]; - - // We extract the first bit and right shift 7 seven bit positions. - // Why? Because we don't care about the bits 6,5,4,3,2,1 and 0. -// int8_t temperature1 = (readBuf[1] & 0x80) >> 7; // is either zero or one -// int8_t temperature1 = (readBuf[1] & 0xf8) >> 3; - //int8_t temperature1 = (readBuf[1] & 0xff); - - //val = (temperature0 << 8) | temperature1; - //val = readBuf[0] << 1 | (readBuf[1] >> 7); // Combine the two bytes of readBuf into a single 16 bit result - val=((int16_t)readBuf[0] << 8) | readBuf[1]; - fLastRawValue = val; - - stopTimer(); - - return val; -} - -bool LM75::devicePresent() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - readBuf[0] = 0; - readBuf[1] = 0; - int n=read(readBuf, 2); // Read the data register into readBuf - return (n==2); -} - -double LM75::getTemperature() -{ - return (double)readRaw() / 256.; -} - - -/* - * X9119 - */ - -unsigned int X9119::readWiperReg() -{ - - // just return the locally stored last value written to WCR - // since readback doesn't work without repeated start transaction - return fWiperReg; - - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80; // op-code read WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - /*int n=*/read(readBuf, 2); // Read the config register into readBuf - // printf( "%d bytes read\n",n); - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; -} - -unsigned int X9119::readDataReg(uint8_t reg) -{ - - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80 | 0x20 | (reg & 0x03) << 2; // op-code read data reg - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - /*int n=*/read(readBuf, 2); // Read the config register into readBuf - // printf( "%d bytes read\n",n); - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - -} - - -unsigned int X9119::readWiperReg2() -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - uint8_t readBuf[16]; // 2 byte buffer to store the data read from the I2C device - int16_t val; // Stores the 16 bit value of our ADC conversion - - writeBuf[0] = 0x80; // op-code read WCR - - - struct i2c_msg rdwr_msgs[2]; - - rdwr_msgs[0].addr = fAddress; - rdwr_msgs[0].flags = 0; - rdwr_msgs[0].len = 1; - rdwr_msgs[0].buf = (char*)writeBuf; - - rdwr_msgs[1].addr = fAddress; - rdwr_msgs[1].flags = I2C_M_RD; - rdwr_msgs[1].len = 2; - rdwr_msgs[1].buf = (char*)readBuf; - - /* - = { - { - .addr = fAddress, - .flags = 0, // write - .len = 1, - .buf = writeBuf - }, - { // Read buffer - .addr = fAddress, - .flags = I2C_M_RD, // read - .len = 2, - .buf = readBuf - } - };*/ - - struct i2c_rdwr_ioctl_data rdwr_data; - - rdwr_data.msgs = rdwr_msgs; - rdwr_data.nmsgs = 2; - - // = { - // .msgs = rdwr_msgs, - // .nmsgs = 2 - // }; - - - //::close(fHandle); - //fHandle = ::open( "/dev/i2c-1", O_RDWR ); - - int result = ioctl(fHandle, I2C_RDWR, &rdwr_data); - - if (result < 0) { - printf("rdwr ioctl error: %d\n", errno); - perror("reason"); - } - else { - printf("rdwr ioctl OK\n"); - // for ( i = 0; i < 16; ++i ) { - // printf( "%c", buffer[i] ); - // } - // printf( "\n" ); - } - - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - - - writeBuf[0] = 0x80; // op-code read WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - - read(readBuf, 2); // Read the config register into readBuf - - val = (readBuf[0] & 0x03) << 8 | readBuf[1]; - - return val; - -} - -unsigned int X9119::readWiperReg3() -{ - - union i2c_smbus_data data; - struct i2c_smbus_ioctl_data args; - - args.read_write = I2C_SMBUS_READ; - args.command = 0x80; - args.size = I2C_SMBUS_WORD_DATA; - args.data = &data; - int result = ioctl(fHandle, I2C_SMBUS, &args); - if (result < 0) { - printf("rdwr ioctl error: %d\n", errno); - perror("reason"); - return 0; - } - else { - printf("rdwr ioctl OK\n"); - // for ( i = 0; i < 16; ++i ) { - // printf( "%c", buffer[i] ); - // } - // printf( "\n" ); - } - return 0x0FFFF & data.word; -} - - - -void X9119::writeWiperReg(unsigned int value) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - writeBuf[0] = 0x80 | 0x20; // op-code write WCR - writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR - writeBuf[2] = (value & 0xff); // LSB of WCR - - // Write writeBuf to the X9119 - // this sets the write address for WCR register and writes WCR - int n = write(writeBuf, 3); - //printf( "%d bytes written\n",n); - if (n == 3) fWiperReg = value; - -} - -void X9119::writeDataReg(uint8_t reg, unsigned int value) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - writeBuf[0] = 0x80 | 0x40 | (reg & 0x03) << 2; // op-code write data reg - writeBuf[1] = ((value & 0xff00) >> 8); // MSB of WCR - writeBuf[2] = (value & 0xff); // LSB of WCR - - // Write writeBuf to the X9119 - // this sets the write address for data register and writes dr with value - /*int n=*/write(writeBuf, 3); - // printf( "%d bytes written\n",n); - -} - - - - -/* - * 24AA02 EEPROM - */ -uint8_t EEPROM24AA02::readByte(uint8_t addr) -{ - uint8_t val = 0; - startTimer(); - /*int n=*/readReg(addr, &val, 1); // Read the data at address location - // printf( "%d bytes read\n",n); - stopTimer(); - return val; -} - -bool EEPROM24AA02::readByte(uint8_t addr, uint8_t* value) -{ - startTimer(); - int n=readReg(addr, value, 1); // Read the data at address location - // printf( "%d bytes read\n",n); - stopTimer(); - return (n==1); -} - -/* -bool EEPROM24AA02::devicePresent() -{ - uint8_t dummy; - return readByte(0,&dummy); -} -*/ - -void EEPROM24AA02::writeByte(uint8_t addr, uint8_t data) -{ - uint8_t writeBuf[2]; // Buffer to store the 2 bytes that we write to the I2C device - - writeBuf[0] = addr; // address of data byte - writeBuf[1] = data; // data byte - - startTimer(); - - // Write address first - write(writeBuf, 2); - - usleep(5000); - stopTimer(); -} - -/** Write multiple bytes to starting from given address into EEPROM memory. - * @param addr First register address to write to - * @param length Number of bytes to write - * @param data Buffer to copy new data from - * @return Status of operation (true = success) - * @note this is an overloaded function to the one from the i2cdevice base class in order to - * prevent sequential write operations crossing page boundaries of the EEPROM. This function conforms to - * the page-wise sequential write (c.f. http://ww1.microchip.com/downloads/en/devicedoc/21709c.pdf p.7). - */ -bool EEPROM24AA02::writeBytes(uint8_t addr, uint16_t length, uint8_t* data) { - - static const uint8_t PAGESIZE=8; - bool success = true; - startTimer(); - for (uint16_t i=0; i=length) pageRemainder = length-currAddr; - int n = writeReg(currAddr, &data[i], pageRemainder); - usleep(5000); - i+=pageRemainder; - success = success && (n==pageRemainder); - } - stopTimer(); - return success; -} - - - -/* -* SHT21 Temperature&Humidity Sensor -* Prefered option is the no hold mastermode -*/ - - -bool SHT21::checksumCorrect(uint8_t data[]) // expects data to be greater or equal 3 (expecting 3) -{ - const uint16_t Polynom = 0x131; - uint8_t crc = 0; - uint8_t byteCtr; - uint8_t bit; - try { - for (byteCtr = 0; byteCtr < 2; ++byteCtr) - { - crc ^= (data[byteCtr]); - for (bit = 8; bit > 0; --bit) - { - if (crc & 0x80) - { - crc = (crc << 1) ^ Polynom; - } - else - { - crc = (crc << 1); - } - } - } - if (crc != data[2]) - { - return false; - } - else - { - return true; - } - } - catch (int i) { - printf("Error, Array too small in function: checksumCorrect\n"); - return false; - } -} - -float SHT21::getHumidity() -{ - uint16_t data_hum = readUH(); - float fhum; //end calculation -> Humidity - fhum = -6.0 + 125.0 * (((float)(data_hum)) / 65536.0); - return (fhum); -} - -float SHT21::getTemperature() -{ - uint16_t data_temp = readUT(); - float ftemp; //endl calculation -> Temperature - ftemp = -46.85 + 175.72 * (((float)(data_temp)) / 65536.0); - return (ftemp); -} - - -uint16_t SHT21::readUT() // von unsigned int auf float geändert -{ - uint8_t writeBuf[1]; - uint8_t readBuf[3]; - uint16_t data_temp; - - writeBuf[0] = 0; - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - data_temp = 0; - - writeReg(0xF3, writeBuf, 0); - usleep(85000); - while (read(readBuf, 3) != 3); - - if (fDebugLevel > 1) - { - printf("Inhalt: (MSB Byte): %x\n", readBuf[0]); - printf("Inhalt: (LSB Byte): %x\n", readBuf[1]); - printf("Inhalt: (Checksum Byte): %x\n", readBuf[2]); - } - - data_temp = ((uint16_t)readBuf[0]) << 8; - data_temp |= readBuf[1]; - data_temp &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. - - if (!checksumCorrect(readBuf)) - { - printf("checksum error\n"); - } - return data_temp; -} - -uint16_t SHT21::readUH() //Hold mode -{ - uint8_t writeBuf[1]; - uint8_t readBuf[3]; //what should be read later - uint16_t data_hum; - - writeBuf[0] = 0; - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - data_hum = 0; - - writeReg(0xF5, writeBuf, 0); - usleep(30000); - while (read(readBuf, 3) != 3); - - - if (fDebugLevel>1) - { - printf("Es wurden gelesen (MSB Bytes): %x\n", readBuf[0]); - printf("Es wurden gelesen (LSB Bytes): %x\n", readBuf[1]); - printf("Es wurden gelesen (Checksum Bytes): %x\n", readBuf[2]); - } - - data_hum = ((uint16_t)readBuf[0]) << 8; - data_hum |= readBuf[1]; - data_hum &= 0xFFFC; //Vergleich mit 0xFC um die letzten beiden Bits auf 00 zu setzen. - - if (!checksumCorrect(readBuf)) - { - printf("checksum error\n"); - } - return data_hum; -} - - - -uint8_t SHT21::readResolutionSettings() -{ //reads the temperature and humidity resolution settings byte - uint8_t readBuf[1]; - - readBuf[0] = 0; //Initialization - - readReg(0xE7, readBuf, 1); - return readBuf[0]; -} - -void SHT21::setResolutionSettings(uint8_t settingsByte) -{ //sets the temperature and humidity resolution settings byte - uint8_t readBuf[1]; - readBuf[0] = 0; //Initialization - readReg(0xE7, readBuf, 1); - readBuf[0] &= 0b00111000; // mask, to not change reserved bits (Bit 3, 4 and 5 are reserved) - settingsByte &= 0b11000111; - uint8_t writeBuf[1]; - writeBuf[0] = settingsByte | readBuf[0]; - writeReg(0xE6, writeBuf, 1); -} - - -bool SHT21::softReset() -{ - uint8_t writeBuf[1]; - writeBuf[0] = 0xFE; - - int n = 0; - n = writeReg(0xFE, writeBuf, 0); - usleep(15000); //wait for the SHT to reset; datasheet on page 9 - - if (n == 0) - { - printf("soft_reset succesfull %i\n", n); - } - - return(n == 0); //Wenn n == 0, gibt die Funktion True zurück. Wenn nicht gibt sie False zurück. - - -} - -/* - * BMP180 Pressure Sensor - */ - -bool BMP180::init() -{ - uint8_t val = 0; - - fCalibrationValid = false; - - // chip id reg - int n = readReg(0xd0, &val, 1); // Read the id register into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("chip id: 0x%x \n", val); - } - if (val == 0x55) readCalibParameters(); - return (val == 0x55); -} - - -unsigned int BMP180::readUT() -{ - uint8_t readBuf[2]; // 2 byte buffer to store the data read from the I2C device - unsigned int val; // Stores the 16 bit value of our ADC conversion - - // start temp measurement: CR -> 0x2e - uint8_t cr_val = 0x2e; - // register address control reg - int n = writeReg(0xf4, &cr_val, 1); - - // wait at least 4.5 ms - usleep(4500); - - readBuf[0] = 0; - readBuf[1] = 0; - - // adc reg - n = readReg(0xf6, readBuf, 2); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = (readBuf[0]) << 8 | readBuf[1]; - - return val; -} - -unsigned int BMP180::readUP(uint8_t oss) -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - unsigned int val; // Stores the 16 bit value of our ADC conversion - static const int delay[4] = { 4500, 7500, 13500, 25500 }; - - // start pressure measurement: CR -> 0x34 | oss<<6 - uint8_t cr_val = 0x34 | (oss & 0x03) << 6; - // register address control reg - int n = writeReg(0xf4, &cr_val, 1); - usleep(delay[oss & 0x03]); - - // writeBuf[0] = 0xf6; // adc reg - // write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - n = readReg(0xf6, readBuf, 3); // Read the conversion result into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = (readBuf[0] << 16 | readBuf[1] << 8 | readBuf[2]) >> (8 - (oss & 0x03)); - - return val; -} - -signed int BMP180::getCalibParameter(unsigned int param) const -{ - if (param < 11) return fCalibParameters[param]; - return 0xffff; -} - -void BMP180::readCalibParameters() -{ - uint8_t readBuf[22]; - // register address first byte eeprom - int n = readReg(0xaa, readBuf, 22); // Read the 11 eeprom word values into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - if (fDebugLevel > 1) - printf("BMP180 eeprom calib data:\n"); - - bool ok = true; - for (int i = 0; i < 11; i++) { - if (i > 2 && i < 6) - fCalibParameters[i] = (uint16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); - else - fCalibParameters[i] = (int16_t)(readBuf[2 * i] << 8 | readBuf[2 * i + 1]); - if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) ok = false; - if (fDebugLevel > 1) - // printf( "calib%d: 0x%4x \n",i,fCalibParameters[i]); - printf("calib%d: %d \n", i, fCalibParameters[i]); - } - if (fDebugLevel > 1) { - if (ok) - printf("calib data is valid.\n"); - else printf("calib data NOT valid!\n"); - } - - fCalibrationValid = ok; -} - -double BMP180::getTemperature() { - if (!fCalibrationValid) return -999.; - signed int UT = readUT(); - signed int X1 = ((UT - fCalibParameters[5])*fCalibParameters[4]) >> 15; - signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); - signed int B5 = X1 + X2; - double T = (B5 + 8) / 160.; - if (fDebugLevel > 1) { - printf("UT=%d\n", UT); - printf("X1=%d\n", X1); - printf("X2=%d\n", X2); - printf("B5=%d\n", B5); - printf("Temp=%f\n", T); - } - return T; -} - - -double BMP180::getPressure(uint8_t oss) { - if (!fCalibrationValid) return 0.; - signed int UT = readUT(); - if (fDebugLevel > 1) - printf("UT=%d\n", UT); - signed int UP = readUP(oss); - if (fDebugLevel > 1) - printf("UP=%d\n", UP); - signed int X1 = ((UT - fCalibParameters[5])*fCalibParameters[4]) >> 15; - signed int X2 = (fCalibParameters[9] << 11) / (X1 + fCalibParameters[10]); - signed int B5 = X1 + X2; - signed int B6 = B5 - 4000; - if (fDebugLevel > 1) - printf("B6=%d\n", B6); - X1 = (fCalibParameters[7] * ((B6*B6) >> 12)) >> 11; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (fCalibParameters[1] * B6) >> 11; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - signed int X3 = X1 + X2; - signed int B3 = ((fCalibParameters[0] * 4 + X3) << (oss & 0x03)) + 2; - B3 = B3 / 4; - if (fDebugLevel > 1) - printf("B3=%d\n", B3); - X1 = (fCalibParameters[2] * B6) >> 13; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (fCalibParameters[6] * (B6*B6) / 4096); - X2 = X2 >> 16; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - X3 = (X1 + X2 + 2) / 4; - if (fDebugLevel > 1) - printf("X3=%d\n", X3); - unsigned long B4 = (fCalibParameters[3] * (unsigned long)(X3 + 32768)) >> 15; - if (fDebugLevel > 1) - printf("B4=%ld\n", B4); - unsigned long B7 = ((unsigned long)UP - B3)*(50000 >> (oss & 0x03)); - if (fDebugLevel > 1) - printf("B7=%ld\n", B7); - int p = 0; - if (B7 < 0x80000000) p = (B7 * 2) / B4; - else p = (B7 / B4) * 2; - if (fDebugLevel > 1) - printf("p=%d\n", p); - - X1 = p >> 8; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X1 = X1 * X1; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X1 = (X1 * 3038) >> 16; - if (fDebugLevel > 1) - printf("X1=%d\n", X1); - X2 = (-7357 * p) >> 16; - if (fDebugLevel > 1) - printf("X2=%d\n", X2); - p = 16 * p + (X1 + X2 + 3791); - double press = p / 16.; - - if (fDebugLevel > 1) { - printf("pressure=%f\n", press); - } - return press; -} - -/* - *BME280 HumidityTemperaturePressuresensor - * -*/ -bool BME280::init() -{ - fTitle = "BME180"; - - uint8_t val = 0; - fCalibrationValid = false; - - // chip id reg - int n = readReg(0xd0, &val, 1); // Read the id register into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("chip id: 0x%x \n", val); - } - if (val == 0x60) readCalibParameters(); - return (val == 0x60); -} - -unsigned int BME280::status() { - uint8_t status[1]; - status[0] = 10; - int n = readReg(0xf3, status, 1); - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - status[0] &= 0b1001; - return (unsigned int)status[0]; -} - -unsigned int BME280::readConfig() { - uint8_t config[1]; - config[0] = 0; - int n = readReg(0xf5, config, 1); - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - return (unsigned int)config[0]; -} - -unsigned int BME280::read_CtrlMeasReg() { - uint8_t ctrl_meas[1]; - ctrl_meas[0] = 0; - int n = readReg(0xf4, ctrl_meas, 1); - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - return (unsigned int)ctrl_meas[0]; -} - -bool BME280::writeConfig(uint8_t config) { - uint8_t buf[1]; - // check for bit 1 because datasheet says: "do not change" - int n = readReg(0xf5, buf, 1); - buf[0] = buf[0] & 0b10; - config = config & 0b11111101; - buf[0] = buf[0] | config; - n += writeReg(0xf5, buf, 1); - if (fDebugLevel > 1) - printf("%d bytes written\n", n); - return (n == 2); -} - -bool BME280::write_CtrlMeasReg(uint8_t config) { - uint8_t buf[1]; - buf[0] = config; - int n = writeReg(0xf4, buf, 1); - if (fDebugLevel > 1) - printf("%d bytes written\n", n); - return (n == 1); -} - -bool BME280::setMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b11) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0xfc; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setTSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b00011111; - mode = mode << 5; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setPSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf4, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b11100011; - mode = mode << 2; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf4, buf, 1); - return (n == 2); -} - -bool BME280::setHSamplingMode(uint8_t mode) -{ // 0= skipped; oversampling: 1: x1; 2:x2; 3: x4; 4:x8; 5:x16 - if (mode > 0b111) { - if (fDebugLevel > 1) - printf("mode > 3 error\n"); - return false; - } - uint8_t buf[1]; - int n = readReg(0xf2, buf, 1); - uint8_t ctrl_meas = buf[0]; - ctrl_meas = ctrl_meas & 0b11111000; - ctrl_meas = ctrl_meas | mode; - buf[0] = ctrl_meas; - n += writeReg(0xf2, buf, 1); - return (n == 2); -} - -void BME280::measure() { - // calculate t_max [ms] from settings: - uint8_t readBuf[1]; - double t_max = 1.25; - readReg(0xf2, readBuf, 1); - unsigned int val = readBuf[0] & 0b111; - if (fDebugLevel > 1) - printf("osrs_h: %u\n", val); - if (val > 5) - val = 5; - unsigned int add = 1; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add + 0.575; - } - - readBuf[0] = 0; - add = 1; - readReg(0xf4, readBuf, 1); - val = readBuf[0] & 0b00011100; - val = val >> 2; - if (fDebugLevel > 1) - printf("osrs_p: %u\n", val); - if (val > 5) - val = 5; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add + 0.575; - } - - add = 1; - val = readBuf[0] & 0b11100000; - val = val >> 5; - if (fDebugLevel > 1) - printf("osrs_t: %u\n", val); - if (val > 5) - val = 5; - if (val != 0) { - add = add << (val - 1); - t_max += 2.3*(double)add; - } - // t_max corresponds to the maximum time that a measurement can take with given - // settings read out from registers f2 and f4 - - // wait while status not ready: - while (status() != 0) { - usleep(5000); - } - setMode(0x2); // set mode to "forced measurement" (single-shot) - // it will now perform a measurement as configured in 0xf4, 0xf2 and 0xf5 registers - - // wait at least 112.8 ms for a full accuracy measurement of all 3 values - // or ask for status to be 0 - usleep((int)(t_max * 1000 + 0.5) + 200); - if (fDebugLevel > 1) - printf("measurement took about %.1f ms\n", t_max + 0.2); - while (status() != 0) { - usleep(5000); - } - return; -} - -unsigned int BME280::readUT() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - uint32_t val; // Stores the 20 bit value of our ADC conversion - - measure(); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - int n = readReg(0xfa, readBuf, 3); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read: 0x%02x 0x%02x 0x%02x\n", n, readBuf[0], readBuf[1], readBuf[2]); - - val = ((uint32_t)readBuf[0]) << 12; // <-------///// should the lower 4 bits or the higher 4 bits of the 24 bits of registers be left 0 ??? - val |= ((uint32_t)readBuf[1]) << 4; // (look datasheet page 25) - val |= ((uint32_t)readBuf[2]) >> 4; - - return val; -} - -unsigned int BME280::readUP() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - uint32_t val; // Stores the 20 bit value of our ADC conversion - - measure(); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // adc reg - int n = readReg(0xf7, readBuf, 3); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = ((uint32_t)readBuf[0]) << 12; - val |= ((uint32_t)readBuf[1]) << 4; - val |= ((uint32_t)readBuf[2]) >> 4; - - return val; -} - -unsigned int BME280::readUH() -{ - uint8_t readBuf[2]; - uint16_t val; - - measure(); - readBuf[0] = 0; - readBuf[1] = 0; - - // adc reg - int n = readReg(0xfd, readBuf, 2); // Read the config register into readBuf - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - val = ((uint32_t)readBuf[0]) << 8; - val |= ((uint32_t)readBuf[1]); // (look datasheet page 25) - - return val; -} - -TPH BME280::readTPCU() -{ - uint8_t readBuf[8]; - for (int i = 0; i < 8; i++) { - readBuf[i] = 0; - } - measure(); - int n = readReg(0xf7, readBuf, 8); // read T, P and H registers; - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - uint32_t adc_P = ((uint32_t)readBuf[0]) << 12; - adc_P |= ((uint32_t)readBuf[1]) << 4; - adc_P |= ((uint32_t)readBuf[2]) >> 4; - uint32_t adc_T = ((uint32_t)readBuf[3]) << 12; - adc_T |= ((uint32_t)readBuf[4]) << 4; - adc_T |= ((uint32_t)readBuf[5]) >> 4; - uint32_t adc_H = ((uint32_t)readBuf[6]) << 8; - adc_H |= ((uint32_t)readBuf[7]); // (look datasheet page 25) - - TPH val; - val.adc_P = (int32_t)adc_P; - val.adc_T = (int32_t)adc_T; - val.adc_H = (int32_t)adc_H; - return val; -} - -bool BME280::softReset() { - uint8_t resetWord[1]; - resetWord[0] = 0xb6; - int val = writeReg(0xe0, resetWord, 1); - return(val == 1); -} - -signed int BME280::getCalibParameter(unsigned int param) const -{ - if (param < 11) return fCalibParameters[param]; - return 0xffff; -} - -void BME280::readCalibParameters() -{ - uint8_t readBuf[33]; - uint8_t readBufPart2[8]; - // register address first byte eeprom - int n = readReg(0x88, readBuf, 25); // Read the 26 eeprom word values into readBuf - n = n + readReg(0xe1, readBufPart2, 8); // from two different locations - for (int i = 0; i < 8; i++) { - readBuf[i + 25] = readBufPart2[i]; - } - if (fDebugLevel > 1) - printf("%d bytes read\n", n); - - if (fDebugLevel > 1) - printf("BME280 eeprom calib data:\n"); - - bool ok = true; - for (int i = 0; i < 12; i++) { - fCalibParameters[i] = ((uint16_t)readBuf[2 * i]) | (((uint16_t)readBuf[2 * i + 1]) << 8); // 2x 8-Bit ergibt 16-Bit Wort - //if (i == 0 || i == 3) - // fCalibParameters[i] = ((uint16_t)readBuf[2 * i]) | (((uint16_t)readBuf[2 * i + 1]) << 8); // 2x 8-Bit ergibt 16-Bit Wort - //else - // fCalibParameters[i] = ((int16_t)readBuf[2 * i]) | (((int16_t)readBuf[2 * i + 1]) << 8); - if (fCalibParameters[i] == 0 || fCalibParameters[i] == 0xffff) ok = false; - if (fDebugLevel > 1) - printf("calib%d: %d \n", i, fCalibParameters[i]); - } - fCalibParameters[12] = (uint16_t)readBuf[24]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 12, fCalibParameters[12]); - fCalibParameters[13] = ((uint16_t)readBuf[25]) | (((uint16_t)readBuf[26]) << 8); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 13, fCalibParameters[13]); - fCalibParameters[14] = (uint16_t)readBuf[27]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 14, fCalibParameters[14]); - fCalibParameters[15] = (((uint16_t)readBuf[28]) << 4) | (((uint16_t)readBuf[29]) & 0b1111); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 15, fCalibParameters[15]); - fCalibParameters[16] = (((uint16_t)readBuf[30] & 0xf0) >> 4) | (((uint16_t)readBuf[31]) << 4); - if (fDebugLevel > 1) - printf("calib%d: %d \n", 16, fCalibParameters[16]); - fCalibParameters[17] = (uint16_t)readBuf[32]; - if (fDebugLevel > 1) - printf("calib%d: %d \n", 17, fCalibParameters[17]); - - if (fDebugLevel > 1) { - if (ok) - printf("calib data is valid.\n"); - else printf("calib data NOT valid!\n"); - } - - fCalibrationValid = ok; -} - -TPH BME280::getTPHValues() { - TPH vals = readTPCU(); - vals.T = getTemperature(vals.adc_T); - vals.P = getPressure(vals.adc_P); - vals.H = getHumidity(vals.adc_H); - return vals; -} - -double BME280::getTemperature(signed int adc_T) { - adc_T = (int32_t)adc_T; - if (!fCalibrationValid) return -999.; - uint32_t dig_T1 = (uint32_t)fCalibParameters[0]; - int32_t dig_T2 = (int32_t)((int16_t)fCalibParameters[1]); - int32_t dig_T3 = (int32_t)((int16_t)fCalibParameters[2]); - int32_t X1 = (((adc_T >> 3) - (((int32_t)dig_T1) << 1))*((int32_t)dig_T2)) >> 11; - int32_t X2 = (((((adc_T >> 4) - ((int32_t)dig_T1))*((adc_T >> 4) - ((int32_t)dig_T1))) >> 12)*((int32_t)dig_T3)) >> 14; - fT_fine = X1 + X2; - int32_t t = (fT_fine * 5 + 128) >> 8; - double T = t / 100.0; - if (fDebugLevel > 1) { - printf("adc_T=%d\n", adc_T); - printf("X1=%d\n", X1); - printf("X2=%d\n", X2); - printf("t_fine=%d\n", fT_fine); - printf("temp=%d\n", t); - } - return T; -} - -double BME280::getHumidity(signed int adc_H) { // please only do this if "getTemperature()" has been executed before - return getHumidity(adc_H, fT_fine); -} -double BME280::getHumidity(signed int adc_H, signed int t_fine) { - adc_H = (int32_t)adc_H; - if (!fCalibrationValid) return -999.; - if (t_fine == 0) return -999.; - uint32_t dig_H1 = (uint32_t)fCalibParameters[12]; - int32_t dig_H2 = (int32_t)((int16_t)fCalibParameters[13]); - uint32_t dig_H3 = (uint32_t)fCalibParameters[14]; - int32_t dig_H4 = (int32_t)((int16_t)fCalibParameters[15]); - int32_t dig_H5 = (int32_t)((int16_t)fCalibParameters[16]); - int32_t dig_H6 = (int32_t)((int8_t)((uint8_t)fCalibParameters[17])); - int32_t X1 = 0; - X1 = (t_fine - (76800)); - X1 = (((((adc_H << 14) - (((int32_t)dig_H4) << 20) - (((int32_t)dig_H5)* X1)) + - (16384)) >> 15) * (((((((X1 * ((int32_t)dig_H6)) >> 10) * (((X1 * - ((int32_t)dig_H3)) >> 11) + (32768))) >> 10) + (2097152)) * - ((int32_t)dig_H2) + 8192) >> 14)); - X1 = (X1 - (((((X1 >> 15) * (X1 >> 15)) >> 7) * ((int32_t)dig_H1)) >> 4)); - X1 = (X1 < 0 ? 0 : X1); - X1 = (X1 > 419430400 ? 419430400 : X1); - unsigned int h = (uint32_t)(X1 >> 12); - double H = h / 1024.0; - if (fDebugLevel > 1) { - printf("adc_H=%d\n", adc_H); - printf("X1=%d\n", X1); - printf("t_fine=%d\n", t_fine); - printf("Humidity=%u\n", h); - } - return H; -} - -double BME280::getPressure(signed int adc_P) { - return getPressure(adc_P, fT_fine); -} -double BME280::getPressure(signed int adc_P, signed int t_fine) { - if (!fCalibrationValid) return -999.0; - if (fT_fine == 0) return -999.0; - uint32_t dig_P1 = (uint32_t)fCalibParameters[3]; - int32_t dig_P2 = (int32_t)((int16_t)fCalibParameters[4]); - int32_t dig_P3 = (int32_t)((int16_t)fCalibParameters[5]); - int32_t dig_P4 = (int32_t)((int16_t)fCalibParameters[6]); - int32_t dig_P5 = (int32_t)((int16_t)fCalibParameters[7]); - int32_t dig_P6 = (int32_t)((int16_t)fCalibParameters[8]); - int32_t dig_P7 = (int32_t)((int16_t)fCalibParameters[9]); - int32_t dig_P8 = (int32_t)((int16_t)fCalibParameters[10]); - int32_t dig_P9 = (int32_t)((int16_t)fCalibParameters[11]); - - int64_t X1, X2, p; - X1 = ((int64_t)t_fine) - 128000; - X2 = X1 * X1 * (int64_t)dig_P6; - X2 = X2 + ((X1*(int64_t)dig_P5) << 17); - X2 = X2 + (((int64_t)dig_P4) << 35); - X1 = ((X1 * X1 * (int64_t)dig_P3) >> 8) + ((X1 * (int64_t)dig_P2) << 12); - X1 = (((((int64_t)1) << 47) + X1))*((int64_t)dig_P1) >> 33; - if (X1 == 0) - { - return 0; // avoid exception caused by division by zero - } - p = 1048576 - adc_P; - p = (((p << 31) - X2) * 3125) / X1; - X1 = (((int64_t)dig_P9) * (p >> 13) * (p >> 13)) >> 25; - X2 = (((int64_t)dig_P8) * p) >> 19; - p = ((p + X1 + X2) >> 8) + (((int64_t)dig_P7) << 4); - - double P = ((uint32_t)p) / 256.; - if (fDebugLevel > 1) { - printf("adc_P=%d\n", adc_P); - printf("X1=%lld\n", X1); - printf("X2=%lld\n", X2); - printf("p=%lld\n", p); - printf("P=%.3f\n", P); - } - return P; -} - -/* - * HMC5883 3 axis magnetic field sensor (Honeywell) - */ -bool HMC5883::init() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // init value 0 for gain - fGain = 0; - - // writeBuf[0] = 0x0a; // chip id reg A - // write(writeBuf, 1); - - readBuf[0] = 0; - readBuf[1] = 0; - readBuf[2] = 0; - - // int n=read(readBuf, 3); // Read the id registers into readBuf - // chip id reg A: 0x0a - int n = readReg(0x0a, readBuf, 3); // Read the id registers into readBuf - // printf( "%d bytes read\n",n); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("id reg A: 0x%x \n", readBuf[0]); - printf("id reg B: 0x%x \n", readBuf[1]); - printf("id reg C: 0x%x \n", readBuf[2]); - } - - if (readBuf[0] != 0x48) return false; - - // set CRA - // writeBuf[0] = 0x00; // addr config reg A (CRA) - // writeBuf[1] = 0x70; // 8 average, 15 Hz, single measurement - - // addr config reg A (CRA) - // 8 average, 15 Hz, single measurement: 0x70 - uint8_t cmd = 0x70; - n = writeReg(0x00, &cmd, 1); - - setGain(fGain); - return true; -} - -void HMC5883::setGain(uint8_t gain) -{ - uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device - - // set CRB - writeBuf[0] = 0x01; // addr config reg B (CRB) - writeBuf[1] = (gain & 0x07) << 5; // gain=xx - write(writeBuf, 2); - fGain = gain & 0x07; -} - -// uint8_t HMC5883::readGain() -// { -// uint8_t writeBuf[3]; // Buffer to store the 3 bytes that we write to the I2C device -// uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device -// -// // set CRB -// writeBuf[0] = 0x01; // addr config reg B (CRB) -// write(writeBuf, 1); -// -// int n=read(readBuf, 1); // Read the config register into readBuf -// -// if (n!=1) return 0; -// uint8_t gain = readBuf[0]>>5; -// if (fDebugLevel>1) -// { -// printf( "%d bytes read\n",n); -// printf( "gain (read from device): 0x%x\n",gain); -// } -// //fGain = gain & 0x07; -// return gain; -// } - -uint8_t HMC5883::readGain() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - int n = readReg(0x01, readBuf, 1); // Read the config register into readBuf - - if (n != 1) return 0; - uint8_t gain = readBuf[0] >> 5; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("gain (read from device): 0x%x\n", gain); - } - //fGain = gain & 0x07; - return gain; -} - -bool HMC5883::readRDYBit() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // addr status reg (SR) - int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf - - if (n != 1) return 0; - uint8_t sr = readBuf[0]; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("status (read from device): 0x%x\n", sr); - } - if ((sr & 0x01) == 0x01) return true; - return false; -} - -bool HMC5883::readLockBit() -{ - uint8_t readBuf[3]; // 2 byte buffer to store the data read from the I2C device - - // addr status reg (SR) - int n = readReg(0x09, readBuf, 1); // Read the status register into readBuf - - if (n != 1) return 0; - uint8_t sr = readBuf[0]; - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - printf("status (read from device): 0x%x\n", sr); - } - if ((sr & 0x02) == 0x02) return true; - return false; -} - -bool HMC5883::getXYZRawValues(int &x, int &y, int &z) -{ - uint8_t readBuf[6]; - - uint8_t cmd = 0x01; // start single measurement - int n = writeReg(0x02, &cmd, 1); // addr mode reg (MR) - usleep(6000); - - // Read the 3 data registers into readBuf starting from addr 0x03 - n = readReg(0x03, readBuf, 6); - int16_t xreg = (int16_t)(readBuf[0] << 8 | readBuf[1]); - int16_t yreg = (int16_t)(readBuf[2] << 8 | readBuf[3]); - int16_t zreg = (int16_t)(readBuf[4] << 8 | readBuf[5]); - - if (fDebugLevel > 1) - { - printf("%d bytes read\n", n); - // printf( "xreg: %2x %2x %d\n",readBuf[0], readBuf[1], xreg); - printf("xreg: %d\n", xreg); - printf("yreg: %d\n", yreg); - printf("zreg: %d\n", zreg); - - - } - - x = xreg; y = yreg; z = zreg; - - if (xreg >= -2048 && xreg < 2048 && - yreg >= -2048 && yreg < 2048 && - zreg >= -2048 && zreg < 2048) - return true; - - return false; -} - - -bool HMC5883::getXYZMagneticFields(double &x, double &y, double &z) -{ - int xreg, yreg, zreg; - bool ok = getXYZRawValues(xreg, yreg, zreg); - double lsbgain = GAIN[fGain]; - x = lsbgain * xreg / 1000.; - y = lsbgain * yreg / 1000.; - z = lsbgain * zreg / 1000.; - - if (fDebugLevel > 1) - { - printf("x field: %f G\n", x); - printf("y field: %f G\n", y); - printf("z field: %f G\n", z); - } - - return ok; -} - -bool HMC5883::calibrate(int &x, int &y, int &z) -{ - - // addr config reg A (CRA) - // 8 average, 15 Hz, positive self test measurement: 0x71 - uint8_t cmd = 0x71; - /*int n=*/writeReg(0x00, &cmd, 1); - - uint8_t oldGain = fGain; - setGain(5); - - int xr, yr, zr; - // one dummy measurement - getXYZRawValues(xr, yr, zr); - // measurement - getXYZRawValues(xr, yr, zr); - - x = xr; y = yr; z = zr; - - setGain(oldGain); - // one dummy measurement - getXYZRawValues(xr, yr, zr); - - - // set normal measurement mode in CRA again - cmd = 0x70; - /*n=*/writeReg(0x00, &cmd, 1); - return true; -} - - -/* Ublox GPS receiver, I2C interface */ -bool UbloxI2c::devicePresent() -{ - uint8_t dummy; - return (1==readReg(0xff, &dummy, 1)); -// return getTxBufCount(dummy); -} - -std::string UbloxI2c::getData() -{ - uint16_t nrBytes = 0; - if (!getTxBufCount(nrBytes)) return ""; - if (nrBytes==0) return ""; - uint8_t reg=0xff; - int n=write(®, 1); - if (n!=1) return ""; - uint8_t buf[128]; - if (nrBytes>128) nrBytes=128; - n = read(buf, nrBytes); - if (n!=nrBytes) return ""; - std::string str(nrBytes, ' '); - std::transform(&buf[0], &buf[nrBytes], str.begin(), [](uint8_t c) { return (unsigned char)c; } ); - return str; -// std::copy(buf[0], buf[nrBytes-1], std::back_inserter(str)); -} - -bool UbloxI2c::getTxBufCount(uint16_t& nrBytes) -{ - startTimer(); - uint8_t reg=0xfd; - uint8_t buf[2]; - int n=write(®, 1); - if (n!=1) return false; - n=read(buf, 2); // Read the data at TX buf counter location - stopTimer(); - if (n!=2) return false; - uint16_t temp = buf[1]; - temp |= (uint16_t)buf[0]<<8; - nrBytes = temp; - return true; -} - - - -/********************************************************************* -This is a library for our Monochrome OLEDs based on SSD1306 drivers - - Pick one up today in the adafruit shop! - ------> http://www.adafruit.com/category/63_98 - -These displays use SPI to communicate, 4 or 5 pins are required to -interface - -Adafruit invests time and resources providing this open source code, -please support Adafruit and open-source hardware by purchasing -products from Adafruit! - -Written by Limor Fried/Ladyada for Adafruit Industries. -BSD license, check license.txt for more information -All text above, and the splash screen below must be included in any redistribution - -02/18/2013 Charles-Henri Hallard (http://hallard.me) - Modified for compiling and use on Raspberry ArduiPi Board - LCD size and connection are now passed as arguments on - the command line (no more #define on compilation needed) - ArduiPi project documentation http://hallard.me/arduipi -07/01/2013 Charles-Henri Hallard - Reduced code size removed the Adafruit Logo (sorry guys) - Buffer for OLED is now dynamic to LCD size - Added support of Seeed OLED 64x64 Display - -*********************************************************************/ - -//#include "./ArduiPi_SSD1306.h" -//#include "./Adafruit_GFX.h" -//#include "./Adafruit_SSD1306.h" - -/*========================================================================= - SSDxxxx Common Displays - ----------------------------------------------------------------------- - Common values to all displays -=========================================================================*/ - -//#define SSD_Command_Mode 0x80 /* DC bit is 0 */ Seeed set C0 to 1 why ? -#define SSD_Command_Mode 0x00 /* C0 and DC bit are 0 */ -#define SSD_Data_Mode 0x40 /* C0 bit is 0 and DC bit is 1 */ - -#define SSD_Inverse_Display 0xA7 - -#define SSD_Display_Off 0xAE -#define SSD_Display_On 0xAF - -#define SSD_Set_ContrastLevel 0x81 - -#define SSD_External_Vcc 0x01 -#define SSD_Internal_Vcc 0x02 - - -#define SSD_Activate_Scroll 0x2F -#define SSD_Deactivate_Scroll 0x2E - -#define Scroll_Left 0x00 -#define Scroll_Right 0x01 - -#define Scroll_2Frames 0x07 -#define Scroll_3Frames 0x04 -#define Scroll_4Frames 0x05 -#define Scroll_5Frames 0x00 -#define Scroll_25Frames 0x06 -#define Scroll_64Frames 0x01 -#define Scroll_128Frames 0x02 -#define Scroll_256Frames 0x03 - -#define VERTICAL_MODE 01 -#define PAGE_MODE 01 -#define HORIZONTAL_MODE 02 - - -/*========================================================================= - SSD1306 Displays - ----------------------------------------------------------------------- - The driver is used in multiple displays (128x64, 128x32, etc.). -=========================================================================*/ -#define SSD1306_DISPLAYALLON_RESUME 0xA4 -#define SSD1306_DISPLAYALLON 0xA5 - -#define SSD1306_Normal_Display 0xA6 - -#define SSD1306_SETDISPLAYOFFSET 0xD3 -#define SSD1306_SETCOMPINS 0xDA -#define SSD1306_SETVCOMDETECT 0xDB -#define SSD1306_SETDISPLAYCLOCKDIV 0xD5 -#define SSD1306_SETPRECHARGE 0xD9 -#define SSD1306_SETMULTIPLEX 0xA8 -#define SSD1306_SETLOWCOLUMN 0x00 -#define SSD1306_SETHIGHCOLUMN 0x10 -#define SSD1306_SETSTARTLINE 0x40 -#define SSD1306_MEMORYMODE 0x20 -#define SSD1306_COMSCANINC 0xC0 -#define SSD1306_COMSCANDEC 0xC8 -#define SSD1306_SEGREMAP 0xA0 -#define SSD1306_CHARGEPUMP 0x8D - -// Scrolling #defines -#define SSD1306_SET_VERTICAL_SCROLL_AREA 0xA3 -#define SSD1306_RIGHT_HORIZONTAL_SCROLL 0x26 -#define SSD1306_LEFT_HORIZONTAL_SCROLL 0x27 -#define SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL 0x29 -#define SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL 0x2A - -/*========================================================================= - SSD1308 Displays - ----------------------------------------------------------------------- - The driver is used in multiple displays (128x64, 128x32, etc.). -=========================================================================*/ -#define SSD1308_Normal_Display 0xA6 - -/*========================================================================= - SSD1327 Displays - ----------------------------------------------------------------------- - The driver is used in Seeed 96x96 display -=========================================================================*/ -#define SSD1327_Normal_Display 0xA4 - - -//#define BLACK 0 -//#define WHITE 1 - - -// Low level I2C Write function -inline void Adafruit_SSD1306::fastI2Cwrite(uint8_t d) { - //bcm2835_i2c_transfer(d); - i2cDevice::write(&d, 1); -} -inline void Adafruit_SSD1306::fastI2Cwrite(char* tbuf, uint32_t len) { - //bcm2835_i2c_write(tbuf, len); - i2cDevice::write((uint8_t*)tbuf, len); -} - -#define _BV(bit) (1 << (bit)) -// the most basic function, set a single pixel -void Adafruit_SSD1306::drawPixel(int16_t x, int16_t y, uint16_t color) -{ - uint8_t * p = poledbuff ; - - if ((x < 0) || (x >= width()) || (y < 0) || (y >= height())) - return; - - // check rotation, move pixel around if necessary - switch (getRotation()) - { - case 1: - swap(x, y); - x = WIDTH - x - 1; - break; - - case 2: - x = WIDTH - x - 1; - y = HEIGHT - y - 1; - break; - - case 3: - swap(x, y); - y = HEIGHT - y - 1; - break; - } - - // Get where to do the change in the buffer - p = poledbuff + (x + (y/8)*ssd1306_lcdwidth ); - - // x is which column - if (color == WHITE) - *p |= _BV((y%8)); - else - *p &= ~_BV((y%8)); -} - -/* -// Display instantiation -Adafruit_SSD1306::Adafruit_SSD1306() -: i2cDevice(0x3c) -{ - // Init all var, and clean - // Command I/O - rst = 0 ; - fTitle = "SSD1306 OLED"; - - // Lcd size - ssd1306_lcdwidth = 0; - ssd1306_lcdheight = 0; - - // Empty pointer to OLED buffer - poledbuff = NULL; -} -*/ - -// initializer for OLED Type -void Adafruit_SSD1306::select_oled(uint8_t OLED_TYPE) -{ - // Default type - ssd1306_lcdwidth = 128; - ssd1306_lcdheight = 64; - - // default OLED are using internal boost VCC converter - vcc_type = SSD_Internal_Vcc; - - // Oled supported display - // Setup size and I2C address - switch (OLED_TYPE) - { - case OLED_ADAFRUIT_I2C_128x32: - ssd1306_lcdheight = 32; - break; - - case OLED_ADAFRUIT_I2C_128x64: - break; - - case OLED_SEEED_I2C_128x64: - vcc_type = SSD_External_Vcc; - break; - - case OLED_SEEED_I2C_96x96: - ssd1306_lcdwidth = 96; - ssd1306_lcdheight = 96; - break; - - // houston, we have a problem - default: - return; - break; - } -} - -// initializer for I2C - we only indicate the reset pin and OLED type ! -bool Adafruit_SSD1306::init(uint8_t OLED_TYPE, int8_t RST) -{ - rst = RST; - - // Select OLED parameters - select_oled(OLED_TYPE); - - // Setup reset pin direction as output - //bcm2835_gpio_fsel(rst, BCM2835_GPIO_FSEL_OUTP); - - // De-Allocate memory for OLED buffer if any - if (poledbuff) - free(poledbuff); - - // Allocate memory for OLED buffer - poledbuff = (uint8_t *) malloc ( (ssd1306_lcdwidth * ssd1306_lcdheight / 8 )); - if (!poledbuff) return false; - - return (true); -} - -void Adafruit_SSD1306::close(void) -{ - // De-Allocate memory for OLED buffer if any - if (poledbuff) - free(poledbuff); - - poledbuff = NULL; -} - - -void Adafruit_SSD1306::begin( void ) -{ - uint8_t multiplex; - uint8_t chargepump; - uint8_t compins; - uint8_t contrast; - uint8_t precharge; - - constructor(ssd1306_lcdwidth, ssd1306_lcdheight); - -// Reset handling, todo - -/* - // Setup reset pin direction (used by both SPI and I2C) - bcm2835_gpio_fsel(rst, BCM2835_GPIO_FSEL_OUTP); - bcm2835_gpio_write(rst, HIGH); - - // VDD (3.3V) goes high at start, lets just chill for a ms - usleep(1000); - - // bring reset low - bcm2835_gpio_write(rst, LOW); - - // wait 10ms - usleep(10000); - - // bring out of reset - bcm2835_gpio_write(rst, HIGH); -*/ - - // depends on OLED type configuration - if (ssd1306_lcdheight == 32) - { - multiplex = 0x1F; - compins = 0x02; - contrast = 0x8F; - } - else - { - multiplex = 0x3F; - compins = 0x12; - contrast = (vcc_type==SSD_External_Vcc?0x9F:0xCF); - } - - if (vcc_type == SSD_External_Vcc) - { - chargepump = 0x10; - precharge = 0x22; - } - else - { - chargepump = 0x14; - precharge = 0xF1; - } - - ssd1306_command(SSD_Display_Off); // 0xAE - ssd1306_command(SSD1306_SETDISPLAYCLOCKDIV, 0x80); // 0xD5 + the suggested ratio 0x80 - ssd1306_command(SSD1306_SETMULTIPLEX, multiplex); - ssd1306_command(SSD1306_SETDISPLAYOFFSET, 0x00); // 0xD3 + no offset - ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 - ssd1306_command(SSD1306_CHARGEPUMP, chargepump); - ssd1306_command(SSD1306_MEMORYMODE, 0x00); // 0x20 0x0 act like ks0108 - ssd1306_command(SSD1306_SEGREMAP | 0x1); - ssd1306_command(SSD1306_COMSCANDEC); - ssd1306_command(SSD1306_SETCOMPINS, compins); // 0xDA - ssd1306_command(SSD_Set_ContrastLevel, contrast); - ssd1306_command(SSD1306_SETPRECHARGE, precharge); // 0xd9 - ssd1306_command(SSD1306_SETVCOMDETECT, 0x40); // 0xDB - ssd1306_command(SSD1306_DISPLAYALLON_RESUME); // 0xA4 - ssd1306_command(SSD1306_Normal_Display); // 0xA6 - - // Reset to default value in case of - // no reset pin available on OLED - ssd1306_command( 0x21, 0, 127 ); - ssd1306_command( 0x22, 0, 7 ); - stopscroll(); - - // Empty uninitialized buffer - clearDisplay(); - ssd1306_command(SSD_Display_On); //--turn on oled panel -} - - -void Adafruit_SSD1306::invertDisplay(bool inv) -{ - if (inv) - ssd1306_command(SSD_Inverse_Display); - else - ssd1306_command(SSD1306_Normal_Display); -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c) -{ - char buff[2] ; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode ; - buff[1] = c; - - // Write Data on I2C - fastI2Cwrite(buff, sizeof(buff)) ; -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1) -{ - char buff[3] ; - buff[1] = c0; - buff[2] = c1; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode ; - - // Write Data on I2C - fastI2Cwrite(buff, 3) ; -} - -void Adafruit_SSD1306::ssd1306_command(uint8_t c0, uint8_t c1, uint8_t c2) -{ - char buff[4] ; - - buff[1] = c0; - buff[2] = c1; - buff[3] = c2; - - // Clear D/C to switch to command mode - buff[0] = SSD_Command_Mode; - - // Write Data on I2C - fastI2Cwrite(buff, sizeof(buff)) ; -} - - -// startscrollright -// Activate a right handed scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrollright(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_RIGHT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(0XFF); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrollleft -// Activate a right handed scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrollleft(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_LEFT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(0XFF); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrolldiagright -// Activate a diagonal scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrolldiagright(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); - ssd1306_command(0X00); - ssd1306_command(ssd1306_lcdheight); - ssd1306_command(SSD1306_VERTICAL_AND_RIGHT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(SSD_Activate_Scroll); -} - -// startscrolldiagleft -// Activate a diagonal scroll for rows start through stop -// Hint, the display is 16 rows tall. To scroll the whole display, run: -// display.scrollright(0x00, 0x0F) -void Adafruit_SSD1306::startscrolldiagleft(uint8_t start, uint8_t stop) -{ - ssd1306_command(SSD1306_SET_VERTICAL_SCROLL_AREA); - ssd1306_command(0X00); - ssd1306_command(ssd1306_lcdheight); - ssd1306_command(SSD1306_VERTICAL_AND_LEFT_HORIZONTAL_SCROLL); - ssd1306_command(0X00); - ssd1306_command(start); - ssd1306_command(0X00); - ssd1306_command(stop); - ssd1306_command(0X01); - ssd1306_command(SSD_Activate_Scroll); -} - -void Adafruit_SSD1306::stopscroll(void) -{ - ssd1306_command(SSD_Deactivate_Scroll); -} - -void Adafruit_SSD1306::ssd1306_data(uint8_t c) -{ - char buff[2] ; - - // Setup D/C to switch to data mode - buff[0] = SSD_Data_Mode; - buff[1] = c; - - // Write on i2c - fastI2Cwrite( buff, sizeof(buff)) ; -} - -void Adafruit_SSD1306::display(void) -{ - ssd1306_command(SSD1306_SETLOWCOLUMN | 0x0); // low col = 0 - ssd1306_command(SSD1306_SETHIGHCOLUMN | 0x0); // hi col = 0 - ssd1306_command(SSD1306_SETSTARTLINE | 0x0); // line #0 - - uint16_t i=0 ; - - // pointer to OLED data buffer - uint8_t * p = poledbuff; - - char buff[17] ; - uint8_t x ; - - // Setup D/C to switch to data mode - buff[0] = SSD_Data_Mode; - - // loop trough all OLED buffer and - // send a bunch of 16 data byte in one xmission - for ( i=0; i<(ssd1306_lcdwidth*ssd1306_lcdheight/8); i+=16 ) - { - for (x=1; x<=16; x++) - buff[x] = *p++; - - fastI2Cwrite( buff, 17); - } -} - -// clear everything (in the buffer) -void Adafruit_SSD1306::clearDisplay(void) -{ - memset(poledbuff, 0, (ssd1306_lcdwidth*ssd1306_lcdheight/8)); -} - diff --git a/source/daemon/src/logengine.cpp b/source/daemon/src/logengine.cpp deleted file mode 100644 index 212f1451..00000000 --- a/source/daemon/src/logengine.cpp +++ /dev/null @@ -1,174 +0,0 @@ -#include -#include -#include -#include -#include -#include - -/* g_fmt(buf,x) stores the closest decimal approximation to x in buf; - * it suffices to declare buf - * char buf[32]; - */ -/* -#ifdef __cplusplus -extern "C" { -#endif - extern char *g_fmt(char *, double); -#ifdef __cplusplus - } -#endif -*/ - - -static QString dateStringNow(){ - return QDateTime::currentDateTimeUtc().toString("yyyy-MM-dd_hh-mm-ss"); -// uncomment the code below (and comment out the line above) to format the log date in unix timestamp format -// this would be more consistent to the data timestamp format -// but would involve several changes to the existing analysis tools -/* -#if QT_VERSION >= 0x050800 - return QString::number(QDateTime::currentSecsSinceEpoch()); -#else - return QString::number(QDateTime::currentMSecsSinceEpoch()/1000); -#endif -*/ -} - - -LogEngine::LogEngine(QObject *parent) : QObject(parent) -{ - QTimer *logReminder = new QTimer(this); - logReminder->setInterval(60*1000*MuonPi::Config::Log::interval); - logReminder->setSingleShot(false); - connect(logReminder, &QTimer::timeout, this, &LogEngine::onLogInterval); - logReminder->start(); -} - -LogEngine::~LogEngine() -{ -} - -void LogEngine::onLogParameterReceived(const LogParameter& logpar) { -// writeToLogFile(dateStringNow()+" "+QString(log.name()+" "+log.value()+"\n")); -// LogParameter localLog(log); -// localLog.setUpdatedRecently(true); - if (logpar.logType()==LogParameter::LOG_NEVER) { - // do nothing, just return - return; - } - if (logpar.logType()==LogParameter::LOG_EVERY) { - // directly log to file since LOG_EVERY attribute is set - // no need to store in buffer, just return after logging -// writeToLogFile(dateStringNow()+" "+QString(log.name()+" "+log.value()+"\n")); - emit sendLogString(dateStringNow()+" "+QString(logpar.name()+" "+logpar.value())); - // reset already existing entries but preserve logType attribute - if (logData.find(logpar.name())!=logData.end()) { - int logType=logData[logpar.name()].front().logType(); - if (logType!=LogParameter::LOG_AVERAGE) { - logData[logpar.name()].clear(); - } - logData[logpar.name()].push_back(LogParameter(logpar.name(),logpar.value(),logType)); - logData[logpar.name()].back().setUpdatedRecently(false); - } - return; - } else { - // save to buffer - if (logpar.logType()==LogParameter::LOG_ONCE) { - // don't save if a LOG_ONCE param with this name is already in buffer - //if (logData.find(log.name())!=logData.end()) return; - } - logData[logpar.name()].push_back(logpar); - logData[logpar.name()].back().setUpdatedRecently(true); - } -} - -void LogEngine::onLogInterval() { - emit logIntervalSignal(); - // loop over the map with all accumulated parameters since last log reminder - // no increment here since we erase and invalidate iterators within the loop - for (auto it=logData.begin(); it != logData.end();) { - QString name=it.key(); - QVector parVector=it.value(); - // check if name string is set but no entry exists. This should not happen - if (parVector.isEmpty()) { - ++it; - continue; - } - - if (parVector.back().logType()==LogParameter::LOG_LATEST) { - // easy to write only the last value to file - //writeToLogFile(dateStringNow()+" "+name+" "+parVector.back().value()+"\n"); - emit sendLogString(dateStringNow()+" "+name+" "+parVector.back().value()); - it=logData.erase(it); - } else if (parVector.back().logType()==LogParameter::LOG_AVERAGE) { - // here we loop over all values in the vector for the current parameter and do the averaging - double sum=0.; - bool ok=false; - // parse last field of value string - QString unitString=parVector.back().value().section(" ",-1,-1); - // compare with first field - if (unitString.compare(parVector.back().value().section(" ",0,0))==0) { - // unit and value are identical, so there is probably no unit suffix - // set unit to empty string - unitString=""; - } - // do the averaging - for (int i=0; i2) { - parVector.pop_front(); - } - parVector.front().setUpdatedRecently(false); - logData[name]=parVector; - ++it; - } else if (parVector.back().logType()==LogParameter::LOG_ON_CHANGE) { - // we want to log only if one value differs from the first entry - // first entry is reference value - if (onceLogFlag || parVector.front().updatedRecently()) { - // log the first time anyway - //writeToLogFile(dateStringNow()+" "+name+" "+parVector.back().value()+"\n"); - emit sendLogString(dateStringNow()+" "+name+" "+parVector.back().value()); - } else { - for (int i=1; i log it - emit sendLogString(dateStringNow()+" "+name+" "+parVector[i].value()); - //writeToLogFile(dateStringNow()+" "+name+" "+parVector[i].value()+"\n"); - parVector.replace(0,parVector[i]); - } - } - } - while (parVector.size()>1) { - parVector.pop_back(); - } - parVector.front().setUpdatedRecently(false); - logData[name]=parVector; - ++it; - } else ++it; - } - onceLogFlag=false; -} diff --git a/source/daemon/src/main.cpp b/source/daemon/src/main.cpp deleted file mode 100644 index 88c558b4..00000000 --- a/source/daemon/src/main.cpp +++ /dev/null @@ -1,693 +0,0 @@ -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* -#include -#include -#include -*/ - -#include "custom_io_operators.h" -#include "daemon.h" -#include "gpio_pin_definitions.h" -#include -#include "config.h" - -//static const char* CONFIG_FILE = "/etc/muondetector/muondetector.conf"; -static const char* CONFIG_FILE = MuonPi::Config::file; -static int verbose = 0; - - -[[nodiscard]] auto getch() -> int; -[[nodiscard]] auto getpass(const char *prompt, bool show_asterisk) -> std::string; - -auto getch() -> int { - int ch; - struct termios t_old, t_new; - - tcgetattr(STDIN_FILENO, &t_old); - t_new = t_old; - t_new.c_lflag &= ~(ICANON | ECHO); - tcsetattr(STDIN_FILENO, TCSANOW, &t_new); - - ch = getchar(); - - tcsetattr(STDIN_FILENO, TCSANOW, &t_old); - return ch; -} - -auto getpass(const char *prompt, bool show_asterisk) -> std::string -{ - const char BACKSPACE=127; - const char RETURN=10; - - std::string password; - unsigned char ch=0; - ch=getch(); - std::cout <("TcpMessage"); - qRegisterMetaType("EventTime"); - - qInstallMessageHandler(messageOutput); - QCoreApplication a(argc, argv); - QCoreApplication::setApplicationName("muondetector-daemon"); - QCoreApplication::setApplicationVersion(QString::fromStdString(MuonPi::Version::software.string())); - // config file handling - libconfig::Config cfg; - - // Read the file. If there is an error, report it and exit. - try - { - cfg.readFile(CONFIG_FILE); - } - catch(const libconfig::FileIOException &fioex) - { - qWarning()<<"Error while reading config file" << QString(CONFIG_FILE); - //std::cerr << "Error while reading config file " << std::string(CONFIG_FILE) << std::endl; - //return(EXIT_FAILURE); - } - catch(const libconfig::ParseException &pex) - { - qFatal(qPrintable("Parse error at "+QString(pex.getFile())+" : line "+QString(pex.getLine())+" - "+QString(pex.getError()))); - //std::cerr << "Parse error at " << pex.getFile() << ":" << pex.getLine() - // << " - " << pex.getError() << std::endl; - return(EXIT_FAILURE); - } - - // command line input management - QCommandLineParser parser; - parser.setApplicationDescription("MuonPi cosmic shower muon detector control and configuration program (daemon)\n" - "with added tcp implementation for synchronisation of " - "data with a central server through MQTT protocol"); - parser.addHelpOption(); - parser.addVersionOption(); - - // add module path for example /dev/gps0 or /dev/ttyAMA0 - parser.addPositionalArgument("device", QCoreApplication::translate("main", "path to u-blox GNSS device\n" - "e.g. /dev/ttyAMA0")); - - // login option - QCommandLineOption mqttLoginOption(QStringList() << "l" << "login", - QCoreApplication::translate("main", "ask for login to the online mqtt server")); - parser.addOption(mqttLoginOption); - - // station ID (some name for individual stations if someone has multiple) - QCommandLineOption stationIdOption("id", - QCoreApplication::translate("main", "set station ID"), - QCoreApplication::translate("main", "ID")); - parser.addOption(stationIdOption); - - - // verbosity option - QCommandLineOption verbosityOption(QStringList() << "e" << "verbose", - QCoreApplication::translate("main", "set verbosity level\n" - "5 is max"), - QCoreApplication::translate("main", "verbosity")); - parser.addOption(verbosityOption); - - // dumpraw option - QCommandLineOption dumpRawOption("d", - QCoreApplication::translate("main", "dump raw gps device (NMEA) output to stdout")); - parser.addOption(dumpRawOption); - - // show GNSS configs - QCommandLineOption showGnssConfigOption("c", - QCoreApplication::translate("main", "configure standard ubx protocol messages at start")); - parser.addOption(showGnssConfigOption); - - // show outgoing ubx messages as hex - QCommandLineOption showoutOption(QStringList() << "showoutgoing" << "showout", - QCoreApplication::translate("main", "show outgoing ubx messages as hex")); - parser.addOption(showoutOption); - - // show incoming ubx messages as hex - QCommandLineOption showinOption(QStringList() << "showincoming" << "showin", - QCoreApplication::translate("main", "show incoming ubx messages as hex")); - parser.addOption(showinOption); - - // peerAddress option - QCommandLineOption peerIpOption(QStringList() << "peer" << "peerAddress", - QCoreApplication::translate("main", "set file server ip address"), - QCoreApplication::translate("main", "peerAddress")); - parser.addOption(peerIpOption); - - // peerPort option - QCommandLineOption peerPortOption(QStringList() << "pp" << "peerPort", - QCoreApplication::translate("main", "set file server port"), - QCoreApplication::translate("main", "peerPort")); - parser.addOption(peerPortOption); - - // daemonAddress option - QCommandLineOption daemonIpOption(QStringList() << "server" << "daemonAddress", - QCoreApplication::translate("main", "set gui server ip address"), - QCoreApplication::translate("main", "daemonAddress")); - parser.addOption(daemonIpOption); - - // daemonPort option - QCommandLineOption daemonPortOption(QStringList() << "dp" << "daemonPort", - QCoreApplication::translate("main", "set gui server port"), - QCoreApplication::translate("main", "daemonPort")); - parser.addOption(daemonPortOption); - - // baudrate option - QCommandLineOption baudrateOption("b", - QCoreApplication::translate("main", "set baudrate for serial connection"), - QCoreApplication::translate("main", "baudrate")); - parser.addOption(baudrateOption); - - // discriminator thresholds: - QCommandLineOption discr1Option(QStringList() << "discr1" << "thresh1" << "th1", - QCoreApplication::translate("main", - "set discriminator 1 threshold in Volts"), - QCoreApplication::translate("main", "threshold1")); - parser.addOption(discr1Option); - QCommandLineOption discr2Option(QStringList() << "discr2" << "thresh2" << "th2", - QCoreApplication::translate("main", - "set discriminator 2 threshold in Volts"), - QCoreApplication::translate("main", "threshold2")); - parser.addOption(discr2Option); - - // pcaChannel to select signal to ublox - QCommandLineOption pcaChannelOption(QStringList() << "pca" << "signal", - QCoreApplication::translate("main", "set input signal for ublox interrupt pin:" - "\n0 - coincidence (AND)" - "\n1 - anti-coincidence (XOR)" - "\n2 - discr 1" - "\n3 - discr 2" - "\n4 - vcc" - "\n5 - timepulse" - "\n6 - N/A" - "\n7 - ext signal" - ), - QCoreApplication::translate("main", "channel")); - parser.addOption(pcaChannelOption); - - // biasVoltage for SiPM - QCommandLineOption biasVoltageOption(QStringList() << "bias" << "vout", - QCoreApplication::translate("main", "set bias voltage for SiPM"), - QCoreApplication::translate("main", "bias voltage")); - parser.addOption(biasVoltageOption); - - // biasVoltage on or off - QCommandLineOption biasPowerOnOff(QStringList() << "p", - QCoreApplication::translate("main", "bias voltage on or off")); - parser.addOption(biasPowerOnOff); - - // preamps on: - QCommandLineOption preamp1Option(QStringList() << "pre1" << "preamp1", - QCoreApplication::translate("main", "preamplifier channel 1 on/off (0/1)")); - parser.addOption(preamp1Option); - QCommandLineOption preamp2Option(QStringList() << "pre2" << "preamp2", - QCoreApplication::translate("main", "preamplifier channel 2 on/off (0/1)")); - parser.addOption(preamp2Option); - - // gain: - QCommandLineOption gainOption(QStringList() << "g" << "gain", - QCoreApplication::translate("main", "peak detector high gain select")); - parser.addOption(gainOption); - - // event trigger for ADC - QCommandLineOption eventInputOption(QStringList() << "t" << "trigger", - QCoreApplication::translate("main", "event (trigger) signal input:" - "\n0 - coincidence (AND)" - "\n1 - anti-coincidence (XOR)"), - QCoreApplication::translate("main", "trigger")); - parser.addOption(eventInputOption); - - // input polarity switch: - QCommandLineOption pol1Option(QStringList() << "pol1" << "polarity1", - QCoreApplication::translate("main", "input polarity ch1 negative (0) or positive (1)")); - parser.addOption(pol1Option); - QCommandLineOption pol2Option(QStringList() << "pol2" << "polarity2", - QCoreApplication::translate("main", "input polarity ch2 negative (0) or positive (1)")); - parser.addOption(pol2Option); - - // process the actual command line arguments given by the user - parser.process(a); - const QStringList args = parser.positionalArguments(); - if (args.size() > 1) { qWarning() << "you set additional positional arguments but the program does not use them"; } - - bool ok; - if (parser.isSet(verbosityOption)) { - verbose = parser.value(verbosityOption).toInt(&ok); - if (!ok) { - verbose = 0; - qWarning() << "wrong verbosity level selection...setting to 0"; - } - } - - // setup all variables for ublox module manager, then make the object run - QString gpsdevname=""; - if (!args.empty() && args.at(0) != "") { - gpsdevname = args.at(0); - } else - try - { - std::string gpsdevnameCfg = cfg.lookup("ublox_device"); - if (verbose>2) std::cout << "ublox device: " << gpsdevnameCfg << std::endl; - gpsdevname = QString::fromStdString(gpsdevnameCfg); - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) - qWarning() << "No 'ublox_device' setting in configuration file. Will guess..."; - QDir directory("/dev","*",QDir::Name, QDir::System); - QStringList serialports = directory.entryList(QStringList({"ttyS0","ttyAMA0","serial0"})); - if (!serialports.empty()){ - gpsdevname=QString("/dev/"+serialports.last()); - //if (verbose>2) - qInfo() << "detected" << gpsdevname << "as most probable candidate"; - }else{ - qCritical() << "no device selected, will not connect to GNSS module" << endl; - } - } - - if (verbose > 4) { - qDebug() << "int main running in thread" - << QString("0x%1").arg(reinterpret_cast(QCoreApplication::instance()->thread())); - } - bool dumpRaw = parser.isSet(dumpRawOption); - int baudrate = 9600; - if (parser.isSet(baudrateOption)) { - baudrate = parser.value(baudrateOption).toInt(&ok); - if (!ok || baudrate < 0) { - baudrate = 9600; - qWarning() << "wrong input for baudrate...using default:" << baudrate; - } - } else - try - { - int baudrateCfg = cfg.lookup("ublox_baud"); - if (verbose>2) qInfo() << "ublox baudrate:" << baudrateCfg; - baudrate = baudrateCfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - if (verbose>1) - qWarning() << "No 'ublox_baud' setting in configuration file. Assuming" << baudrate; - } - - bool showGnssConfig = false; - showGnssConfig = parser.isSet(showGnssConfigOption); - quint16 peerPort = 0; - if (parser.isSet(peerPortOption)) { - peerPort = parser.value(peerPortOption).toUInt(&ok); - if (!ok) { - peerPort = 0; - qCritical() << "wrong input peerPort (maybe not an integer)"; - } - } - QString peerAddress = ""; - if (parser.isSet(peerIpOption)) { - peerAddress = parser.value(peerIpOption); - if (!QHostAddress(peerAddress).toIPv4Address()) { - if (peerAddress != "localhost" && peerAddress != "local") { - peerAddress = ""; - qCritical() << "wrong input ipAddress, not an ipv4address"; - } - } - } - quint16 daemonPort = 0; - if (parser.isSet(daemonPortOption)) { - daemonPort = parser.value(daemonPortOption).toUInt(&ok); - if (!ok) { - peerPort = 0; - qCritical() << "wrong input peerPort (maybe not an integer)"; - } - } - QString daemonAddress = ""; - if (parser.isSet(daemonIpOption)) { - daemonAddress = parser.value(daemonIpOption); - if (!QHostAddress(daemonAddress).toIPv4Address()) { - if (daemonAddress != "localhost" && daemonAddress != "local") { - daemonAddress = ""; - qCritical() << "wrong daemon ipAddress, not an ipv4address"; - } - } - } - - quint8 pcaChannel = 0; - if (parser.isSet(pcaChannelOption)) { - pcaChannel = parser.value(pcaChannelOption).toUInt(&ok); - if (!ok) { - pcaChannel = 0; - qCritical() << "wrong input pcaChannel (maybe not an unsigned integer)"; - } - } else - try - { - int pcaChannelCfg = cfg.lookup("timing_input"); - if (verbose>2) qDebug() << "timing input: " << pcaChannelCfg << endl; - pcaChannel = pcaChannelCfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) - qWarning() << "No 'timing_input' setting in configuration file. Assuming" << (int)pcaChannel; - } - - bool showout = false; - showout = parser.isSet(showoutOption); - bool showin = false; - showin = parser.isSet(showinOption); - - float dacThresh[2]; - dacThresh[0] = -1.; - if (parser.isSet(discr1Option)) { - dacThresh[0] = parser.value(discr1Option).toFloat(&ok); - if (!ok) { - dacThresh[0] = -1.; - qCritical() << "error in value for discr1 (maybe not a float)"; - } - } - dacThresh[1] = -1.; - if (parser.isSet(discr2Option)) { - dacThresh[1] = parser.value(discr2Option).toFloat(&ok); - if (!ok) { - dacThresh[1] = -1.; - qCritical() << "error in value for discr2 (maybe not a float)"; - } - } - float biasVoltage = -1.; - if (parser.isSet(biasVoltageOption)) { - biasVoltage = parser.value(biasVoltageOption).toFloat(&ok); - if (!ok) { - biasVoltage = -1.; - qCritical() << "error in value for biasVoltage (maybe not a float)"; - } - } - bool biasPower = false; - if (parser.isSet(biasPowerOnOff)) { - biasPower = true; - } else - try - { - int biasPowerCfg = cfg.lookup("bias_switch"); - if (verbose>2) qDebug() << "bias switch:" << biasPowerCfg; - biasPower = biasPowerCfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) - qWarning() << "No 'bias_switch' setting in configuration file. Assuming" << (int)biasPower; - } - - bool preamp1 = false; - if (parser.isSet(preamp1Option)) { - preamp1 = true; - } else - try - { - int preamp1Cfg = cfg.lookup("preamp1_switch"); - if (verbose>2) qDebug() << "preamp1 switch:" << preamp1Cfg; - preamp1 = preamp1Cfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) - qWarning() << "No 'preamp1_switch' setting in configuration file. Assuming" << (int)preamp1; - } - - bool preamp2 = false; - if (parser.isSet(preamp2Option)) { - preamp2 = true; - } else - try - { - int preamp2Cfg = cfg.lookup("preamp2_switch"); - if (verbose>2) qDebug() << "preamp2 switch:" << preamp2Cfg; - preamp2 = preamp2Cfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) - qWarning() << "No 'preamp2_switch' setting in configuration file. Assuming " << (int)preamp2; - } - - - bool gain = false; - if (parser.isSet(gainOption)) { - gain = true; - } else { - try - { - int gainCfg = cfg.lookup("gain_switch"); - if (verbose>2) qDebug() << "gain switch:" << gainCfg; - gain = gainCfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - if (verbose>0) - qWarning() << "No 'gain_switch' setting in configuration file. Assuming" << (int)gain; - } - } - - unsigned int eventSignal = EVT_XOR; - if (parser.isSet(eventInputOption)) { - eventSignal = parser.value(eventInputOption).toUInt(&ok); - if (!ok || eventSignal>1) { - qCritical() << "wrong trigger input signal (valid: 0,1)"; - return -1; - } else { - switch (eventSignal) { - case 1: eventSignal=EVT_AND; - break; - case 0: - default: - eventSignal=EVT_XOR; - break; - } - } - } else - try - { - int eventSignalCfg = cfg.lookup("trigger_input"); - if (verbose>2) qDebug() << "event trigger : " << eventSignalCfg; - switch (eventSignalCfg) { - case 1: eventSignal=EVT_AND; - break; - case 0: - default: - eventSignal=EVT_XOR; - break; - } - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose>2) -// qWarning() << "No 'trigger_input' setting in configuration file. Assuming gpio" << (int)eventSignal << endl; - qWarning() << "No 'trigger_input' setting in configuration file. Assuming signal" << GPIO_SIGNAL_MAP[(GPIO_SIGNAL)eventSignal].name; - } - - - bool pol1 = true; - if (parser.isSet(pol1Option)) { - unsigned int pol1int = parser.value(pol1Option).toUInt(&ok); - if (!ok || pol1int>1) { - qCritical() << "wrong input polarity setting ch1 (valid: 0,1)"; - return -1; - } else { - pol1=(bool)pol1int; - } - } else { - try - { - int pol1Cfg = cfg.lookup("input1_polarity"); - if (verbose>2) qDebug() << "input polarity ch1:" << pol1Cfg; - pol1 = (bool)pol1Cfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - if (verbose>0) - qWarning() << "No 'input1_polarity' setting in configuration file. Assuming" << (int)pol1; - } - } - - bool pol2 = true; - if (parser.isSet(pol2Option)) { - unsigned int pol2int = parser.value(pol2Option).toUInt(&ok); - if (!ok || pol2int>1) { - qCritical() << "wrong input polarity setting ch2 (valid: 0,1)"; - return -1; - } else { - pol2=(bool)pol2int; - } - } else { - try - { - int pol2Cfg = cfg.lookup("input2_polarity"); - if (verbose>2) qDebug() << "input polarity ch2:" << pol2Cfg; - pol2 = (bool)pol2Cfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - if (verbose>0) - qWarning() << "No 'input2_polarity' setting in configuration file. Assuming" << (int)pol2; - } - } - - - std::string username=""; - std::string password=""; - if (parser.isSet(mqttLoginOption)){ - std::cout << "To set the login for the mqtt-server, please enter user name:\n"<> username; - password = getpass("please enter password:",true); - } else - try - { - std::string userNameCfg = cfg.lookup("mqtt_user"); - std::string passwordCfg = cfg.lookup("mqtt_password"); - if (verbose>2) qDebug() << "mqtt user: " << QString::fromStdString(userNameCfg) << " passw: " << QString::fromStdString(passwordCfg); - username=userNameCfg; - password=passwordCfg; - } - catch(const libconfig::SettingNotFoundException &nfex) - { - if (verbose>1) - qDebug() << "No 'mqtt_user' or 'mqtt_password' setting in configuration file. Will continue with previously stored credentials"; - } - - QString stationID = "0"; - if (parser.isSet(stationIdOption)){ - stationID = parser.value(stationIdOption); - } else { - // Get the station id from config, if it exists - try - { - std::string stationIdString = cfg.lookup("stationID"); - if (verbose) qInfo() << "station id: " << QString::fromStdString(stationIdString); - stationID = QString::fromStdString(stationIdString); - } - catch(const libconfig::SettingNotFoundException &nfex) - { - //if (verbose) - qWarning() << "No 'stationID' setting in configuration file. Assuming stationID='0'"; - } - } - /* - pid_t pid; - - // Fork off the parent process - pid = fork(); - - // An error occurred - if (pid < 0) - exit(EXIT_FAILURE); - - // Success: Let the parent terminate - if (pid > 0) - exit(EXIT_SUCCESS); - - // On success: The child process becomes session leader - if (setsid() < 0) - exit(EXIT_FAILURE); - - // Catch, ignore and handle signals - //TODO: Implement a working signal handler - signal(SIGCHLD, SIG_IGN); - signal(SIGHUP, SIG_IGN); - - // Fork off for the second time - pid = fork(); - - // An error occurred - if (pid < 0) - exit(EXIT_FAILURE); - - // Success: Let the parent terminate - if (pid > 0) - exit(EXIT_SUCCESS); - - // Set new file permissions - umask(0); - - // Change the working directory to the root directory - // or another appropriated directory - chdir("/"); - - // Close all open file descriptors - int x; - for (x = sysconf(_SC_OPEN_MAX); x>=0; x--) - { - close (x); - } - - // Open the log file - openlog ("muondetector-daemon", LOG_PID, LOG_DAEMON); - */ - Daemon daemon(QString::fromStdString(username), QString::fromStdString(password), gpsdevname, verbose, pcaChannel, dacThresh, biasVoltage, biasPower, dumpRaw, - baudrate, showGnssConfig, eventSignal, peerAddress, peerPort, daemonAddress, daemonPort, showout, showin, preamp1, preamp2, gain, stationID, pol1, pol2); - - return a.exec(); -} diff --git a/source/daemon/src/ratebuffer.cpp b/source/daemon/src/ratebuffer.cpp deleted file mode 100644 index a31bcaed..00000000 --- a/source/daemon/src/ratebuffer.cpp +++ /dev/null @@ -1,100 +0,0 @@ -#include -#include - -constexpr auto invalid_time = std::chrono::system_clock::time_point::min(); - -RateBuffer::RateBuffer(QObject *parent) : QObject(parent) -{ - -} - -void RateBuffer::updateAllIntervals( unsigned int new_gpio, EventTime new_event_time ) -{ - for ( const auto [ other_gpio, buffer_item ] : buffermap ) { - if ( new_gpio == other_gpio ) continue; - if ( buffer_item.eventbuffer.empty() ) continue; - auto last_other_time = buffer_item.eventbuffer.back(); - std::chrono::nanoseconds nsecs = std::chrono::duration_cast( new_event_time - last_other_time ); - fIntervalMap.insert_or_assign( std::make_pair( new_gpio, other_gpio ), nsecs ); - } -} - -void RateBuffer::onEvent( unsigned int gpio, EventTime event_time ) { - updateAllIntervals( gpio, event_time ); - if ( buffermap[gpio].eventbuffer.empty() ) { - buffermap[gpio].eventbuffer.push(event_time); - emit filteredEvent(gpio, event_time); - return; - } - - while ( !buffermap.at(gpio).eventbuffer.empty() - && ( event_time - buffermap[gpio].eventbuffer.front() > fBufferTime) ) - { - buffermap[gpio].eventbuffer.pop(); - } - - if ( !buffermap[gpio].eventbuffer.empty() ) { - auto last_event_time = buffermap[gpio].eventbuffer.back(); - buffermap[gpio].last_interval = std::chrono::duration_cast( event_time - last_event_time ); - if ( event_time - last_event_time < MAX_DEADTIME ) { -// std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< 0 ) { - deadtime--; - buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); - } - } - } - buffermap[gpio].eventbuffer.push(event_time); - emit filteredEvent(gpio, event_time); - if ( buffermap[gpio].last_interval != std::chrono::nanoseconds(0) ) { - emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); - } -} - -auto RateBuffer::avgRate(unsigned int gpio) const -> double -{ - auto it = buffermap.find(gpio); - if ( it == buffermap.end() ) return 0.; - if ( it->second.eventbuffer.empty() ) return 0.; - auto end = std::chrono::system_clock::now(); - auto start = end - fBufferTime; - if ( start > it->second.eventbuffer.front() ) start = it->second.eventbuffer.front(); - double span = 1e-6 * std::chrono::duration_cast(end - start).count(); - return ( it->second.eventbuffer.size() / span ); -} - -auto RateBuffer::currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds -{ - auto it = buffermap.find(gpio); - if ( it == buffermap.end() ) return std::chrono::microseconds(0); - return it->second.current_deadtime; -} - -auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds -{ - auto it = buffermap.find(gpio); - if ( it == buffermap.end() || it->second.eventbuffer.size() < 2 ) return std::chrono::nanoseconds(0); - return it->second.last_interval; -} - -auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds -{ - auto it = fIntervalMap.find( std::make_pair( gpio1, gpio2 ) ); - if ( it == fIntervalMap.end() ) return std::chrono::nanoseconds(0); - return fIntervalMap.at( std::make_pair( gpio1, gpio2 ) ); -} - -auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime -{ - auto it = buffermap.find(gpio); - if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; - return it->second.eventbuffer.back(); -} - diff --git a/source/daemon/src/tdc7200.cpp b/source/daemon/src/tdc7200.cpp deleted file mode 100644 index 82181c8f..00000000 --- a/source/daemon/src/tdc7200.cpp +++ /dev/null @@ -1,190 +0,0 @@ -#include "tdc7200.h" -#include - -TDC7200::TDC7200(unsigned int _INTB, QObject *parent) : QObject(parent) -{ - INTB = (uint8_t)_INTB; -} - -void TDC7200::initialise(){ - devicePresent = false; - writeReg(0x03, 0x07); - readReg(0x03); -} - -void TDC7200::onDataAvailable(uint8_t pin){ - // this means if the INTB is high and there are new measurement results - // should read all relevant TOF data and after that - //qDebug() << "received signal on pin " << pin; - if (pin != INTB){ - return; - } - uint8_t num_stop = config[1]&0x07; - if (num_stop > 0b100){ - num_stop = 0; - } - - num_stop++; - - waitingForDataCounter = (int)((num_stop)*2 +3); - readReg(0x1b); // calibration 1 - readReg(0x1c); // calibration 2 - for(int i = 0; i < num_stop*2+1; i++){ - // TIME1 and as many TIMEx and CLOCK_COUNTx as num_stop - // for single num_stop there are TIME1, CLOCK_COUNT1, TIME2 - readReg(i+0x10); - } -} - -void TDC7200::onStatusRequested(){ - emit statusUpdated(devicePresent); -} - -void TDC7200::configRegisters(){ - for (int i = sizeof(config)-1; i > 0; i--){ - writeReg(i, config[i]); - } -} - -void TDC7200::startMeas(){ - if (!devicePresent){ - initialise(); - return; - } - //qDebug() << "start measurement"; - writeReg(0, config[0]|0x01); // the least significant bit starts the measurement -} - -void TDC7200::onDataReceived(uint8_t reg, std::string data){ - //qDebug() << "onDataReceived"; - if (devicePresent == false){ - if(reg == 0x03 && data.size()==1 and data[0] == (char)0x07){ - devicePresent = true; // device is present, do configuration - emit statusUpdated(true); - //qDebug() << "TDC7200 is now present"; - configRegisters(); - return; - }else{ - emit statusUpdated(false); - qDebug() << "TDC7200 not present"; - return; - } - } - if (reg < 10){ - if (data.size()!=1){ - qDebug() << "data size returned does not match the register size"; - return; - } - }else if(data.size()!=3){ - qDebug() << "data size returned does not match the register size"; - return; - }else if(reg > 0x1c){ - qDebug() << "returned register address out of scope"; - return; - } - uint32_t regContent = 0; - if (reg < 10){ - regContent = (uint32_t)data[0]; - regContent1[reg] = (uint8_t)data[0]; - }else{ - regContent = data[0]; - regContent <<=8; - regContent |= data[1]; - regContent <<=8; - regContent |= data[2]; - regContent2[reg-0x10] = regContent; - if (waitingForDataCounter!=-1){ - waitingForDataCounter--; - } - } - emit regContentChanged(reg, regContent); - if (waitingForDataCounter == 0){ - waitingForDataCounter = -1; - processData(); - } -} - -void TDC7200::processData(){ - uint8_t num_stop = config[1]&0x07; - if (num_stop > 0b100){ - num_stop = 0; - } - num_stop += 1; - uint8_t meas_mode = (config[0]&0x2)>>1; - uint32_t CALIBRATION1 = regContent2[0x1b-0x10]; - uint32_t CALIBRATION2 = regContent2[0x1c-0x10]; - uint8_t cal2_periods_setting = (config[1]&0b11000000)>>6; - uint8_t CALIBRATION2_PERIODS = 0; - switch (cal2_periods_setting){ - case 0: - CALIBRATION2_PERIODS = 2; - break; - case 1: - CALIBRATION2_PERIODS = 10; - break; - case 2: - CALIBRATION2_PERIODS = 20; - break; - case 3: - CALIBRATION2_PERIODS = 40; - break; - default: - break; - } - - QVector timings; - double calCount = ((double)CALIBRATION2-(double)CALIBRATION1)/((double)CALIBRATION2_PERIODS-1); - double normLSB = (double)CLOCKperiod/calCount; - double TIME1 = (double)regContent2[0]; - //double TIME2 = regContent2[2]; - //uint32_t CLOCK_COUNT1 = regContent2[1]; - /* - qDebug() << "processData:"; - qDebug() << "num_stop: " < write and bit 7 is 0 for writing only one byte - std::string dataString; - dataString += (char)data; - emit writeData(command, dataString); -} - -void TDC7200::readReg(uint8_t reg){ - unsigned int bytesRead = 0; - if (reg < 10){ - bytesRead = 1; - }else{ - bytesRead = 3; - } - uint8_t command = reg & 0x3f; - emit readData(command, bytesRead); -} diff --git a/source/gui/include/scanform.h b/source/gui/include/scanform.h deleted file mode 100644 index 722db09e..00000000 --- a/source/gui/include/scanform.h +++ /dev/null @@ -1,74 +0,0 @@ -#ifndef SCANFORM_H -#define SCANFORM_H - -#include -#include -#include -#include -#include -#include - -// list of possible scan parameters -const static QVector SP_NAMES = { "VOID", "THR1", "THR2", "BIAS" }; -// list of possible observables -const static QVector OP_NAMES = { "VOID", "UBXRATE" /*, "GPIORATE"*/ }; - - -namespace Ui { -class ScanForm; -} - -class ScanForm : public QWidget -{ - Q_OBJECT - -public: - - struct ScanPoint { - double value { 0. }; - double error { 0. }; - double temp { 0. }; - }; - - explicit ScanForm(QWidget *parent = 0); - ~ScanForm(); - -signals: - void setThresholdVoltage(uint8_t ch, float val); - void setBiasControlVoltage(float val); - void gpioInhibitChanged(bool inhibitState); - void mqttInhibitChanged(bool inhibitState); -public slots: - void onTimeMarkReceived(const UbxTimeMarkStruct& tm); - void onUiEnabledStateChange(bool connected); - -private slots: - void on_scanStartPushButton_clicked(); - void scanParIteration(); - void adjustScanPar(QString scanParName, double value); - void finishScan(); - void updateScanPlot(); - void on_plotDifferentialCheckBox_toggled(bool checked); - void exportData(); - -private: - Ui::ScanForm *ui; - bool active=false; - UbxTimeMarkStruct lastTM; - double minRange=0.; - double maxRange=0.; - double stepSize=0.001; - quint8 scanPar=0; - quint8 obsPar=0; - double currentScanPar=0.0; - uint64_t currentCounts; - double currentTimeInterval=0.; - double maxMeasurementTimeInterval=1.; - unsigned long maxMeasurementStatistics { 0 }; - bool waitForFirst=false; - - QMap scanData; - bool plotDifferential = false; -}; - -#endif // SCANFORM_H diff --git a/source/gui/qml/CustomMap.qml b/source/gui/qml/CustomMap.qml deleted file mode 100644 index 1868e138..00000000 --- a/source/gui/qml/CustomMap.qml +++ /dev/null @@ -1,165 +0,0 @@ -import QtQuick 2.2 -import QtLocation 5.7 -import QtQuick.Layouts 1.0 -import QtPositioning 5.0 -import QtQuick.Controls 2.0 -import "qrc:/qml/places/items" -//import "qrc:/qml/places/views" - -CustomMapForm { - id: page - Plugin { - id: plugin - name: "osm" // "mapboxgl", "esri", ... - } - function setCircle(lon,lat,hAcc) - { - map.onCoordsReceived(lon,lat,hAcc) - } - /* - SearchBar{ - id: searchBar - width: parent.width - anchors.top: parent.top - height: 40 - onDoSearch: { - if (searchText.length > 0) - placeSearchModel.searchForText(searchText); - } - }*/ - MapComponent{ - id: map - property double lastLon: 8.673828 - property double lastLat: 50.569212 - plugin: plugin - anchors.top: parent.top - //anchors.top: searchBar.bottom - width: parent.width - height: parent.height - zoomLevel: (map.maximumZoomLevel - map.minimumZoomLevel)/2 - function onCoordsReceived(lon,lat,hAcc) - { - lastLon = lon - lastLat = lat - circle.center.longitude = lon - circle.center.latitude = lat - circle.radius = hAcc -/* - console.log("lon: "+lon) - console.log("lat: "+lat) - console.log("lastLon: "+lastLon) - console.log("lastLat: "+lastLat) -*/ if (control.checked){ - map.center = QtPositioning.coordinate(lat,lon) - } - } - function jumpToLocation(){ - map.center = QtPositioning.coordinate(lastLat,lastLon) - } - - MapCircle { - id: circle - center: parent.center - radius: 0.0 - border.width: 2 - } - ToolBar{ - id: buttonBar - anchors.top: parent.top - height: 30 - //Behavior on opacity { NumberAnimation{} } - RowLayout{ - Rectangle{ - height: 30 - width: 60 - anchors.top: parent.top - color: "white" - ToolButton{ - id: centerButton - anchors.fill: parent - text: "center" - onClicked: map.jumpToLocation() - } - } - Rectangle{ - Layout.column: 1 - width: 90 - anchors.top: parent.top - height: 30 - color:"white" - CheckBox{ - id: control - anchors.fill: parent - text: "follow" - } - } - } - } - } - /* - Rectangle{ - id: searchRectangle - anchors.fill: parent - visible: false - //! [PlaceSearchModel model] - PlaceSearchModel { - id: placeSearchModel - plugin: plugin; - searchArea: QtPositioning.circle(map.center, 10) - favoritesPlugin: null - relevanceHint: PlaceSearchModel.UnspecifiedHint - function searchForCategory(category) { - searchTerm = ""; - categories = category; - recommendationId = ""; - searchArea = QtPositioning.circle(map.center, 10) - limit = -1; - update(); - } - - function searchForText(text) { - searchTerm = text; - categories = null; - recommendationId = ""; - searchArea = QtPositioning.circle(map.center, 10) - limit = -1; - update(); - } - - function searchForRecommendations(placeId) { - searchTerm = ""; - categories = null; - recommendationId = placeId; - searchArea = null; - limit = -1; - update(); - } - - onStatusChanged: { - switch (status) { - case PlaceSearchModel.Ready: - console.log("ready") - if (count > 0) - console.log("visible!?") - searchRectangle.visible = true - break; - case PlaceSearchModel.Error: - console.log("search place error: "+errorString()) - //stackView.showMessage(qsTr("Search Place Error"),errorString()) - break; - } - } - } - //! [PlaceSearchModel model] - SearchResultView { - id: searchView - } - } - */ - /* - Rectangle{ - id: something - anchors.fill: parent - visible: false - }*/ -} diff --git a/source/gui/src/calibform.cpp b/source/gui/src/calibform.cpp deleted file mode 100644 index ac2fde7e..00000000 --- a/source/gui/src/calibform.cpp +++ /dev/null @@ -1,365 +0,0 @@ -#include -#include "calibform.h" -#include "ui_calibform.h" -#include -#include -#include -#include "calibscandialog.h" - - -using namespace std; - -const static CalibStruct invalidCalibItem; - - -CalibForm::CalibForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::CalibForm) -{ - ui->setupUi(this); - ui->calibItemTableWidget->resizeColumnsToContents(); - - calScan = new CalibScanDialog(this); - calScan->setWindowTitle("Calibration Scan"); - calScan->hide(); - - connect(ui->calibrationScanPushButton, &QPushButton::clicked, this, [this]() { this->calScan->show();} ); - - - -/* - ui->biasVoltageCalibPlot->setTitle("Ubias calibration"); - ui->biasVoltageCalibPlot->setAxisTitle(QwtPlot::xBottom,"DAC voltage / V"); - ui->biasVoltageCalibPlot->setAxisTitle(QwtPlot::yLeft,"Ubias / V"); - ui->biasCurrentCalibPlot->setTitle("Ibias correction"); - ui->biasCurrentCalibPlot->setAxisTitle(QwtPlot::xBottom,"bias voltage / V"); - QFont font = ui->biasCurrentCalibPlot->axisTitle(QwtPlot::yLeft).font(); - font.setPointSize(5); - ui->biasCurrentCalibPlot->axisTitle(QwtPlot::yLeft).font().setPointSize(5); - ui->biasCurrentCalibPlot->setAxisTitle(QwtPlot::yLeft,"Ibias / uA"); - - ui->biasVoltageCalibPlot->addCurve("curve1", Qt::blue); - ui->biasVoltageCalibPlot->curve("curve1").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); - ui->biasVoltageCalibPlot->curve("curve1").setSymbol(sym); - - ui->biasVoltageCalibPlot->addCurve("curve2", Qt::red); - ui->biasVoltageCalibPlot->curve("curve2").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym2=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::red, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); - ui->biasVoltageCalibPlot->curve("curve2").setSymbol(sym2); - - ui->biasCurrentCalibPlot->addCurve("curve3", Qt::green); - ui->biasCurrentCalibPlot->curve("curve3").setStyle(QwtPlotCurve::NoCurve); - //ui->biasCurrentCalibPlot->curve("curve3").setYAxis(QwtPlot::yRight); - QwtSymbol *sym3=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::green, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); - ui->biasCurrentCalibPlot->curve("curve3").setSymbol(sym3); - //ui->biasCurrentCalibPlot->enableAxis(QwtPlot::yRight,true); - ui->biasCurrentCalibPlot->addCurve("Fit", Qt::green); - ui->biasCurrentCalibPlot->curve("Fit").setStyle(QwtPlotCurve::Lines); - - ui->biasVoltageCalibPlot->addCurve("Fit1", Qt::blue); - ui->biasVoltageCalibPlot->curve("Fit1").setStyle(QwtPlotCurve::Lines); - ui->biasVoltageCalibPlot->addCurve("Fit2", Qt::red); - ui->biasVoltageCalibPlot->curve("Fit2").setStyle(QwtPlotCurve::Lines); - - ui->biasVoltageCalibPlot->replot(); - ui->biasCurrentCalibPlot->replot(); - ui->transferBiasCoeffsPushButton->setEnabled(false); -*/ -} - -CalibForm::~CalibForm() -{ - delete ui; -} - -void CalibForm::onCalibReceived(bool valid, bool eepromValid, quint64 id, const QVector & calibList) -{ - calScan->onCalibReceived(valid, eepromValid, id, calibList); - - QString str = "invalid"; - if (eepromValid) str="valid"; - ui->eepromValidLabel->setText(str); - str = "invalid"; - if (valid) str="valid"; - ui->calibValidLabel->setText(str); - ui->idLineEdit->setText(QString::number(id,16)); - - fCalibList.clear(); - for (int i=0; ieepromHwVersionSpinBox->setValue(ver); - double rsense = 0.1*getCalibParameter("RSENSE").toInt(); - ui->rsenseDoubleSpinBox->setValue(rsense); - double vdiv = 0.01*getCalibParameter("VDIV").toInt(); - ui->vdivDoubleSpinBox->setValue(vdiv); - int eepCycles = getCalibParameter("WRITE_CYCLES").toInt(); - ui->eepromWriteCyclesLabel->setText(QString::number(eepCycles)); - int featureFlags = getCalibParameter("FEATURE_FLAGS").toInt(); - ui->featureGnssCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_GNSS); - ui->featureEnergyCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_ENERGY); - ui->featureDetBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_DETBIAS); - ui->featurePreampBiasCheckBox->setChecked(featureFlags & CalibStruct::FEATUREFLAGS_PREAMP_BIAS); - - if (voltageCalibValid()) { - fSlope1 = getCalibParameter("COEFF1").toDouble(); - fOffs1 = getCalibParameter("COEFF0").toDouble(); - } - if (currentCalibValid()) { - fSlope2 = getCalibParameter("COEFF3").toDouble(); - fOffs2 = getCalibParameter("COEFF2").toDouble(); - } - updateCalibTable(); - QVector emptyList; - emit updatedCalib(emptyList); -} - -void CalibForm::updateCalibTable() -{ - ui->calibItemTableWidget->setRowCount(fCalibList.size()); - for (int i=0; isetSizeHint(QSize(90,20)); - ui->calibItemTableWidget->setItem(i, 0, newItem1); - QString type = QString::fromStdString(fCalibList[i].type); - QString numberstr = ""; - if (type=="FLOAT") { - double val = QString::fromStdString(fCalibList[i].value).toDouble(nullptr); - numberstr = QString::number(val); - } else { - numberstr = QString::fromStdString(fCalibList[i].value); - } - - QTableWidgetItem *newItem2 = new QTableWidgetItem(type); - newItem2->setSizeHint(QSize(60,20)); - ui->calibItemTableWidget->setItem(i, 1, newItem2); - QTableWidgetItem *newItem3 = new QTableWidgetItem(numberstr); - newItem3->setSizeHint(QSize(60,20)); - ui->calibItemTableWidget->setItem(i, 2, newItem3); - QTableWidgetItem *newItem4 = new QTableWidgetItem("0x"+QString("%1").arg(fCalibList[i].address, 2, 16, QChar('0'))); - newItem4->setSizeHint(QSize(40,20)); - ui->calibItemTableWidget->setItem(i, 3, newItem4); - } - ui->calibItemTableWidget->resizeColumnsToContents(); - ui->calibItemTableWidget->resizeRowsToContents(); -} - - -void CalibForm::onAdcSampleReceived(uint8_t channel, float value) -{ - calScan->onAdcSampleReceived(channel, value); -} - -void CalibForm::on_readCalibPushButton_clicked() -{ - // calib reread triggered - emit calibRequest(); -} - - -void CalibForm::on_writeEepromPushButton_clicked() -{ - // write eeprom clicked - emit updatedCalib(fCalibList); - emit writeCalibToEeprom(); -} - - -void CalibForm::on_doBiasCalibPushButton_clicked() -{ -/* - // let's go - if (fCalibRunning) { - fCalibRunning=false; - ui->doBiasCalibPushButton->setText("Start"); - return; - } - fCalibRunning=true; - ui->doBiasCalibPushButton->setText("Stop"); - fPoints1.clear(); - fPoints2.clear(); - fPoints3.clear(); - fCurrBias=calVoltMin; - emit setBiasDacVoltage(fCurrBias); -*/ -} - -void CalibForm::doFit() -{ -/* - - QVector goodPoints1,goodPoints2, goodPoints3; - - ui->fitTextEdit->clear(); - - std::copy_if(fPoints1.begin(), fPoints1.end(), std::back_inserter(goodPoints1), [](const QPointF& p) - { return p.y()<26. && p.y()>7.0; } ); - - bool ok=calcLinearCoefficients(goodPoints1,&fOffs1,&fSlope1); - if (!ok) return; - QVector vec; - QPointF p1,p2; - p1.rx()=0.; - p1.ry()=fOffs1; - p2.rx()=2.2; - p2.ry()=fOffs1+2.2*fSlope1; - vec.push_back(p1); - vec.push_back(p2); - ui->biasVoltageCalibPlot->curve("Fit1").setSamples(vec); - ui->biasVoltageCalibPlot->replot(); - ui->fitTextEdit->append("fit voltage: c0="+QString::number(fOffs1)+", c1="+QString::number(fSlope1)); - - // here, we have 2 fits successfully applied. Now we can use the fit fuctions - // V1=Slope1*VADC1+Offs1 - // V2=Slope2*VADC2+Offs2 - // VADC,Diff=VADC1-VADC2 - // VDiff,corr = VDiff * (func1-func2) - - ui->biasVoltageCalibPlot->replot(); - - std::copy_if(fPoints3.begin(), fPoints3.end(), std::back_inserter(goodPoints3), [](const QPointF& p) - { return p.x()<25. && p.x()>7.0; } ); -// double currOffs, currSlope; - ok=calcLinearCoefficients(goodPoints3,&fOffs2,&fSlope2); - if (!ok) return; - vec.clear(); - p1.rx()=0.; - p1.ry()=fOffs2; - p2.rx()=40.; - p2.ry()=fOffs2+40.0*fSlope2; - vec.push_back(p1); - vec.push_back(p2); - ui->biasCurrentCalibPlot->curve("Fit").setSamples(vec); - ui->fitTextEdit->append("fit current: c0="+QString::number(fOffs2)+", c1="+QString::number(fSlope2)); - - ui->biasCurrentCalibPlot->replot(); - ui->transferBiasCoeffsPushButton->setEnabled(true); -*/ -} - -void CalibForm::on_transferBiasCoeffsPushButton_clicked() -{ -/* - // transfer to calib - if (ui->transferBiasCoeffsPushButton->isEnabled()) { - QVector items; - QString str=QString::number(fOffs1); - if (str.size()) { - setCalibParameter("COEFF0",str); - items.push_back(getCalibItem("COEFF0")); - } - str=QString::number(fSlope1); - if (str.size()) { - setCalibParameter("COEFF1",str); - items.push_back(getCalibItem("COEFF1")); - } - str=QString::number(fOffs2); - if (str.size()) { - setCalibParameter("COEFF2",str); - items.push_back(getCalibItem("COEFF2")); - } - str=QString::number(fSlope2); - if (str.size()) { - setCalibParameter("COEFF3",str); - items.push_back(getCalibItem("COEFF3")); - } - uint8_t flags=getCalibParameter("CALIB_FLAGS").toUInt(); - flags |= CalibStruct::CALIBFLAGS_VOLTAGE_COEFFS | CalibStruct::CALIBFLAGS_CURRENT_COEFFS; - setCalibParameter("CALIB_FLAGS",QString::number(flags)); - items.push_back(getCalibItem("CALIB_FLAGS")); - updateCalibTable(); - emit updatedCalib(items); - } -*/ -} - -void CalibForm::setCalibParameter(const QString &name, const QString &value) -{ - if (!fCalibList.empty()) { - auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); - if (result != fCalibList.end()) { - result->value=value.toStdString(); - } - } -} - -QString CalibForm::getCalibParameter(const QString &name) -{ - if (!fCalibList.empty()) { - auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); - if (result != fCalibList.end()) { - return QString::fromStdString(result->value); - } - } - return ""; -} - -const CalibStruct& CalibForm::getCalibItem(const QString &name) -{ - - if (!fCalibList.empty()) { - QVector::iterator result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); - if (result != fCalibList.end()) { - return *result; - } - } - return invalidCalibItem; -} - -bool CalibForm::voltageCalibValid() -{ - // - int calibFlags = getCalibParameter("CALIB_FLAGS").toUInt(); - if (calibFlags & CalibStruct::CALIBFLAGS_VOLTAGE_COEFFS) return true; - return false; -} - -bool CalibForm::currentCalibValid() -{ - // - int calibFlags = getCalibParameter("CALIB_FLAGS").toUInt(); - if (calibFlags & CalibStruct::CALIBFLAGS_CURRENT_COEFFS) return true; - return false; -} - -void CalibForm::onUiEnabledStateChange(bool connected) -{ - //measureBiasCalibGroupBox - if (!connected) { - ui->calibItemTableWidget->setRowCount(0); - fCalibList.clear(); - ui->eepromValidLabel->setText("N/A"); - ui->calibValidLabel->setText("N/A"); - ui->idLineEdit->setText("N/A"); - } - //ui->measureBiasCalibGroupBox->setEnabled(connected); - //ui->biasCalibGroupBox->setEnabled(connected); - ui->calibItemsGroupBox->setEnabled(connected); - ui->eepromGroupBox->setEnabled(connected); - ui->calibrationScanPushButton->setEnabled(connected); - //ui->currentCalibGroupBox->setEnabled(connected); -} - - -void CalibForm::on_calibItemTableWidget_cellChanged(int row, int column) -{ - // - if (column==2) { - QString name=ui->calibItemTableWidget->item(row,0)->text(); - QString valstr=ui->calibItemTableWidget->item(row,2)->text(); - if (valstr=="") { updateCalibTable(); return; } - bool ok=false; - valstr.toDouble(&ok); - if (!ok) { updateCalibTable(); return; } - setCalibParameter(name,valstr); - QVector items; - items.push_back(getCalibItem(name)); - emit updatedCalib(items); - } -} - diff --git a/source/gui/src/calibscandialog.cpp b/source/gui/src/calibscandialog.cpp deleted file mode 100644 index 1a4176d6..00000000 --- a/source/gui/src/calibscandialog.cpp +++ /dev/null @@ -1,260 +0,0 @@ -#include "calibscandialog.h" -#include "ui_calibscandialog.h" -#include -#include -#include -#include - -#define calVoltMin 0.3 -#define calVoltMax 2.5 - -#define BIAS_SCAN_INCREMENT 0.025 // scan step in Volts - -inline static double sqr(double x) { - return x*x; -} - -/* - linear regression algorithm - taken from: - http://stackoverflow.com/questions/5083465/fast-efficient-least-squares-fit-algorithm-in-c - parameters: - n = number of data points - xarray,yarray = arrays of data - *offs = output intercept - *slope = output slope - */ -bool calcLinearCoefficients( const QVector& points, - /*int n, double *xarray, double *yarray, - */double *offs, double* slope) -{ - int n=points.size(); - if (n<3) return false; - - double sumx = 0.0; /* sum of x */ - double sumx2 = 0.0; /* sum of x**2 */ - double sumxy = 0.0; /* sum of x * y */ - double sumy = 0.0; /* sum of y */ - double sumy2 = 0.0; /* sum of y**2 */ - -// int ix=0; -// double offsx=xarray[ix]; -// double offsy=yarray[ix]; - double offsx=0; - double offsy=0; -// long long int offsy=0; - - for (int i=0; i::epsilon()) { - // singular matrix. can't solve the problem. - *slope = 0; - *offs = 0; -// if (r) *r = 0; - return false; - } - - double m = (n * sumxy - sumx * sumy) / denom; - double b = (sumy * sumx2 - sumx * sumxy) / denom; - - *slope=m; - *offs=b+offsy; - return true; -// *offs=b; -// printf("offsI=%lld offsF=%f\n", offsy, b); - -} - - -CalibScanDialog::CalibScanDialog(QWidget *parent) : - QDialog(parent), - ui(new Ui::CalibScanDialog) -{ - ui->setupUi(this); - connect(ui->startCurrentCalibPushButton, &QPushButton::clicked, this, &CalibScanDialog::startManualCurrentCalib); - connect(ui->transferCurrentBiasPushButton, &QPushButton::clicked, this, &CalibScanDialog::transferCurrentCalibCoeffs); - ui->transferCurrentBiasPushButton->setEnabled(false); - ui->currentCalibProgressBar->setEnabled(false); - ui->currentCalibProgressBar->setMaximum(5); -} - -CalibScanDialog::~CalibScanDialog() -{ - delete ui; -} - -void CalibScanDialog::onCalibReceived(bool /*valid*/, bool eepromValid, quint64 /*id*/, const QVector &calibList) -{ - if (!eepromValid) return; - - fCalibList.clear(); - for (int i=0; i=2) { - QString result = getCalibParameter("VDIV"); - if (result!="") { - double vdiv = result.toDouble(nullptr); - ubias = vdiv*value*0.01; - } - } - if (channel == 3) { - double vdiv=getCalibParameter("VDIV").toDouble()*0.01; - double rsense = getCalibParameter("RSENSE").toDouble()*0.1*0.001; // RSense in MOhm - double ibias=vdiv*(fLastRSenseHiVoltage-value)/rsense; - if (fCurrentCalibRunning) manualCurrentCalibProgress(ubias, ibias); -/* - if (fAutoCalibRunning) { - if (fCurrBias>calVoltMax) { on_doBiasCalibPushButton_clicked(); return; } - QPointF p(fCurrBias, ubias); - fCurrBias+=BIAS_SCAN_INCREMENT; - emit setBiasDacVoltage(fCurrBias); - QThread::msleep(100); - fPoints2.push_back(p); - ui->biasVoltageCalibPlot->curve("curve2").setSamples(fPoints2); - - double vdiv=getCalibParameter("VDIV").toDouble()*0.01; - double rsense = getCalibParameter("RSENSE").toDouble()*0.1/1000.; // RSense in MOhm - QPointF p2(ubias,vdiv*(fLastRSenseHiVoltage-value)/rsense); - fPoints3.push_back(p2); - ui->biasCurrentCalibPlot->curve("curve3").setSamples(fPoints3); - - ui->biasVoltageCalibPlot->replot(); - ui->biasCurrentCalibPlot->replot(); - } -*/ - fLastRSenseLoVoltage = value; - } else if (channel == 2) { -/* - if (fAutoCalibRunning) { - QPointF p(fCurrBias, ubias); - fPoints1.push_back(p); - ui->biasVoltageCalibPlot->curve("curve1").setSamples(fPoints1); - ui->biasVoltageCalibPlot->replot(); - doFit(); - } -*/ - fLastRSenseHiVoltage = value; - } -} - -void CalibScanDialog::startManualCurrentCalib() { - if (fCurrentCalibRunning) { fCurrentCalibRunning=0; return; } - fCurrentCalibRunning=1; - ui->currentCalibProgressBar->setEnabled(true); - ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); - QMessageBox msgBox; - msgBox.setText("Disconnect the bias voltage"); - msgBox.setInformativeText("Disconnect the cable at the bias connector of the MuonPi PCB!"); - msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Ok); - int ret = msgBox.exec(); - if (ret == QMessageBox::Cancel) { - fCurrentCalibRunning=0; - ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); - ui->currentCalibProgressBar->setEnabled(false); - return; - } - fCurrentCalibRunning=2; - emit dynamic_cast(parent())->setBiasSwitch(false); - QThread::msleep(500); -} - -void CalibScanDialog::manualCurrentCalibProgress(double vbias, double ibias) { -/* const int N=5; - static int measurementCount=0;*/ - static double currentMeasurements[3] = { 0., 0., 0. }; - - ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); - if (fCurrentCalibRunning==2) { - //emit dynamic_cast(parent())->setBiasSwitch(true); - currentMeasurements[0]=ibias; - emit dynamic_cast(parent())->setBiasSwitch(true); - QThread::msleep(500); - fCurrentCalibRunning++; - } else - if (fCurrentCalibRunning==3) { - currentMeasurements[1]=ibias; - fCurrentCalibRunning++; - QMessageBox msgBox; - msgBox.setText("Reconnect the bias voltage"); - msgBox.setInformativeText("Connect the cable again to the bias connector of the MuonPi PCB!"); - msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); - msgBox.setDefaultButton(QMessageBox::Ok); - int ret = msgBox.exec(); - if (ret == QMessageBox::Cancel) { - fCurrentCalibRunning=0; - ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); - ui->currentCalibProgressBar->setEnabled(false); - return; - } - //emit dynamic_cast(parent())->setBiasSwitch(true); - QThread::msleep(500); - fCurrentCalibRunning++; - } else if (fCurrentCalibRunning==5) { - currentMeasurements[2]=ibias; - fCurrentCalibRunning=0; - fOffs2=currentMeasurements[0]; - fSlope2=(currentMeasurements[1]-currentMeasurements[2])/vbias; - ui->currentCalibOffsetLineEdit->setText(QString::number(fOffs2,'g',4)); - ui->currentCalibSlopeLineEdit->setText(QString::number(fSlope2,'g',4)); - ui->transferCurrentBiasPushButton->setEnabled(true); - ui->currentCalibProgressBar->setValue(fCurrentCalibRunning); - ui->currentCalibProgressBar->setEnabled(false); - } -} - -void CalibScanDialog::transferCurrentCalibCoeffs() { - emit dynamic_cast(parent())->setCalibParameter("COEFF2", QString::number(fOffs2)); - emit dynamic_cast(parent())->setCalibParameter("COEFF3", QString::number(fSlope2)); - uint8_t flags=getCalibParameter("CALIB_FLAGS").toUInt(); - flags |= CalibStruct::CalibStruct::CALIBFLAGS_CURRENT_COEFFS; - emit dynamic_cast(parent())->setCalibParameter("CALIB_FLAGS",QString::number(flags)); - emit dynamic_cast(parent())->updateCalibTable(); - ui->transferCurrentBiasPushButton->setEnabled(false); -} - -void CalibScanDialog::setCalibParameter(const QString &name, const QString &value) -{ - if (!fCalibList.empty()) { - auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); - if (result != fCalibList.end()) { - result->value=value.toStdString(); - } - } -} - -QString CalibScanDialog::getCalibParameter(const QString &name) -{ - if (!fCalibList.empty()) { - auto result = std::find_if(fCalibList.begin(), fCalibList.end(), [&name](const CalibStruct& s){ return s.name==name.toStdString(); } ); - if (result != fCalibList.end()) { - return QString::fromStdString(result->value); - } - } - return ""; -} diff --git a/source/gui/src/custom_histogram_widget.cpp b/source/gui/src/custom_histogram_widget.cpp deleted file mode 100644 index 60035380..00000000 --- a/source/gui/src/custom_histogram_widget.cpp +++ /dev/null @@ -1,243 +0,0 @@ -#include -#include -#include -//#include -#include -#include -#include -#include -#include -#include - -#include "custom_histogram_widget.h" - -typedef std::numeric_limits dbl; - -CustomHistogram::~CustomHistogram(){ - if (grid!=nullptr) { delete grid; grid=nullptr;} - if (fBarChart!=nullptr) { delete fBarChart; fBarChart=nullptr;} -} - -void CustomHistogram::initialize(){ - setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - setStyleSheet("background-color: white; border: 0px;"); - setAutoReplot(true); - enableAxis(QwtPlot::yLeft,true); - enableAxis(QwtPlot::yRight,false); - setAxisAutoScale(QwtPlot::xBottom,true); -// setAxisScaleEngine(QwtPlot::yLeft, new QwtLogScaleEngine()); - setAxisAutoScale(QwtPlot::yLeft,true); - //setAxisAutoScale(QwtPlot::yRight,true); - grid = new QwtPlotGrid(); - const QPen grayPen(Qt::gray); - grid->setPen(grayPen); - grid->attach(this); - fBarChart = new QwtPlotHistogram( title ); - //fBarChart = new QwtPlotBarChart( title ); - //fBarChart->setLayoutPolicy( QwtPlotBarChart::AutoAdjustSamples ); - //fBarChart->setSpacing( 0 ); - //fBarChart->setMargin( 3 ); - - fBarChart->setBrush(QBrush(Qt::darkBlue, Qt::SolidPattern)); - fBarChart->attach( this ); - - this->setContextMenuPolicy(Qt::CustomContextMenu); - connect(this,SIGNAL(customContextMenuRequested(const QPoint & )),this,SLOT(popUpMenu(const QPoint &))); - - replot(); - show(); -} - -void CustomHistogram::setData(const Histogram &hist) -{ - fName = hist.getName(); - fUnit = hist.getUnit(); - fNrBins = hist.getNrBins(); - fMin=hist.getMin(); - fMax=hist.getMax(); - fUnderflow=hist.getUnderflow(); - fOverflow=hist.getOverflow(); - fHistogramMap.clear(); - for (int i=0; isetLogY(checked); this->update(); } ); - contextMenu.addAction(&action1); - contextMenu.addSeparator(); - QAction action2("&Clear", this); -// connect(&action2, &QAction::triggered, this, &CustomHistogram::clear ); - connect(&action2, &QAction::triggered, this, [this](bool /*checked*/){ this->clear(); this->update(); }); - contextMenu.addAction(&action2); - - QAction action3("&Export", this); - connect(&action3, &QAction::triggered, this, &CustomHistogram::exportToFile ); - contextMenu.addAction(&action3); - - contextMenu.exec(mapToGlobal(pos)); -// contextMenu.popup(mapToGlobal(pos)); -} - -void CustomHistogram::exportToFile() { - QPixmap qPix = grab(); - if(qPix.isNull()){ - qDebug("Failed to capture the plot for saving"); - return; - } - QString types( "JPEG file (*.jpeg);;" // Set up the possible graphics formats - "Portable Network Graphics file (*.png);;" - "Bitmap file (*.bmp);;" - "Portable Document Format (*.pdf);;" - "Scalable Vector Graphics Format (*.svg);;" - "ASCII raw data (*.txt)"); - QString filter; // Type of filter - QString jpegExt=".jpeg", pngExt=".png", tifExt=".tif", bmpExt=".bmp", tif2Ext="tiff"; // Suffix for the files - QString pdfExt=".pdf", svgExt=".svg"; - QString txtExt=".txt"; - QString suggestedName=""; - QString fn = QFileDialog::getSaveFileName(this,tr("Export Histogram"), - suggestedName,types,&filter); - - if ( !fn.isEmpty() ) { // If filename is not null - if (fn.contains(jpegExt)) { // Remove file extension if already there - fn.remove(jpegExt); - } else if (fn.contains(pngExt)) { - fn.remove(pngExt); - } else if (fn.contains(bmpExt)) { - fn.remove(bmpExt); - } else if (fn.contains(pdfExt)) { - fn.remove(pdfExt); - } else if (fn.contains(svgExt)) { - fn.remove(svgExt); - } else if (fn.contains(txtExt)) { - fn.remove(txtExt); - } - - if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save - fn+=jpegExt; - qPix.save( fn, "JPEG" ); - } - else if (filter.contains(pngExt)) { // OR, Test to see if png and save - fn+=pngExt; - qPix.save( fn, "PNG" ); - } - else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save - fn+=bmpExt; - qPix.save( fn, "BMP" ); - } - else if (filter.contains(pdfExt)) { - fn+=pdfExt; - QwtPlotRenderer renderer(this); - renderer.renderDocument(this, fn, "pdf", QSizeF(297/2,210/2),72); - } - else if (filter.contains(svgExt)) { - fn+=svgExt; - QwtPlotRenderer renderer(this); - renderer.renderDocument(this, fn, "svg", QSizeF(297/2,210/2),72); - } - if (filter.contains(txtExt)) { - fn+=txtExt; - // export histo in asci raw data format - QFile file(fn); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) return; - QTextStream out(&file); - - for (int i=0; idetach(); QwtPlot::replot(); return; } - fBarChart->attach(this); - QVector intervals; - double rangeX=fMax-fMin; - double xBinSize = rangeX/(fNrBins-1); - double max=0; - for (int i=0; imax) max=fHistogramMap[i]; - double xval=bin2Value(i); - QwtIntervalSample interval(fHistogramMap[i]+1e-12, xval-xBinSize/2., xval+xBinSize/2.); - intervals.push_back(interval); - } - if (intervals.size() && fBarChart != nullptr) fBarChart->setSamples(intervals); - if (fLogY) { - setAxisScale(QwtPlot::yLeft,0.1, 1.5*max); - } - replot(); -} - -void CustomHistogram::clear() -{ -// fHistogramMap.clear(); -// fOverflow=fUnderflow=0; - Histogram::clear(); - emit histogramCleared(QString::fromStdString(fName)); - fName="defaultHisto"; - update(); -} - -void CustomHistogram::setStatusEnabled(bool status){ - if (status==true){ - const QPen blackPen(Qt::black); - grid->setPen(blackPen); - fBarChart->attach(this); - setTitle(title); - update(); - }else{ - const QPen grayPen(Qt::gray); - grid->setPen(grayPen); - fBarChart->detach(); - setTitle(""); - update(); - } -} - -void CustomHistogram::setLogY(bool logscale){ - if (logscale) { -#if QWT_VERSION > 0x060100 - setAxisScaleEngine(QwtPlot::yLeft, new QwtLogScaleEngine()); -#else - setAxisScaleEngine(QwtPlot::yLeft, new QwtLog10ScaleEngine()); -#endif - setAxisAutoScale(QwtPlot::yLeft,false); - fBarChart->setBaseline(1e-12); - fLogY=true; - } else { - setAxisScaleEngine(QwtPlot::yLeft, new QwtLinearScaleEngine()); - setAxisAutoScale(QwtPlot::yLeft,true); - fBarChart->setBaseline(0); - fLogY=false; - } -} - -void CustomHistogram::setXMin(double val) -{ - fMin = val; - rescalePlot(); -} - -void CustomHistogram::setXMax(double val) -{ - fMax = val; - rescalePlot(); -} - -void CustomHistogram::rescalePlot() -{ - double margin = 0.05*(fMax - fMin); - setAxisScale(QwtPlot::xBottom,fMin-margin, fMax+margin); -} diff --git a/source/gui/src/custom_plot_widget.cpp b/source/gui/src/custom_plot_widget.cpp deleted file mode 100644 index 8f946c65..00000000 --- a/source/gui/src/custom_plot_widget.cpp +++ /dev/null @@ -1,229 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include - -#define LOG_BASELINE 0.1 - -QwtPlotCurve CustomPlot::INVALID_CURVE; - -CustomPlot::~CustomPlot(){ - for (auto it=fCurveMap.begin(); it!=fCurveMap.end(); ++it) { - if (*it!=nullptr) delete *it; - } - if (grid!=nullptr) { delete grid; grid=nullptr;} -} - -void CustomPlot::initialize(){ - setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - setStyleSheet("background-color: white; border: 0px;"); - setAutoReplot(false); - enableAxis(QwtPlot::yLeft,true); - //enableAxis(QwtPlot::yRight,true); - setAxisAutoScale(QwtPlot::xBottom,true); - setAxisAutoScale(QwtPlot::yRight,true); - - grid = new QwtPlotGrid(); - const QPen blackPen(Qt::black); - grid->setPen(blackPen); - grid->attach(this); - - this->setContextMenuPolicy(Qt::CustomContextMenu); - connect(this,SIGNAL(customContextMenuRequested(const QPoint & )),this,SLOT(popUpMenu(const QPoint &))); - - show(); -} - -QwtPlotCurve& CustomPlot::curve(const QString& curveName) -{ - auto it = fCurveMap.find(curveName); - if (it!=fCurveMap.end()) return **it; - return INVALID_CURVE; -} - - -void CustomPlot::addCurve(const QString& name, const QColor& curveColor) -{ - QwtPlotCurve *curve = new QwtPlotCurve(); - curve->setYAxis(QwtPlot::yLeft); - curve->setRenderHint(QwtPlotCurve::RenderAntialiased, true); - //curve->setStyle(QwtPlotCurve::Steps); - //QColor curveColor = Qt::darkGreen; - //curveColor.setAlphaF(0.3); - const QPen pen(curveColor); - curve->setPen(pen); - //curve->setBrush(curveColor); - fCurveMap[name]=curve; - fCurveMap[name]->attach(this); -} - -void CustomPlot::popUpMenu(const QPoint & pos) -{ - QMenu contextMenu(tr("Context menu"), this); - - QAction action1("&Log Y", this); - action1.setCheckable(true); - action1.setChecked(getLogY()); - connect(&action1, &QAction::toggled, this, [this](bool checked){ this->setLogY(checked); this->replot(); } ); - contextMenu.addAction(&action1); - contextMenu.addSeparator(); -/* - QAction action2("&Clear", this); -// connect(&action2, &QAction::triggered, this, &CustomHistogram::clear ); - connect(&action2, &QAction::triggered, this, [this](bool checked){ this->clear(); this->replot(); }); - contextMenu.addAction(&action2); -*/ - QAction action3("&Export", this); - connect(&action3, &QAction::triggered, this, &CustomPlot::exportToFile ); - contextMenu.addAction(&action3); - - contextMenu.exec(mapToGlobal(pos)); -// contextMenu.popup(mapToGlobal(pos)); -} - -void CustomPlot::rescale() { -// bool succ=false; - double ymin=1e30; - double ymax=-1e30; - double xmin=1e30; - double xmax=-1e30; - - for (auto it=fCurveMap.begin(); it!=fCurveMap.end(); ++it) { - if ((*it)->dataSize()) { - if (xmin>(*it)->minXValue()) xmin=(*it)->minXValue(); - if (xmax<(*it)->maxXValue()) xmax=(*it)->maxXValue(); - if (ymin>(*it)->minYValue()) ymin=(*it)->minYValue(); - if (ymax<(*it)->maxYValue()) ymax=(*it)->maxYValue(); -// succ=true; - } - } - - if (fLogY) { - if (this->axisInterval(QwtPlot::yLeft).minValue()<=0.) { - } - if (this->axisAutoScale(QwtPlot::yLeft)) { - } else { - - } - } else { - - } - -} - -void CustomPlot::setLogY(bool logscale){ - if (logscale) { - if (this->axisInterval(QwtPlot::yLeft).minValue()<=0.) { - this->setAxisScale(QwtPlot::yLeft, LOG_BASELINE, axisInterval(QwtPlot::yLeft).maxValue()); - } -#if QWT_VERSION > 0x060100 - setAxisScaleEngine(QwtPlot::yLeft, new QwtLogScaleEngine()); -#else - setAxisScaleEngine(QwtPlot::yLeft, new QwtLog10ScaleEngine()); -#endif - setAxisAutoScale(QwtPlot::yLeft,true); - //fBarChart->setBaseline(1e-12); - fLogY=true; - } else { - setAxisScaleEngine(QwtPlot::yLeft, new QwtLinearScaleEngine()); - setAxisAutoScale(QwtPlot::yLeft,true); - //fBarChart->setBaseline(0); - fLogY=false; - } - emit scalingChanged(); -} - - -void CustomPlot::setStatusEnabled(bool status){ - if (status==true){ -// curve->attach(this); - //setTitle(title); - replot(); - }else{ -// curve->detach(); - //setTitle(""); - replot(); - } -} - - -void CustomPlot::exportToFile() { - QPixmap qPix = grab(); - if(qPix.isNull()){ - qDebug("Failed to capture the plot for saving"); - return; - } - QString types( "JPEG file (*.jpeg);;" // Set up the possible graphics formats - "Portable Network Graphics file (*.png);;" - "Bitmap file (*.bmp);;" - "Portable Document Format (*.pdf);;" - "Scalable Vector Graphics Format (*.svg);;" - "ASCII raw data (*.txt)"); - QString filter; // Type of filter - QString jpegExt=".jpeg", pngExt=".png", tifExt=".tif", bmpExt=".bmp", tif2Ext="tiff"; // Suffix for the files - QString pdfExt=".pdf", svgExt=".svg"; - QString txtExt=".txt"; - QString suggestedName=""; - QString fn = QFileDialog::getSaveFileName(this,tr("Export Plot"), - suggestedName,types,&filter); - - if ( !fn.isEmpty() ) { // If filename is not null - if (fn.contains(jpegExt)) { // Remove file extension if already there - fn.remove(jpegExt); - } else if (fn.contains(pngExt)) { - fn.remove(pngExt); - } else if (fn.contains(bmpExt)) { - fn.remove(bmpExt); - } else if (fn.contains(pdfExt)) { - fn.remove(pdfExt); - } else if (fn.contains(svgExt)) { - fn.remove(svgExt); - } else if (fn.contains(txtExt)) { - fn.remove(txtExt); - } - - if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save - fn+=jpegExt; - qPix.save( fn, "JPEG" ); - } - else if (filter.contains(pngExt)) { // OR, Test to see if png and save - fn+=pngExt; - qPix.save( fn, "PNG" ); - } - else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save - fn+=bmpExt; - qPix.save( fn, "BMP" ); - } - else if (filter.contains(pdfExt)) { - fn+=pdfExt; - QwtPlotRenderer renderer(this); - renderer.renderDocument(this, fn, "pdf", QSizeF(297/2,210/2),72); - } - else if (filter.contains(svgExt)) { - fn+=svgExt; - QwtPlotRenderer renderer(this); - renderer.renderDocument(this, fn, "svg", QSizeF(297/2,210/2),72); - } else if (filter.contains(txtExt)) { - fn+=txtExt; - // export histo in asci raw data format - QFile file(fn); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) return; - QTextStream out(&file); - //out.setFieldWidth(20); - - foreach (QwtPlotCurve *curve , fCurveMap) { - out << "# " << this->title().text() << "\n"; - out << "# " << curve->title().text() << "\n"; - out << "# " << this->axisTitle(QwtPlot::xBottom).text() << " " << this->axisTitle(QwtPlot::yLeft).text() << "\n"; - for (size_t i=0; i < curve->dataSize(); i++) { - out << QString::number(curve->sample(static_cast(i)).x(),'g',10) << " " << QString::number(curve->sample(static_cast(i)).y(), 'g', 10) << "\n"; - } - } - } - } -} diff --git a/source/gui/src/gnssposwidget.cpp b/source/gui/src/gnssposwidget.cpp deleted file mode 100644 index 2230ef82..00000000 --- a/source/gui/src/gnssposwidget.cpp +++ /dev/null @@ -1,510 +0,0 @@ -#include "gnssposwidget.h" -#include "ui_gnssposwidget.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#define _USE_MATH_DEFINES -#include - -using namespace std; - -namespace Detail -{ - double constexpr sqrtNewtonRaphson(double x, double curr, double prev) - { - return curr == prev - ? curr - : sqrtNewtonRaphson(x, 0.5 * (curr + x / curr), curr); - } - double constexpr sqrt(double x) - { - return x >= 0 && x < std::numeric_limits::infinity() - ? Detail::sqrtNewtonRaphson(x, x, 0) - : std::numeric_limits::quiet_NaN(); - } -} -constexpr double pi() { return M_PI; } -constexpr double sqrt2() {return Detail::sqrt(2.); } - -const int MAX_SAT_TRACK_ENTRIES = 1000; - -static const QList GNSS_COLORS = { Qt::darkGreen, Qt::darkYellow, Qt::blue, Qt::magenta, Qt::gray, Qt::cyan, Qt::red, Qt::black }; - -int GnssPosWidget::alphaFromCnr(int cnr) { -// int alpha=cnr*255/cnrColorRange; - int alpha=cnr*255/ui->cnrRangeSpinBox->value(); - if (alpha>255) alpha=255; - return alpha; -} - -GnssPosWidget::GnssPosWidget(QWidget *parent) : - QWidget(parent), - ui(new Ui::GnssPosWidget) -{ - ui->setupUi(this); - ui->satLabel->setText(QString::number(ui->satLabel->width())+"x"+QString::number(ui->satLabel->height())); - connect(ui->receivedSatsCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); - connect(ui->satLabelsCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); - connect(ui->tracksCheckBox, &QCheckBox::toggled, this, &GnssPosWidget::replot); - this->setContextMenuPolicy(Qt::CustomContextMenu); - connect(this,SIGNAL(customContextMenuRequested(const QPoint & )),this,SLOT(popUpMenu(const QPoint &))); - connect(ui->cartPolarCheckBox, &QCheckBox::toggled, this, [this](bool /*checked*/) { resizeEvent(nullptr); } ); - connect(ui->cnrRangeSpinBox, static_cast(&QSpinBox::valueChanged), this, [this](int) { replot(); } ); -} - -GnssPosWidget::~GnssPosWidget() -{ - delete ui; -} - -void GnssPosWidget::resizeEvent(QResizeEvent* /*event*/) -{ - int w=ui->hostWidget->width(); - int h=ui->hostWidget->height(); - if (ui->cartPolarCheckBox->isChecked()) { - if (hsatLabel->resize(w,h); - - replot(); - //ui->satLabel->setText(QString::number(ui->satLabel->width())+"x"+QString::number(ui->satLabel->height())); -} - - -QPolygonF GnssPosWidget::getPolarUnitPolygon(const QPointF& pos, int controlPoints) { - const double step=1./(controlPoints+1); - QPolygonF path; - QPointF p(pos+QPointF(-0.5,-0.5)); - for (int side=0; side<4; side++){ - for (int i=0; i=90.) return QPointF(0.,0.); - double magn=(90.-pol.y())/180.; - double xpos = magn*sin(pi()*pol.x()/180.); - double ypos = -magn*cos(pi()*pol.x()/180.); - return QPointF(xpos,ypos); -} - -void GnssPosWidget::drawPolarPixMap(QPixmap& pm) { - - QVector newlist; - QString str; - QColor color; - - const int satPosPixmapSize = pm.width(); - const QPointF originOffset(satPosPixmapSize/2., satPosPixmapSize/2.); - - // pixmap.fill(QColor("transparent")); - pm.fill(Qt::white); - QPainter satPosPainter(&pm); - satPosPainter.setPen(QPen(Qt::black)); - satPosPainter.drawEllipse(QPoint(satPosPixmapSize/2,satPosPixmapSize/2),satPosPixmapSize/6,satPosPixmapSize/6); - satPosPainter.drawEllipse(QPoint(satPosPixmapSize/2,satPosPixmapSize/2),satPosPixmapSize/3,satPosPixmapSize/3); - satPosPainter.drawEllipse(QPoint(satPosPixmapSize/2,satPosPixmapSize/2),satPosPixmapSize/2,satPosPixmapSize/2); - satPosPainter.drawLine(QPoint(satPosPixmapSize/2,0),QPoint(satPosPixmapSize/2,satPosPixmapSize)); - satPosPainter.drawLine(QPoint(0,satPosPixmapSize/2),QPoint(satPosPixmapSize,satPosPixmapSize/2)); - satPosPainter.drawText(satPosPixmapSize/2+2,3,18,18,Qt::AlignHCenter,"N"); - satPosPainter.drawText(satPosPixmapSize/2+2,satPosPixmapSize-19,18,18,Qt::AlignHCenter,"S"); - satPosPainter.drawText(4,satPosPixmapSize/2-19,18,18,Qt::AlignHCenter,"W"); - satPosPainter.drawText(satPosPixmapSize-19,satPosPixmapSize/2-19,18,18,Qt::AlignHCenter,"E"); - - QFont font = satPosPainter.font(); - font.setPointSize(font.pointSize()-2); - satPosPainter.setFont(font); - satPosPainter.drawText(satPosPixmapSize/2-14,satPosPixmapSize-12,18,18,Qt::AlignHCenter,"0°"); - satPosPainter.drawText(satPosPixmapSize/2-16,satPosPixmapSize*5/6-12,18,18,Qt::AlignHCenter,"30°"); - satPosPainter.drawText(satPosPixmapSize/2-16,satPosPixmapSize*2/3-12,18,18,Qt::AlignHCenter,"60°"); - - // set up coordinate transformation - QTransform trafo; -// trafo.translate(0.5,0.5); - trafo.translate(originOffset.x(),originOffset.y()); - trafo.scale(satPosPixmapSize,satPosPixmapSize); -// trafo.translate(originOffset.x(),originOffset.y()); - satPosPainter.setTransform(trafo); - - // draw the sat tracks first - if (ui->tracksCheckBox->isChecked()) { - for (const auto& pointMap : satTracks) { - for (const QVector &pointVector : pointMap) { - if (pointVector.size()==0) continue; - double cnr=0.; - SatHistoryPoint satPoint; - for (int i=0; ireceivedSatsCheckBox->isChecked()) { - if (fCurrentSatlist[i].fCnr>0) newlist.push_back(fCurrentSatlist[i]); - } else newlist.push_back(fCurrentSatlist[i]); - if (fCurrentSatlist[i].fElev<=90. && fCurrentSatlist[i].fElev>=-90.) { - if (ui->receivedSatsCheckBox->isChecked() && fCurrentSatlist[i].fCnr==0) continue; - QPointF currPos(fCurrentSatlist[i].fAzim, fCurrentSatlist[i].fElev); - QPointF currPoint = polar2cartUnity(currPos); - - QColor satColor=Qt::white; - QColor fillColor=Qt::white; - satColor = GNSS_COLORS[fCurrentSatlist[i].fGnssId]; - satPosPainter.setPen(satColor); - fillColor=satColor; - int alpha = alphaFromCnr(fCurrentSatlist[i].fCnr); - fillColor.setAlpha(alpha); - int satId = fCurrentSatlist[i].fGnssId*1000 + fCurrentSatlist[i].fSatId; -/* QPointF lastPoint(-2,-2); - int lastCnr = 255;*/ - if (fCurrentSatlist[i].fCnr>0) - { - SatHistoryPoint p; - p.posCart=currPoint; - p.color=fillColor; - p.posPolar=QPoint(currPos.x(), currPos.y()); - p.gnssId=fCurrentSatlist[i].fGnssId; - p.satId=fCurrentSatlist[i].fSatId; - p.cnr=fCurrentSatlist[i].fCnr; - p.time=QDateTime::currentDateTimeUtc(); - satTracks[satId][p.posPolar].push_back(p); - if (satTracks[satId][p.posPolar].size()>MAX_SAT_TRACK_ENTRIES) - satTracks[satId][p.posPolar].pop_front(); - } - satPosPainter.setPen(satColor); - satPosPainter.setBrush(fillColor); - - // somehow, drawEllipse doesn't work with a painter when a transform is set before (bug?) - // so reset the transform of the painter and do the scaling and shifting manually - satPosPainter.setTransform(QTransform()); - currPoint*=satPosPixmapSize; - currPoint+=originOffset; - - float satsize=ui->satSizeSpinBox->value(); -// qreal satsize=(qreal)ui->satSizeSpinBox->value()/1000.; - satPosPainter.drawEllipse(currPoint,satsize/2.,satsize/2.); -// if (fCurrentSatlist[i].fUsed) satPosPainter.drawEllipse(currPoint,satsize/2.+0.5,satsize/2.+0.5); - if (fCurrentSatlist[i].fUsed) satPosPainter.drawEllipse(currPoint,1.05*satsize/2.,1.05*satsize/2.); - currPoint.rx()+=satsize/2+4; - if (ui->satLabelsCheckBox->isChecked()) satPosPainter.drawText(currPoint, QString::number(fCurrentSatlist[i].fSatId)); - } - } -} - -void GnssPosWidget::drawCartesianPixMap(QPixmap& pm) { - - QVector newlist; - QString str; - QColor color; - - const QPointF originOffset(0., pm.height()*0.9); - - // pixmap.fill(QColor("transparent")); - pm.fill(Qt::white); - QPainter satPosPainter(&pm); - satPosPainter.setPen(QPen(Qt::black)); - satPosPainter.drawLine(originOffset,originOffset+QPointF(pm.width(),0)); - satPosPainter.drawLine(0.33*originOffset,0.33*originOffset+QPointF(pm.width(),0)); - satPosPainter.drawLine(0.67*originOffset,0.67*originOffset+QPointF(pm.width(),0)); - satPosPainter.drawLine(QPoint(pm.width()/2,0),originOffset+QPointF(pm.width()/2,0)); - - satPosPainter.drawText(pm.width()/2-3,originOffset.y()+6,18,18,Qt::AlignHCenter,"S"); - satPosPainter.drawText(2,originOffset.y()+6,18,18,Qt::AlignHCenter,"N"); - satPosPainter.drawText(pm.width()-18,originOffset.y()+6,18,18,Qt::AlignHCenter,"N"); - satPosPainter.drawText(pm.width()/4-3,originOffset.y()+6,18,18,Qt::AlignHCenter,"E"); - satPosPainter.drawText(3*pm.width()/4-3,originOffset.y()+6,18,18,Qt::AlignHCenter,"W"); - - QFont font = satPosPainter.font(); - font.setPointSize(font.pointSize()-2); - satPosPainter.setFont(font); - satPosPainter.drawText(pm.width()/2,originOffset.y()-10,18,18,Qt::AlignHCenter,"0°"); - satPosPainter.drawText(pm.width()/2,0.33*originOffset.y()+3,18,18,Qt::AlignHCenter,"60°"); - satPosPainter.drawText(pm.width()/2,0.67*originOffset.y()+3,18,18,Qt::AlignHCenter,"30°"); - - // draw the sat tracks first - if (ui->tracksCheckBox->isChecked()) { - for (const auto& pointMap : satTracks) { - for (const QVector &pointVector : pointMap) { - if (pointVector.size()==0) continue; - double cnr=0.; - SatHistoryPoint satPoint; - for (int i=0; ireceivedSatsCheckBox->isChecked()) { - if (fCurrentSatlist[i].fCnr>0) newlist.push_back(fCurrentSatlist[i]); - } else newlist.push_back(fCurrentSatlist[i]); - if (fCurrentSatlist[i].fElev<=90. && fCurrentSatlist[i].fElev>=-90.) { - if (ui->receivedSatsCheckBox->isChecked() && fCurrentSatlist[i].fCnr==0) continue; - QPointF currPos(fCurrentSatlist[i].fAzim, fCurrentSatlist[i].fElev); - QPointF currPoint = polar2cartUnity(currPos); - - QColor satColor=Qt::white; - QColor fillColor=Qt::white; - satColor = GNSS_COLORS[fCurrentSatlist[i].fGnssId]; - satPosPainter.setPen(satColor); - fillColor=satColor; - int alpha = alphaFromCnr(fCurrentSatlist[i].fCnr); - fillColor.setAlpha(alpha); - int satId = fCurrentSatlist[i].fGnssId*1000 + fCurrentSatlist[i].fSatId; - - if (fCurrentSatlist[i].fCnr>0) - { - SatHistoryPoint p; - p.posCart=currPoint; - p.color=fillColor; - p.posPolar=QPoint(currPos.x(), currPos.y()); - p.gnssId=fCurrentSatlist[i].fGnssId; - p.satId=fCurrentSatlist[i].fSatId; - p.cnr=fCurrentSatlist[i].fCnr; - p.time=QDateTime::currentDateTimeUtc(); - satTracks[satId][p.posPolar].push_back(p); - if (satTracks[satId][p.posPolar].size()>MAX_SAT_TRACK_ENTRIES) - satTracks[satId][p.posPolar].pop_front(); - - } - satPosPainter.setPen(satColor); - satPosPainter.setBrush(fillColor); - - currPos=QPointF(currPos.x()/360.*pm.width(), -currPos.y()/90.*pm.height()*0.9+pm.height()*0.9); - - float satsize=ui->satSizeSpinBox->value(); - satPosPainter.drawEllipse(currPos,satsize/2.,satsize/2.); - if (fCurrentSatlist[i].fUsed) satPosPainter.drawEllipse(currPos,satsize/2.+0.5,satsize/2.+0.5); - currPos.rx()+=satsize/2+4; - if (ui->satLabelsCheckBox->isChecked()) satPosPainter.drawText(currPos, QString::number(fCurrentSatlist[i].fSatId)); - } - } -} - -void GnssPosWidget::replot() { - - const int w=ui->satLabel->width(); - const int h=ui->satLabel->height(); - - QPixmap satPosPixmap(w,h); - if (ui->cartPolarCheckBox->isChecked()){ - drawPolarPixMap(satPosPixmap); - } else { - drawCartesianPixMap(satPosPixmap); - } - - ui->satLabel->setPixmap(satPosPixmap); -} - -void GnssPosWidget::onSatsReceived(const QVector &satlist) -{ - fCurrentSatlist = satlist; - replot(); -} - -void GnssPosWidget::on_satSizeSpinBox_valueChanged(int /*arg1*/) -{ - replot(); -} - -void GnssPosWidget::onUiEnabledStateChange(bool connected) -{ - if (!connected) { - QVector emptylist; -// onSatsReceived(emptylist); - fCurrentSatlist.clear(); - } - this->setEnabled(connected); - -} - -void GnssPosWidget::popUpMenu(const QPoint & pos) -{ - QMenu contextMenu(tr("Context menu"), this); - - QAction action2("&Clear Tracks", this); - connect(&action2, &QAction::triggered, this, [this](bool /*checked*/){ satTracks.clear() ; this->replot(); }); - contextMenu.addAction(&action2); - - contextMenu.addSeparator(); - - QAction action3("&Export", this); - connect(&action3, &QAction::triggered, this, &GnssPosWidget::exportToFile ); - contextMenu.addAction(&action3); - - contextMenu.exec(mapToGlobal(pos)); -} - -void GnssPosWidget::exportToFile() { - const int pixmapSize = 512; - QPixmap satPosPixmap; - if (ui->cartPolarCheckBox->isChecked()){ - satPosPixmap = QPixmap(pixmapSize, pixmapSize); - drawPolarPixMap(satPosPixmap); - } else { - satPosPixmap = QPixmap(sqrt2()*pixmapSize, pixmapSize); - drawCartesianPixMap(satPosPixmap); - } - - QString types( "JPEG file (*.jpeg);;" // Set up the possible graphics formats - "Portable Network Graphics file (*.png);;" - "Bitmap file (*.bmp);;" - "ASCII raw data (*.txt)"); - QString filter; // Type of filter - QString jpegExt=".jpeg", pngExt=".png", tifExt=".tif", bmpExt=".bmp", tif2Ext="tiff"; // Suffix for the files - QString txtExt=".txt"; - QString suggestedName=""; - QString fn = QFileDialog::getSaveFileName(this,tr("Export Pixmap"), - suggestedName,types,&filter); - - if ( !fn.isEmpty() ) { // If filename is not null - if (fn.contains(jpegExt)) { // Remove file extension if already there - fn.remove(jpegExt); - } else if (fn.contains(pngExt)) { - fn.remove(pngExt); - } else if (fn.contains(bmpExt)) { - fn.remove(bmpExt); - } else if (fn.contains(txtExt)) { - fn.remove(txtExt); - } - - if (filter.contains(jpegExt)) { // OR, Test to see if jpeg and save - fn+=jpegExt; - satPosPixmap.save( fn, "JPEG" ); - } - else if (filter.contains(pngExt)) { // OR, Test to see if png and save - fn+=pngExt; - satPosPixmap.save( fn, "PNG" ); - } - else if (filter.contains(bmpExt)) { // OR, Test to see if bmp and save - fn+=bmpExt; - satPosPixmap.save( fn, "BMP" ); - } - else if (filter.contains(txtExt)) { - fn+=txtExt; - // export sat history in asci raw data format - QFile file(fn); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) return; - QTextStream out(&file); - //out.setFieldWidth(20); - out<<"# GNSS sat history from xxx to yyy\n"; - out<<"# datetime marks the entrance time into space point (az,el)\n"; - out<<"# \n"; - - for (const auto& pointMap : satTracks) { - for (const QVector &pointVector : pointMap) { - if (pointVector.size()==0) continue; - double cnr=0.; - SatHistoryPoint p; - for (int i=0; i -#include "gpssatsform.h" -#include "ui_gpssatsform.h" -#include -#include -#include - -const int MAX_IQTRACK_BUFFER = 250; - - -//const QVector FIX_TYPE_STRINGS = { "No Fix", "Dead Reck." , "2D-Fix", "3D-Fix", "GPS+Dead Reck.", "Time Fix" }; -//const QString GNSS_ORBIT_SRC_STRING[] = { "N/A","Ephem","Alm","AOP","AOP+","Alt","Alt","Alt" }; - -// helper function to format human readable numbers with common suffixes (k(ilo), M(ega), m(illi) etc.) -QString printReadableFloat(double value, int prec=2, int lowOrderInhibit=-12, int highOrderInhibit=9) { - QString str=""; - QString suffix=""; - double order=std::log10(std::fabs(value)); - if (order>=lowOrderInhibit && order<=highOrderInhibit) { - if (order>=9) { value*=1e-9; suffix="G"; } - else if (order>=6) { value*=1e-6; suffix="M"; } - else if (order>=3) { value*=1e-3; suffix="k"; } - else if (order>=0) { suffix=""; } - //else if (order>-2) { value*=100.; suffix="c"; } - else if (order>=-3) { value*=1000.; suffix="m"; } - else if (order>=-6) { value*=1e6; suffix="u"; } - else if (order>=-9) { value*=1e9; suffix="n"; } - else if (order>=-12) { value*=1e12; suffix="p"; } - } - char fmtChar='f'; - double newOrder = std::log10(std::fabs(value)); - if (fabs(newOrder)>=3.) { fmtChar='g'; } - else { prec=prec-(int)newOrder - 1; } - if (prec<0) prec=0; - return QString::number(value,fmtChar,prec)+" "+suffix; -} - - -GpsSatsForm::GpsSatsForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::GpsSatsForm) -{ - ui->setupUi(this); - ui->satsTableWidget->resizeColumnsToContents(); - //ui->satsTableWidget->resizeRowsToContents(); -} - -GpsSatsForm::~GpsSatsForm() -{ - delete ui; -} - -void GpsSatsForm::onSatsReceived(const QVector &satlist) -{ - ui->gnssPosWidget->onSatsReceived(satlist); - - QVector newlist; - QString str; - QColor color; - - int nrGoodSats = 0; - for (auto it=satlist.begin(); it!=satlist.end(); it++) - if (it->fCnr>0) nrGoodSats++; - - ui->nrSatsLabel->setText(QString::number(nrGoodSats)+"/"+QString::number(satlist.size())); - - for (int i=0; ivisibleSatsCheckBox->isChecked()) { - if (satlist[i].fCnr>0) newlist.push_back(satlist[i]); - } else newlist.push_back(satlist[i]); - } - - int N=newlist.size(); - ui->satsTableWidget->setRowCount(N); - for (int i=0; isetSizeHint(QSize(25,24)); - ui->satsTableWidget->setItem(i, 0, newItem1); -// QTableWidgetItem *newItem2 = new QTableWidgetItem(QString::number(satlist[i].fGnssId)); - QTableWidgetItem *newItem2 = new QTableWidgetItem(GNSS_ID_STRING[newlist[i].fGnssId]); - newItem2->setSizeHint(QSize(50,24)); - ui->satsTableWidget->setItem(i, 1, newItem2); - QTableWidgetItem *newItem3 = new QTableWidgetItem(QString::number(newlist[i].fCnr)); - newItem3->setSizeHint(QSize(70,24)); - ui->satsTableWidget->setItem(i, 2, newItem3); - QTableWidgetItem *newItem4 = new QTableWidgetItem(QString::number(newlist[i].fAzim)); - newItem4->setSizeHint(QSize(100,24)); - ui->satsTableWidget->setItem(i, 3, newItem4); - QTableWidgetItem *newItem5 = new QTableWidgetItem(QString::number(newlist[i].fElev)); - newItem5->setSizeHint(QSize(100,24)); - ui->satsTableWidget->setItem(i, 4, newItem5); - QTableWidgetItem *newItem6 = new QTableWidgetItem(printReadableFloat(newlist[i].fPrRes,2,0)); - newItem6->setSizeHint(QSize(60,24)); - ui->satsTableWidget->setItem(i, 5, newItem6); - QTableWidgetItem *newItem7 = new QTableWidgetItem(QString::number(newlist[i].fQuality)); - color=Qt::green; - float transp=0.166*(newlist[i].fQuality-1); - if (transp<0.) transp=0.; - if (transp>1.) transp=1.; - color.setAlphaF(transp); - newItem7->setBackground(color); - - newItem7->setSizeHint(QSize(25,24)); - ui->satsTableWidget->setItem(i, 6, newItem7); - str="n/a"; - if (newlist[i].fHealth=2) { color=Qt::red; } - QTableWidgetItem *newItem8 = new QTableWidgetItem(str); - //newItem8->setBackgroundColor(color); - newItem8->setSizeHint(QSize(25,24)); - ui->satsTableWidget->setItem(i, 7, newItem8); - int orbSrc=newlist[i].fOrbitSource; - if (orbSrc<0) orbSrc=0; - if (orbSrc>7) orbSrc=7; - QTableWidgetItem *newItem9 = new QTableWidgetItem(GNSS_ORBIT_SRC_STRING[orbSrc]); - newItem9->setSizeHint(QSize(50,24)); - ui->satsTableWidget->setItem(i, 8, newItem9); - QTableWidgetItem *newItem10 = new QTableWidgetItem(); - newItem10->setCheckState(Qt::CheckState::Unchecked); - if (newlist[i].fUsed) newItem10->setCheckState(Qt::CheckState::Checked); - newItem10->setFlags(newItem10->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user - newItem10->setFlags(newItem10->flags() & (~Qt::ItemIsEditable)); - newItem10->setSizeHint(QSize(20,24)); - ui->satsTableWidget->setItem(i, 9, newItem10); - QTableWidgetItem *newItem11 = new QTableWidgetItem(); - newItem11->setCheckState(Qt::CheckState::Unchecked); - if (newlist[i].fDiffCorr) newItem11->setCheckState(Qt::CheckState::Checked); - newItem11->setFlags(newItem11->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user - newItem11->setFlags(newItem11->flags() & (~Qt::ItemIsEditable)); - newItem11->setSizeHint(QSize(20,24)); - ui->satsTableWidget->setItem(i, 10, newItem11); - /* - QTableWidgetItem *newItem12 = new QTableWidgetItem(); - newItem12->setCheckState(Qt::CheckState::Unchecked); - if (newlist[i].fSmoothed) newItem12->setCheckState(Qt::CheckState::Checked); - newItem12->setFlags(newItem12->flags() & (~Qt::ItemIsUserCheckable)); // disables checkbox edit from user - newItem12->setFlags(newItem12->flags() & (~Qt::ItemIsEditable)); - newItem12->setSizeHint(QSize(20,24)); - ui->satsTableWidget->setItem(i, 11, newItem12); - */ - } - //ui->satsTableWidget->resizeColumnsToContents(); - //ui->satsTableWidget->resizeRowsToContents(); -} - -void GpsSatsForm::onTimeAccReceived(quint32 acc) -{ - double tAcc=acc*1e-9; - ui->timePrecisionLabel->setText(printReadableFloat(tAcc)+"s"); - // ui->timePrecisionLabel->setText(QString::number(acc)+" ns"); -} - -void GpsSatsForm::onFreqAccReceived(quint32 acc) -{ - double fAcc=acc*1e-12; - ui->freqPrecisionLabel->setText(printReadableFloat(fAcc)+"s/s"); -} - -void GpsSatsForm::onIntCounterReceived(quint32 cnt) -{ - ui->intCounterLabel->setText(QString::number(cnt)); -} - -/* -void GpsSatsForm::onGpsMonHWReceived(quint16 noise, quint16 agc, quint8 antStatus, quint8 antPower, quint8 jamInd, quint8 flags) -{ - ui->lnaNoiseLabel->setText(QString::number(-noise)+" dBHz"); - ui->lnaAgcLabel->setText(QString::number(agc)); - QString str=GNSS_ANT_STATUS_STRINGS[antStatus]; - switch (antStatus) { - case 0: ui->antStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); - break; - case 2: ui->antStatusLabel->setStyleSheet("QLabel { background-color : Window }"); - break; - case 3: ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); - break; - case 4: ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); - break; - case 1: - default: - ui->antStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); - } - ui->antStatusLabel->setText(str); - switch (antPower) { - case 0: str="off"; - break; - case 1: str="on"; - break; - case 2: - default: - str="unknown"; - } - ui->antPowerLabel->setText(str); - ui->jammingProgressBar->setValue(jamInd/2.55); -} -*/ - -void GpsSatsForm::onGpsMonHWReceived(const GnssMonHwStruct& hwstruct) -{ - ui->lnaNoiseLabel->setText(QString::number(-hwstruct.noise)+" dBHz"); - ui->lnaAgcLabel->setText(QString::number(hwstruct.agc)); - QString str="n/a"; - if (hwstruct.antStatusantStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); - break; - case 2: ui->antStatusLabel->setStyleSheet("QLabel { background-color : Window }"); - break; - case 3: ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); - break; - case 4: ui->antStatusLabel->setStyleSheet("QLabel { background-color : red }"); - break; - case 1: - default: - ui->antStatusLabel->setStyleSheet("QLabel { background-color : yellow }"); - } - ui->antStatusLabel->setText(str); - switch (hwstruct.antPower) { - case 0: str="off"; - break; - case 1: str="on"; - break; - case 2: - default: - str="unknown"; - } - ui->antPowerLabel->setText(str); - ui->jammingProgressBar->setValue(hwstruct.jamInd/2.55); -} - -/* -void GpsSatsForm::onGpsMonHW2Received(qint8 ofsI, quint8 magI, qint8 ofsQ, quint8 magQ, quint8 cfgSrc) -{ - const int iqPixmapSize=65; - QPixmap iqPixmap(iqPixmapSize,iqPixmapSize); - // pixmap.fill(QColor("transparent")); - iqPixmap.fill(Qt::white); - QPainter iqPainter(&iqPixmap); - iqPainter.setPen(QPen(Qt::black)); - iqPainter.drawLine(QPoint(iqPixmapSize/2,0),QPoint(iqPixmapSize/2,iqPixmapSize)); - iqPainter.drawLine(QPoint(0,iqPixmapSize/2),QPoint(iqPixmapSize,iqPixmapSize/2)); - QColor col(Qt::blue); - iqPainter.setPen(col); - double x=0., y=0.; - for (int i=0; iiqAlignmentLabel->setPixmap(iqPixmap); - iqTrack.push_back(QPointF(x,y)); - if (iqTrack.size()>MAX_IQTRACK_BUFFER) iqTrack.pop_front(); -} -*/ - -void GpsSatsForm::onGpsMonHW2Received(const GnssMonHw2Struct& hw2struct) -{ - const int iqPixmapSize=65; - QPixmap iqPixmap(iqPixmapSize,iqPixmapSize); - // pixmap.fill(QColor("transparent")); - iqPixmap.fill(Qt::white); - QPainter iqPainter(&iqPixmap); - iqPainter.setPen(QPen(Qt::black)); - iqPainter.drawLine(QPoint(iqPixmapSize/2,0),QPoint(iqPixmapSize/2,iqPixmapSize)); - iqPainter.drawLine(QPoint(0,iqPixmapSize/2),QPoint(iqPixmapSize,iqPixmapSize/2)); - QColor col(Qt::blue); - iqPainter.setPen(col); - double x=0., y=0.; - for (int i=0; iiqAlignmentLabel->setPixmap(iqPixmap); - iqTrack.push_back(QPointF(x,y)); - if (iqTrack.size()>MAX_IQTRACK_BUFFER) iqTrack.pop_front(); -} - -void GpsSatsForm::onGpsVersionReceived(const QString &swString, const QString &hwString, const QString& protString) -{ - ui->ubxHwVersionLabel->setText(hwString); - ui->ubxSwVersionLabel->setText(swString); - ui->UBXprotLabel->setText(protString); -} - -void GpsSatsForm::onGpsFixReceived(quint8 val) -{ - QString fixType = "N/A"; - if (valfixTypeLabel->setStyleSheet("QLabel { background-color : red }"); - else if (val==2) ui->fixTypeLabel->setStyleSheet("QLabel { background-color : lightgreen }"); - else if (val>2) ui->fixTypeLabel->setStyleSheet("QLabel { background-color : green }"); - else ui->fixTypeLabel->setStyleSheet("QLabel { background-color : Window }"); - ui->fixTypeLabel->setText(fixType); -} - -void GpsSatsForm::onGeodeticPosReceived(const GeodeticPos& pos){ - - QString str; - str=printReadableFloat(pos.hAcc/1000.,2,4)+"m / "+printReadableFloat(pos.vAcc/1000.,2,4)+"m"; -/* str=QString::number((float)pos.hAcc/1000.,'f',3)+"m"; - str+="/"+QString::number((float)pos.vAcc/1000.,'f',3)+"m"; -*/ - ui->xyzResLabel->setText(str); -} - -void GpsSatsForm::onUiEnabledStateChange(bool connected) -{ - if (!connected) { - QVector emptylist; - onSatsReceived(emptylist); - iqTrack.clear(); - //satTracks.clear(); -// onGpsMonHW2Received(0,0,0,0,0); - onGpsMonHW2Received(GnssMonHw2Struct()); - ui->jammingProgressBar->setValue(0); - ui->timePrecisionLabel->setText("N/A"); - ui->freqPrecisionLabel->setText("N/A"); - ui->intCounterLabel->setText("N/A"); - ui->lnaNoiseLabel->setText("N/A"); - ui->lnaAgcLabel->setText("N/A"); - ui->antStatusLabel->setText("N/A"); - ui->antPowerLabel->setText("N/A"); - ui->fixTypeLabel->setText("N/A"); - ui->fixTypeLabel->setStyleSheet("QLabel { background-color : Window }"); - ui->xyzResLabel->setText("N/A"); - ui->ubxHwVersionLabel->setText("N/A"); - ui->ubxSwVersionLabel->setText("N/A"); - ui->UBXprotLabel->setText("N/A"); - ui->ubxUptimeLabel->setText("N/A"); - //ui->satsTableWidget->setRowCount(0); - } - ui->jammingProgressBar->setEnabled(connected); - iqTrack.clear(); - this->setEnabled(connected); - -} - -void GpsSatsForm::onUbxUptimeReceived(quint32 val) -{ - ui->ubxUptimeLabel->setText(" "+QString::number(val/3600.,'f',2)+" h "); -} diff --git a/source/gui/src/i2cform.cpp b/source/gui/src/i2cform.cpp deleted file mode 100644 index ff0b9d25..00000000 --- a/source/gui/src/i2cform.cpp +++ /dev/null @@ -1,79 +0,0 @@ -#include -#include -#include - - -I2cForm::I2cForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::I2cForm) -{ - ui->setupUi(this); -} - - -I2cForm::~I2cForm() -{ - delete ui; -} - - -void I2cForm::onI2cStatsReceived(quint32 bytesRead, quint32 bytesWritten, const QVector& deviceList) -{ - ui->nrDevicesLabel->setText("Nr. of devices: "+QString::number(deviceList.size())); - ui->bytesReadLabel->setText("total bytes read: "+QString::number(bytesRead)); - ui->bytesWrittenLabel->setText("total bytes written: "+QString::number(bytesWritten)); - - ui->devicesTableWidget->setRowCount(deviceList.size()); - for (int i=0; isetSizeHint(QSize(120,24)); - newItem1->setTextAlignment(Qt::AlignCenter); - ui->devicesTableWidget->setItem(i, 0, newItem1); - - QTableWidgetItem *newItem2 = new QTableWidgetItem(deviceList[i].name); - newItem2->setSizeHint(QSize(200,24)); - newItem2->setTextAlignment(Qt::AlignCenter); - ui->devicesTableWidget->setItem(i, 1, newItem2); - - uint8_t status = deviceList[i].status; - QString str; - QBrush brush = QBrush(Qt::green, Qt::SolidPattern); - if (status == 0) { str="unknown"; brush = QBrush(Qt::lightGray, Qt::SolidPattern); } - if (status & 0x04) { str="missing"; brush = QBrush(Qt::red, Qt::SolidPattern); } - else { - if (status & 0x01) { str="online"; brush = QBrush(Qt::green, Qt::SolidPattern); } - if (status & 0x02) { str="system"; brush = QBrush(Qt::blue, Qt::SolidPattern); } - } - if(status & 0x08) { str="bus error"; brush = QBrush(Qt::red, Qt::SolidPattern); } - if(status & 0x10) { str="locked"; brush = QBrush(Qt::darkGray, Qt::SolidPattern); } - - QTableWidgetItem *newItem3 = new QTableWidgetItem(str); - newItem3->setBackground(brush); - newItem3->setSizeHint(QSize(140,24)); - newItem3->setTextAlignment(Qt::AlignCenter); - ui->devicesTableWidget->setItem(i, 2, newItem3); - } - -} - -void I2cForm::onUiEnabledStateChange(bool connected) -{ - if (!connected) { - ui->nrDevicesLabel->setText("Nr. of devices: "); - ui->bytesReadLabel->setText("total bytes read: "); - ui->bytesWrittenLabel->setText("total bytes written: "); - ui->devicesTableWidget->setRowCount(0); - } - this->setEnabled(connected); -} - -void I2cForm::on_statsQueryPushButton_clicked() -{ - emit i2cStatsRequest(); -} - -void I2cForm::on_scanBusPushButton_clicked() -{ - emit scanI2cBusRequest(); -} diff --git a/source/gui/src/mainwindow.ui b/source/gui/src/mainwindow.ui deleted file mode 100644 index 41b6077e..00000000 --- a/source/gui/src/mainwindow.ui +++ /dev/null @@ -1,511 +0,0 @@ - - - MainWindow - - - true - - - - 0 - 0 - 608 - 575 - - - - muondetector-gui - - - - - - - - 0 - 0 - - - - - - - - - connect to: - - - - - - - - 200 - 22 - - - - Qt::WheelFocus - - - - - - true - - - - - - QComboBox::InsertAlphabetically - - - 1 - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - connect - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - not connected - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal - - - - - - - - - - - - - - 0 - 0 - - - - - 53 - 0 - - - - Thresh1 - - - Qt::AlignCenter - - - - - - - - - - 8191 - - - Qt::Vertical - - - - - - - - 0 - 0 - - - - - 65 - 24 - - - - - 51 - 0 - - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - - 53 - 0 - - - - Thresh2 - - - Qt::AlignCenter - - - - - - - 8191 - - - Qt::Vertical - - - - - - - true - - - - 0 - 0 - - - - - 65 - 24 - - - - - 51 - 0 - - - - Qt::AlignCenter - - - - - - - - - - - Store DAC settings - - - - - - - - - Qt::Horizontal - - - - - - - - Bias DAC Control - - - - - Bias Voltage - - - - - - - - - 0 - 0 - - - - 10 - - - Qt::Horizontal - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - V - - - 3.300000000000000 - - - 0.010000000000000 - - - 0.700000000000000 - - - - - - - - - QFrame::Box - - - Bias OFF - - - Qt::AlignCenter - - - - - - - Enable Bias - - - - - - - Qt::Horizontal - - - - - - - - - - 54 - 24 - - - - - 54 - 24 - - - - QFrame::Box - - - XOR - - - Qt::AlignCenter - - - - - - - - 54 - 24 - - - - - 54 - 24 - - - - QFrame::Box - - - AND - - - Qt::AlignCenter - - - - - - - - - - - - 54 - 24 - - - - - 54 - 24 - - - - xRate - - - Qt::AlignCenter - - - - - - - - 54 - 24 - - - - - 54 - 24 - - - - aRate - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - true - - - - - - - - - - - - - - data acquisition mode - - - - - settings - - - - - - - diff --git a/source/gui/src/map.cpp b/source/gui/src/map.cpp deleted file mode 100644 index 82657f12..00000000 --- a/source/gui/src/map.cpp +++ /dev/null @@ -1,69 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include - - -Map::Map(QWidget *parent) : - QWidget(parent), - mapUi(new Ui::Map) -{ - QVariantMap parameters; - mapUi->setupUi(this); - mapUi->quickWidget->setResizeMode(QQuickWidget::SizeRootObjectToView); -/* - // Fetch tokens from the environment, if present - const QByteArray mapboxMapID = qgetenv("MAPBOX_MAP_ID"); - const QByteArray mapboxAccessToken = qgetenv("MAPBOX_ACCESS_TOKEN"); - const QByteArray hereAppID = qgetenv("HERE_APP_ID"); - const QByteArray hereToken = qgetenv("HERE_TOKEN"); - const QByteArray esriToken = qgetenv("ESRI_TOKEN"); - if (!mapboxMapID.isEmpty()){ - parameters["mapbox.map_id"] = QString::fromLocal8Bit(mapboxMapID); - } - if (!mapboxAccessToken.isEmpty()){ - parameters["mapbox.access_token"] = QString::fromLocal8Bit(mapboxAccessToken); - } - if (!hereAppID.isEmpty()){ - parameters["here.app_id"] = QString::fromLocal8Bit(hereAppID); - } - if (!hereToken.isEmpty()){ - parameters["here.token"] = QString::fromLocal8Bit(hereToken); - } - if (!esriToken.isEmpty()){ - parameters["esri.token"] = QString::fromLocal8Bit(esriToken); - }*/ - - QQmlEngine* engine = new QQmlEngine(this); - //engine->addImportPath(QStringLiteral(":/imports")); - //QQmlComponent* component = new QQmlComponent(engine, "qrc:/qml/mymap.qml");//QUrl::fromLocalFile("/usr/share/muondetector-gui/qml/mymap.qml")); - QQmlComponent* component = new QQmlComponent(engine, "qrc:/qml/CustomMap.qml"); - mapComponent = component->create(); - //QMetaObject::invokeMethod(mapComponent, "initializeProviders", - // Q_ARG(QVariant, QVariant::fromValue(parameters))); - mapUi->quickWidget->setContent(component->url(), component, mapComponent); - mapUi->quickWidget->show(); - //mapUi->quickWidget->setSource(QUrl::fromLocalFile("qml/mymap.qml")); -} - -Map::~Map() -{ - delete mapComponent; - delete mapUi; -} - -void Map::onGeodeticPosReceived(GeodeticPos pos){ - //qDebug() << (double)pos.lon*1e-7 << (double)pos.lat*1e-7 << (double)pos.hAcc/1000.0; - if (mapComponent==nullptr){ - return; - } - QMetaObject::invokeMethod(mapComponent, "setCircle", - Q_ARG(QVariant, ((double)pos.lon)*1e-7), - Q_ARG(QVariant, ((double)pos.lat)*1e-7), - Q_ARG(QVariant, ((double)pos.hAcc)/1000)); -} - diff --git a/source/gui/src/plotcustom.cpp b/source/gui/src/plotcustom.cpp deleted file mode 100644 index fb68768d..00000000 --- a/source/gui/src/plotcustom.cpp +++ /dev/null @@ -1,158 +0,0 @@ -#include -#include -#include -#include -#include - -class TimeScaleDraw : public QwtScaleDraw -{ -public: - TimeScaleDraw(const QTime &base, const bool invert = true) - : invertValues(invert) - , baseTime(base) - { - } - virtual QwtText label(qreal v) const - { - if (invertValues){ - QTime upTime = baseTime.addSecs(-(int)v); - return QString("- "+upTime.toString()); - }else{ - QTime upTime = baseTime.addSecs((int)v); - return QString(upTime.toString()); - } - } -private: - bool invertValues; - QTime baseTime; -}; - -void PlotCustom::initialize(){ - setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - setStyleSheet("background-color: white; border: 0px;"); - setAutoReplot(false); - enableAxis(QwtPlot::yLeft,false); - enableAxis(QwtPlot::yRight,true); - //setAxisAutoScale(QwtPlot::xBottom,false); - setAxisAutoScale(QwtPlot::yRight,true); - - QwtLegend *legend = new QwtLegend(this); - legend->setDefaultItemMode(QwtLegendData::Checkable); - this->insertLegend(legend,QwtPlot::BottomLegend); - - const QPen grayPen(Qt::gray); - grid.setPen(grayPen); - grid.attach(this); - - xorCurve.setAxes(QwtPlot::xBottom,QwtPlot::yRight); - xorCurve.setRenderHint(QwtPlotCurve::RenderAntialiased, true); - //xorCurve.setStyle(QwtPlotCurve::Steps); - QColor xorCurveColor = Qt::darkGreen; - xorCurveColor.setAlphaF(0.3); - const QPen greenPen(xorCurveColor); - xorCurve.setTitle(QwtText("xor-curve")); - xorCurve.setPen(greenPen); - xorCurve.setBrush(xorCurveColor); - xorCurve.attach(this); - - andCurve.setTitle(QwtText("and-curve")); - andCurve.setAxes(QwtPlot::xBottom,QwtPlot::yRight); - andCurve.setRenderHint(QwtPlotCurve::RenderAntialiased, true); - //xorCurve.setStyle(QwtPlotCurve::Steps); - QColor andCurveColor = Qt::darkBlue; - andCurveColor.setAlphaF(0.3); - const QPen bluePen(andCurveColor); - andCurve.setPen(bluePen); - andCurve.setBrush(andCurveColor); - andCurve.attach(this); - connect(legend, &QwtLegend::checked, this, [this](const QVariant &itemInfo, bool on, int /*index*/){ - if (on){ - if (itemInfo=="xor-curve"){ - xorCurve.show(); - } - if (itemInfo=="xor-curve"){ - andCurve.show(); - } - }else{ - if (itemInfo=="xor-curve"){ - xorCurve.hide(); - } - if (itemInfo=="xor-curve"){ - andCurve.hide(); - } - } - this->replot(); - }); - legend->checked(QString(""),true,0); - legend->checked(QString(""),true,1); - replot(); - show(); -} - -void PlotCustom::plotSamples(QVector& samples, QwtPlotCurve& curve){ - if (!isEnabled()) return; - QVector someSamples; - for (auto sample : samples){ - someSamples.push_back(sample); - someSamples.last().setX(sample.x() - samples.at(samples.size()-1).x()); - } - - qreal xMin = 0.0; - qreal xMax = 0.0; - if (!someSamples.isEmpty()){ - xMin = someSamples.first().x(); - } - qreal step = (double)(int)((xMax-xMin)/6); - if (this->size().width()<450){ - step = (double)(int)((xMax-xMin)/3); - } - setAxisScale(QwtPlot::xBottom,xMin,xMax,step); - QwtPointSeriesData *dat = new QwtPointSeriesData(someSamples); - curve.setData(dat); - replot(); -} - -void PlotCustom::plotXorSamples(QVector& xorSamples){ - setPreset(""); - plotSamples(xorSamples,xorCurve); -} - -void PlotCustom::plotAndSamples(QVector& andSamples){ - setPreset(""); - plotSamples(andSamples,andCurve); -} - -void PlotCustom::setPreset(QString preset){ - if (!preset.isEmpty()){ - xAxisPreset = preset; - } - if (xAxisPreset=="seconds"){ - setAxisScaleDraw(QwtPlot::xBottom, new QwtScaleDraw()); - } - if (xAxisPreset=="hh:mm:ss"){ - setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw(QTime(0,0,0,0),true)); - } - if (xAxisPreset=="time"){ - setAxisScaleDraw(QwtPlot::xBottom, new TimeScaleDraw(QTime::currentTime(),false)); - } - replot(); -} - -void PlotCustom::setStatusEnabled(bool status){ - if (status==true){ - xorCurve.attach(this); - andCurve.attach(this); - const QPen blackPen(Qt::black); - grid.setPen(blackPen); - setTitle(title); - replot(); - }else{ - xorCurve.detach(); - andCurve.detach(); - const QPen grayPen(Qt::gray); - grid.setPen(grayPen); - setTitle(""); - replot(); - } -} - diff --git a/source/gui/src/scanform.cpp b/source/gui/src/scanform.cpp deleted file mode 100644 index 32f46f95..00000000 --- a/source/gui/src/scanform.cpp +++ /dev/null @@ -1,255 +0,0 @@ -#include "scanform.h" -#include "ui_scanform.h" -#include -#include -#include -#include -#include -#include -#include - -ScanForm::ScanForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::ScanForm) -{ - ui->setupUi(this); - ui->scanParComboBox->clear(); - foreach (QString item, SP_NAMES) { - ui->scanParComboBox->addItem(item); - } - ui->observableComboBox->clear(); - foreach (QString item, OP_NAMES) { - ui->observableComboBox->addItem(item); - } - ui->minRangeLineEdit->setValidator(new QDoubleValidator(.001, 3.3, 4, ui->minRangeLineEdit)); - ui->maxRangeLineEdit->setValidator(new QDoubleValidator(.001, 3.3, 4, ui->maxRangeLineEdit)); - ui->stepSizeLineEdit->setValidator(new QDoubleValidator(0., 1.0, 5, ui->stepSizeLineEdit)); - - ui->scanPlot->setTitle("Parameter Scan"); - ui->scanPlot->setAxisTitle(QwtPlot::xBottom,"scanpar"); - ui->scanPlot->setAxisTitle(QwtPlot::yLeft,"observable"); - -/* - ui->scanPlot->addCurve("parscan", Qt::blue); - ui->scanPlot->curve("parscan").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); - ui->scanPlot->curve("parscan").setSymbol(sym); -*/ - ui->scanPlot->setAxisAutoScale(QwtPlot::xBottom, true); - ui->scanPlot->setAxisAutoScale(QwtPlot::yLeft, true); - ui->scanPlot->replot(); - connect(ui->exportDataPushButton, &QPushButton::clicked, this, &ScanForm::exportData); - ui->exportDataPushButton->setEnabled(false); -} - -ScanForm::~ScanForm() -{ - delete ui; -} - -void ScanForm::onTimeMarkReceived(const UbxTimeMarkStruct &tm) -{ - if (!tm.risingValid) { - qDebug()<<"received invalid timemark"; - return; - } - if (active && OP_NAMES[obsPar]=="UBXRATE") { - if (waitForFirst) { - currentCounts=0; - currentTimeInterval=0.; - waitForFirst=false; - } else { - currentCounts+=(uint16_t)(tm.evtCounter-lastTM.evtCounter); - double interval=(tm.rising.tv_nsec-lastTM.rising.tv_nsec)*1e-9; - interval+=tm.rising.tv_sec-lastTM.rising.tv_sec; - currentTimeInterval+=interval; - if ( (currentTimeInterval > maxMeasurementTimeInterval) - || ( (currentCounts > maxMeasurementStatistics) - && (currentTimeInterval > 1) ) ) - { - scanParIteration(); - } - } - } - lastTM=tm; -} - -void ScanForm::scanParIteration() { - if (!active) return; - if (OP_NAMES[obsPar]=="UBXRATE") { - double rate=currentCounts/currentTimeInterval; - scanData[currentScanPar].value=rate; - scanData[currentScanPar].error=std::sqrt(currentCounts)/currentTimeInterval; - updateScanPlot(); - } - currentScanPar+=stepSize; - adjustScanPar(SP_NAMES[scanPar], currentScanPar); - ui->scanProgressBar->setValue((currentScanPar-minRange)/stepSize); - if (currentScanPar>maxRange) { - // measurement finished - finishScan(); -/* - for (auto it=scanData.constBegin(); it!=scanData.constEnd(); ++it) { - qDebug()<minRangeLineEdit->text().toDouble(&ok); - if (!ok) return; - maxRange = ui->maxRangeLineEdit->text().toDouble(&ok); - if (!ok) return; - stepSize = ui->stepSizeLineEdit->text().toDouble(&ok); - if (!ok) return; - scanPar=ui->scanParComboBox->currentIndex(); - if (SP_NAMES[scanPar]=="VOID") return; - obsPar=ui->observableComboBox->currentIndex(); - if (OP_NAMES[obsPar]=="VOID") return; - - maxMeasurementTimeInterval=ui->timeIntervalSpinBox->value(); - if (ui->limitStatisticsCheckBox->isChecked()) { - int power = ui->maxStatisticsComboBox->currentIndex() + 1; - maxMeasurementStatistics=std::pow(10,power); - } else maxMeasurementStatistics = std::numeric_limits::max(); - - - if (OP_NAMES[obsPar]=="UBXRATE") { - emit gpioInhibitChanged(true); - emit mqttInhibitChanged(true); - } - // values seem to be valid - // start the scan - ui->scanStartPushButton->setText(tr("Stop Scan")); - currentScanPar=minRange; - adjustScanPar(SP_NAMES[scanPar], currentScanPar); - - active=true; - waitForFirst=true; - scanData.clear(); - ui->scanProgressBar->setRange(0, abs(maxRange-minRange)/stepSize+0.5); - ui->scanProgressBar->reset(); -} - -void ScanForm::finishScan() { - ui->scanStartPushButton->setText(tr("Start Scan")); - active=false; - ui->scanProgressBar->reset(); - emit gpioInhibitChanged(false); - emit mqttInhibitChanged(false); - updateScanPlot(); - ui->exportDataPushButton->setEnabled(true); -} - -void ScanForm::updateScanPlot() { - QVector vec; - for (auto it=scanData.constBegin(); it!=scanData.constEnd(); ++it) { - QPointF p1; - if (!plotDifferential) { - p1.rx()=it.key(); - p1.ry()=it.value().value; - } else { - if (it==--scanData.constEnd()) continue; - p1.rx()=it.key(); - auto it2 = it; - ++it2; - p1.ry()=it.value().value-it2.value().value; - if ( ui->scanPlot->getLogY() && p1.ry()<=0. ) continue; - } - vec.push_back(p1); - } - - ui->scanPlot->curve("parscan").setSamples(vec); - ui->scanPlot->replot(); -} - -void ScanForm::on_plotDifferentialCheckBox_toggled(bool checked) -{ - plotDifferential=checked; - updateScanPlot(); -} - -void ScanForm::onUiEnabledStateChange(bool connected) -{ - this->setEnabled(connected); - ui->scanPlot->setEnabled(connected); - if (connected) { - ui->scanPlot->addCurve("parscan", Qt::blue); - ui->scanPlot->curve("parscan").setStyle(QwtPlotCurve::NoCurve); - QwtSymbol *sym=new QwtSymbol(QwtSymbol::Rect, QBrush(Qt::blue, Qt::SolidPattern),QPen(Qt::black),QSize(5,5)); - ui->scanPlot->curve("parscan").setSymbol(sym); - } else { - ui->scanPlot->curve("parscan").detach(); - if (active) finishScan(); - } -} - -void ScanForm::exportData() { - QString types("ASCII raw data (*.txt)"); - QString filter; // Type of filter - QString txtExt=".txt"; - QString suggestedName=""; - QString fn = QFileDialog::getSaveFileName(this,tr("Export Plot"), - suggestedName,types,&filter); - - if ( !fn.isEmpty() ) { // If filename is not null - if (fn.contains(txtExt)) { - fn.remove(txtExt); - } - - if (filter.contains(txtExt)) { - fn+=txtExt; - // export histo in asci raw data format - QFile file(fn); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) return; - QTextStream out(&file); - //out.setFieldWidth(20); - - out << "# Parameter Scan\n"; - out << "# scanparValue measValue measError diffMeasValue diffMeasError temp\n"; - for (auto it=scanData.constBegin(); it!=scanData.constEnd(); ++it) { - double x = it.key(); - ScanPoint point1 = it.value(); - ScanPoint point2 {}; - bool hasSuccessor { false }; - if (it!=--scanData.constEnd()) { - hasSuccessor = true; - auto it2 = it; - ++it2; - point2 = it2.value(); - } - out << QString::number(x,'g',10) << " " - << QString::number(point1.value, 'g', 10) << " " - << QString::number(point1.error, 'g', 10) << " "; - - if (hasSuccessor) { - out << QString::number(point1.value-point2.value, 'g', 10) << " " - << QString::number(point1.error+point2.error, 'g', 10) << " "; - } else { - out << "0 0 "; - } - out << QString::number(point1.temp, 'g', 10) << "\n"; - } - } - } -} diff --git a/source/gui/src/scanform.ui b/source/gui/src/scanform.ui deleted file mode 100644 index 4b28b9ca..00000000 --- a/source/gui/src/scanform.ui +++ /dev/null @@ -1,356 +0,0 @@ - - - ScanForm - - - - 0 - 0 - 581 - 338 - - - - Form - - - - - - Qt::Horizontal - - - - - - - Parameters && Range - - - - - - - - Observable - - - - - - - - UBX Rate - - - - - GPIO Rate - - - - - - - - - - - - Scan Parameter - - - - - - - - THR1 - - - - - THR2 - - - - - - - - - - - - Scan Range from: - - - - - - - 0 - - - - - - - to: - - - - - - - 1 - - - - - - - - - - - Step Size - - - - - - - - 60 - 0 - - - - 0.005 - - - - - - - - - - - - 0 - 0 - - - - Meas.Time Interval - - - - - - - 1 - - - 10000 - - - - - - - s - - - - - - - - - - - limit statistics - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - max counts: - - - - - - - false - - - 2 - - - - 10 - - - - - 100 - - - - - 1k - - - - - 10k - - - - - 100k - - - - - 1M - - - - - 10M - - - - - 100M - - - - - 1G - - - - - 10G - - - - - 100G - - - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Start Scan - - - - - - - 0 - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - - - differential - - - - - - - export data - - - - - - - - - - - - CustomPlot - QWidget -
custom_plot_widget.h
- 1 -
-
- - - - limitStatisticsCheckBox - toggled(bool) - maxStatisticsComboBox - setEnabled(bool) - - - 83 - 176 - - - 295 - 176 - - - - -
diff --git a/source/library/include/config.h b/source/library/include/config.h deleted file mode 100644 index d25301fe..00000000 --- a/source/library/include/config.h +++ /dev/null @@ -1,73 +0,0 @@ -#ifndef MUONPI_CONFIG_H -#define MUONPI_CONFIG_H - -#include "version.h" - -#include -#include - - -namespace MuonPi::Version { -constexpr struct Version { - int major; - int minor; - int patch; - - [[nodiscard]] auto string() const -> std::string; -} - hardware { 3, 0, 0 }, - software { CMake::Version::major, CMake::Version::minor, CMake::Version::patch }; -} - -namespace MuonPi::Config { -constexpr const char* file { "/etc/muondetector/muondetector.conf" }; -constexpr int event_count_deadtime_ticks { 50000 }; - -namespace MQTT { -constexpr const char* host { "116.202.96.181" }; -constexpr int port { 1883 }; -constexpr int timeout { 2000 }; -constexpr int qos { 1 }; -constexpr int keepalive_interval { 45 }; -constexpr const char* data_topic { "muonpi/data/" }; -constexpr const char* log_topic { "muonpi/log/" }; -} -namespace Log { -constexpr int interval { 1 }; -} -namespace Upload { -constexpr int reminder { 5 }; -constexpr std::size_t timeout { 600000UL }; -constexpr const char* url { "balu.physik.uni-giessen.de:/cosmicshower" }; -constexpr int port { 35221 }; -} -namespace Hardware { -namespace OLED { -constexpr int update_interval { 2000 }; -} -namespace ADC { -constexpr int buffer_size { 50 }; -constexpr int pretrigger { 10 }; -constexpr int deadtime { 8 }; -} -namespace DAC { -namespace Voltage { -constexpr float bias {0.5}; -constexpr float threshold[2] {0.1, 1.0}; -} -} -namespace GPIO::Clock::Measurement { -constexpr int interval { 100 }; -constexpr int buffer_size { 500 }; -} -constexpr int trace_sampling_interval { 5 }; -constexpr int monitor_interval { 5000 }; -namespace RateScan { -constexpr int iterations { 10 }; -constexpr int interval { 400 }; -} -} - -} // namespace MuonPi::Config - -#endif // MUONPI_CONFIG_H diff --git a/source/library/include/gpio_pin_definitions.h b/source/library/include/gpio_pin_definitions.h deleted file mode 100644 index d0081f61..00000000 --- a/source/library/include/gpio_pin_definitions.h +++ /dev/null @@ -1,77 +0,0 @@ -#ifndef GPIO_SIGNAL_DEFINITIONS_H -#define GPIO_SIGNAL_DEFINITIONS_H - -#include "muondetector_shared_global.h" - -#include -#include -#include -#include - -// Define the signals of the hardware interface to the MuonPi HAT -// Note: The pin definitions are enum constants and have nothing to do with the actual pin numbers -// of the RPi GPIO header. To be independent of the specific hardware implementation, -// the pin numbers for these signals are defined in gpio_pin_mapping.h on the daemon side through the static map GPIO_PINMAP - -enum GPIO_SIGNAL { UBIAS_EN, - PREAMP_1, PREAMP_2, - EVT_AND, EVT_XOR, - GAIN_HL, ADC_READY, - TIMEPULSE, - TIME_MEAS_OUT, - STATUS1, STATUS2, STATUS3, - PREAMP_FAULT, EXT_TRIGGER, - TDC_INTB, - TDC_STATUS, - IN_POL1, IN_POL2, - UNDEFINED_SIGNAL=255 - }; - -enum SIGNAL_DIRECTION { DIR_UNDEFINED, DIR_IN, DIR_OUT, DIR_IO }; -//enum SIGNAL_POLARITY { POL_UNDEFINED, POL_POSITIVE, POL_NEGATIVE, POL_ANY }; - -struct GpioSignalDescriptor { - QString name; - SIGNAL_DIRECTION direction; -// SIGNAL_POLARITY polarity; -}; - -static const QMap GPIO_SIGNAL_MAP = - { { UBIAS_EN, { "UBIAS_EN", DIR_OUT } }, - { PREAMP_1, { "PREAMP_1", DIR_OUT } }, - { PREAMP_2, { "PREAMP_2", DIR_OUT } }, - { EVT_AND, { "EVT_AND", DIR_IN } }, - { EVT_XOR, { "EVT_XOR", DIR_IN } }, - { GAIN_HL, { "GAIN_HL", DIR_OUT } }, - { ADC_READY, { "ADC_READY", DIR_IN } }, - { TIMEPULSE, { "TIMEPULSE", DIR_IN }}, - { TIME_MEAS_OUT, { "TIME_MEAS_OUT", DIR_IN } }, - { STATUS1, { "STATUS1", DIR_OUT } }, - { STATUS2, { "STATUS2", DIR_OUT } }, - { STATUS3, { "STATUS3", DIR_OUT } }, - { PREAMP_FAULT, { "PREAMP_FAULT", DIR_IN } }, - { EXT_TRIGGER, { "EXT_TRIGGER", DIR_IN } }, - { TDC_INTB, { "TDC_INTB", DIR_IN } }, - { TDC_STATUS, { "TDC_STATUS", DIR_OUT} }, - { IN_POL1, { "IN_POL1", DIR_OUT} }, - { IN_POL2, { "IN_POL2", DIR_OUT} }, - { UNDEFINED_SIGNAL, { "UNDEFINED_SIGNAL", DIR_UNDEFINED} } - }; - - -static const QVector TIMING_MUX_SIGNAL_NAMES = - { - "AND", "XOR", "DISCR1", "DISCR2", "N/A", "TIMEPULSE", "N/A", "EXT" - }; - -enum class TIMING_MUX_SELECTION : uint8_t { - AND = 0, - XOR = 1, - DISCR1 = 2, - DISCR2 = 3, - TIMEPULSE = 5, - EXT = 7, - UNDEFINED = 255 -}; - -#endif // GPIO_SIGNAL_DEFINITIONS_H diff --git a/source/library/include/histogram.h b/source/library/include/histogram.h deleted file mode 100644 index 9f7434d2..00000000 --- a/source/library/include/histogram.h +++ /dev/null @@ -1,136 +0,0 @@ -#ifndef HISTOGRAM_H -#define HISTOGRAM_H - -#include "muondetector_shared_global.h" - -#include -#include -#include -#include - - -class Histogram -{ -public: - Histogram()=default; - Histogram(const std::string& name, int nrBins, double min, double max) - : fName(name), fNrBins(nrBins), fMin(min), fMax(max) - { } - ~Histogram() { fHistogramMap.clear(); } - void clear() { fHistogramMap.clear(); fUnderflow=fOverflow=0.; } - void setName(const std::string& name) { fName=name; } - void setUnit(const std::string& unit) { fUnit=unit; } - void setNrBins(int bins) { fNrBins = bins; clear(); } - int getNrBins() const { return fNrBins; } - void setMin(double val) { fMin=val; } - double getMin() const { return fMin; } - void setMax(double val) { fMax=val; } - double getMax() const { return fMax; } - double getRange() const { return fMax-fMin; } - double getCenter() const { return 0.5*getRange()+fMin; } - double getBinCenter(int bin) const { return bin2Value(bin); } - int getLowestOccupiedBin() const { - if (fHistogramMap.empty()) return -1; - auto it=fHistogramMap.begin(); - while (it!=fHistogramMap.end() && it->second<1e-3) ++it; - if (it==fHistogramMap.end()) return -1; - return it->first; - } - int getHighestOccupiedBin() const { - if (fHistogramMap.empty()) return -1; - auto it=--fHistogramMap.end(); - while (it!=fHistogramMap.begin() && it->second<1e-3) --it; - if (it==fHistogramMap.begin()) return 0; - return it->first; - } - - void fill(double x, double mult = 1.) { - int bin=value2Bin(x); - if (bin<0) { - fUnderflow+=mult; - } else if (bin>=fNrBins) { - fOverflow+=mult; - } else fHistogramMap[bin]+=mult; - } - void setBinContent(int bin, double value) { - if (bin>=0 && bin=0 && bin0.) return sum/entries; - else return 0.; - } - - double getRMS() { - double mean=getMean(); - double sum = 0., entries=0.; - for (const auto &entry : fHistogramMap) { - entries+=entry.second; - double dx=bin2Value(entry.first)-mean; - sum+=dx*dx*entry.second; - } - if (entries>1.) return sqrt(sum/(entries-1.)); - else return 0.; - } - double getUnderflow() const { return fUnderflow; } - double getOverflow() const { return fOverflow; } - double getEntries() { - double sum = fUnderflow+fOverflow; - // foreach (double value, fHistogramMap) sum+=value; - // this should also work, but it doesn't compile. reason unclear - for (const auto &entry : fHistogramMap) { - sum+=entry.second; - } -/* - // this should also work, but it doesn't compile. reason unclear - sum += std::accumulate(fHistogramMap.begin(), fHistogramMap.end(), 0., - [](double previous, const QPair& p) - { return previous + p.second; }); -*/ - return sum; - } - - friend QDataStream& operator << (QDataStream& out, const Histogram& h); - friend QDataStream& operator >> (QDataStream& in, Histogram& h); - - const std::string& getName() const { return fName; } - const std::string& getUnit() const { return fUnit; } - -protected: - int value2Bin(double value) const { - double range=fMax-fMin; - if (range<=0.) return -1; - int bin=(value-fMin)/range*(fNrBins-1)+0.5; - return bin; - } - double bin2Value(int bin) const { - double range=fMax-fMin; - if (range<=0.) return -1; - double value=range*bin/(fNrBins-1)+fMin; - return value; - } - std::string fName = "defaultHisto"; - std::string fUnit = "A.U."; - int fNrBins=100; - double fMin=0.0; - double fMax=1.0; - double fOverflow=0; - double fUnderflow=0; - std::map fHistogramMap; -}; - - -#endif // HISTOGRAM_H diff --git a/source/library/include/muondetector_structs.h b/source/library/include/muondetector_structs.h deleted file mode 100644 index cc958166..00000000 --- a/source/library/include/muondetector_structs.h +++ /dev/null @@ -1,403 +0,0 @@ -#ifndef MUONDETECTOR_STRUCTS_H -#define MUONDETECTOR_STRUCTS_H - -#include "muondetector_shared_global.h" -#include "histogram.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -enum ADC_SAMPLING_MODE {ADC_MODE_DISABLED=0, ADC_MODE_PEAK=1, ADC_MODE_TRACE=2 }; -enum TIMING_MUX_INPUTS { MUX_AND=0, MUX_XOR=1, MUX_DISC1=2, MUX_DISC2=3 }; - -using EventTime = std::chrono::time_point; - -struct CalibStruct { -public: - enum { CALIBFLAGS_NO_CALIB=0x00, CALIBFLAGS_COMPONENTS=0x01, - CALIBFLAGS_VOLTAGE_COEFFS=0x02, CALIBFLAGS_CURRENT_COEFFS=0x04}; - - enum { FEATUREFLAGS_NONE=0x00, FEATUREFLAGS_GNSS=0x01, - FEATUREFLAGS_ENERGY=0x02, FEATUREFLAGS_DETBIAS=0x04, FEATUREFLAGS_PREAMP_BIAS=0x08}; - - CalibStruct()=default; - CalibStruct(const std::string& a_name, const std::string& a_type, uint8_t a_address, const std::string& a_value) - : name(a_name), type(a_type), address(a_address), value(a_value) - { } - ~CalibStruct()=default; - CalibStruct(const CalibStruct& s) - : name(s.name), type(s.type), address(s.address), value(s.value) - { } - //friend QDataStream& operator << (QDataStream& out, const CalibStruct& calib); - //friend QDataStream& operator >> (QDataStream& in, CalibStruct& calib); - std::string name=""; - std::string type=""; - uint16_t address=0; - std::string value=""; -}; - - -struct GeodeticPos { - uint32_t iTOW; - int32_t lon; // longitude 1e-7 scaling (increase by 1 means 100 nano degrees) - int32_t lat; // latitude 1e-7 scaling (increase by 1 means 100 nano degrees) - int32_t height; // height above ellipsoid - int32_t hMSL; // height above main sea level - uint32_t hAcc; // horizontal accuracy estimate - uint32_t vAcc; // vertical accuracy estimate -}; - - -struct GnssConfigStruct { - uint8_t gnssId; - uint8_t resTrkCh; - uint8_t maxTrkCh; - uint32_t flags; -}; - - -class GnssSatellite { -public: - GnssSatellite() {} - GnssSatellite(int gnssId, int satId, int cnr, int elev, int azim, float prRes, uint32_t flags) - : fGnssId(gnssId), fSatId(satId), fCnr(cnr), fElev(elev), fAzim(azim), fPrRes(prRes) - { - fQuality = (int)(flags & 0x07); - if (flags & 0x08) fUsed = true; else fUsed = false; - fHealth = (int)(flags >> 4 & 0x03); - fOrbitSource = (flags >> 8 & 0x07); - fSmoothed = (flags & 0x80); - fDiffCorr = (flags & 0x40); - } - - GnssSatellite(int gnssId, int satId, int cnr, int elev, int azim, float prRes, - int quality, int health, int orbitSource, bool used, bool diffCorr, bool smoothed) - : fGnssId(gnssId), fSatId(satId), fCnr(cnr), fElev(elev), fAzim(azim), fPrRes(prRes), - fQuality(quality), fHealth(health), fOrbitSource(orbitSource), fUsed(used), fDiffCorr(diffCorr), fSmoothed(smoothed) - { } - - //GnssSatellite(const std::string& ubxNavSatSubMessage); - - ~GnssSatellite() {} - - static void PrintHeader(bool wIndex); - void Print(bool wHeader) const; - void Print(int index, bool wHeader) const; - - static bool sortByCnr(const GnssSatellite &sat1, const GnssSatellite &sat2) - { return sat1.getCnr() > sat2.getCnr(); } - - - inline int getCnr() const { return fCnr; } - - friend QDataStream& operator << (QDataStream& out, const GnssSatellite& sat); - friend QDataStream& operator >> (QDataStream& in, GnssSatellite& sat); - - -public: - int fGnssId=0, fSatId=0, fCnr=0, fElev=0, fAzim=0; - float fPrRes=0.; - int fQuality=0, fHealth=0; - int fOrbitSource=0; - bool fUsed=false, fDiffCorr=false, fSmoothed=false; -}; - -struct UbxTimePulseStruct { - enum { ACTIVE=0x01, LOCK_GPS=0x02, LOCK_OTHER=0x04, IS_FREQ=0x08, IS_LENGTH=0x10, ALIGN_TO_TOW=0x20, POLARITY=0x40, GRID_UTC_GPS=0x780 }; - uint8_t tpIndex=0; - uint8_t version=0; - int16_t antCableDelay=0; - int16_t rfGroupDelay = 0; - uint32_t freqPeriod = 0; - uint32_t freqPeriodLock = 0; - uint32_t pulseLenRatio = 0; - uint32_t pulseLenRatioLock = 0; - int32_t userConfigDelay = 0; - uint32_t flags = 0; -}; - -struct UbxTimeMarkStruct { - enum { TIMEBASE_LOCAL=0x00, TIMEBASE_GNSS=0x01, TIMEBASE_UTC=0x02, TIMEBASE_OTHER=0x03 }; - struct timespec rising = {0,0}; - struct timespec falling = {0,0}; - bool risingValid = false; - bool fallingValid = false; - uint32_t accuracy_ns=0; - bool valid=false; - uint8_t timeBase=0; - bool utcAvailable=false; - uint8_t flags = 0; - uint16_t evtCounter = 0; -}; - -struct GnssMonHwStruct { - GnssMonHwStruct() = default; - GnssMonHwStruct(quint16 a_noise, quint16 a_agc, quint8 a_antStatus, quint8 a_antPower, quint8 a_jamInd, quint8 a_flags) - : noise(a_noise), agc(a_agc), antStatus(a_antStatus), antPower(a_antPower), jamInd(a_jamInd), flags(a_flags) - {} - quint16 noise=0, agc=0; - quint8 antStatus=0, antPower=0, jamInd=0, flags=0; -}; - -struct GnssMonHw2Struct { - GnssMonHw2Struct() = default; - GnssMonHw2Struct(qint8 a_ofsI, qint8 a_ofsQ, quint8 a_magI, quint8 a_magQ, quint8 a_cfgSrc) - : ofsI(a_ofsI), ofsQ(a_ofsQ), magI(a_magI), magQ(a_magQ), cfgSrc(a_cfgSrc) - {} - qint8 ofsI=0, ofsQ=0; - quint8 magI=0, magQ=0; - quint8 cfgSrc=0; -}; - - -enum I2C_DEVICE_MODE { I2C_MODE_NONE=0, I2C_MODE_NORMAL=0x01, I2C_MODE_FORCE=0x02, - I2C_MODE_UNREACHABLE=0x04, I2C_MODE_FAILED=0x08, I2C_MODE_LOCKED=0x10 }; - -struct I2cDeviceEntry { - quint8 address; - QString name; - quint8 status; - quint32 nrBytesWritten; - quint32 nrBytesRead; - quint32 nrIoErrors; - quint32 lastTransactionTime; // in us -}; - -struct LogInfoStruct { - QString logFileName; - QString dataFileName; - quint8 status; - quint32 logFileSize; - quint32 dataFileSize; - qint32 logAge; -}; - -struct OledItem { - QString name; - QString displayString; -}; - - -//inline const std::string GnssSatellite::GNSS_ID_STRING[] = { " GPS","SBAS"," GAL","BEID","IMES","QZSS","GLNS"," N/A" }; -//const MUONDETECTORSHARED std::string GNSS_ID_STRING[] = { " GPS","SBAS"," GAL","BEID","IMES","QZSS","GLNS"," N/A" }; -//const MUONDETECTORSHARED std::string GnssSatellite::GNSS_ID_STRING[]; -//inline const std::string GNSS_ID_STRING() -static const QList GNSS_ID_STRING = { " GPS","SBAS"," GAL","BEID","IMES","QZSS","GLNS"," N/A" }; -static const QList FIX_TYPE_STRINGS = { "No Fix", "Dead Reck." , "2D-Fix", "3D-Fix", "GPS+Dead Reck.", "Time Fix" }; -static const QList GNSS_ORBIT_SRC_STRING = { "N/A","Ephem","Alm","AOP","AOP+","Alt","Alt","Alt" }; -static const QList GNSS_ANT_STATUS_STRINGS = { "init", "unknown", "ok", "short", "open", "unknown", "unknown" }; -static const QList GNSS_HEALTH_STRINGS = { "N/A", "good", "bad", "bad+" }; -static const QMap I2C_MODE_STRINGMAP = { {0x00, "None"}, - {0x01, "Normal"}, - {0x02, "System"}, - {0x04, "Unreachable"}, - {0x08, "Failed"}, - {0x10, "Locked"} }; - -inline void GnssSatellite::PrintHeader(bool wIndex) -{ - if (wIndex) { - std::cout << " ----------------------------------------------------------------------------------" << std::endl; - std::cout << " Nr Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; - std::cout << " ----------------------------------------------------------------------------------" << std::endl; - } - else { - std::cout << " -----------------------------------------------------------------" << std::endl; - std::cout << " Sys ID S/N(dB) El(deg) Az(deg) Res(m) Qlty Use Hlth Src Smth DiffCorr" << std::endl; - std::cout << " -----------------------------------------------------------------" <> (QDataStream& in, CalibStruct& calib); -inline QDataStream& operator << (QDataStream& out, const CalibStruct& calib) -{ - out << QString::fromStdString(calib.name) << QString::fromStdString(calib.type) - << (quint16)calib.address << QString::fromStdString(calib.value); - return out; -} - - -inline QDataStream& operator >> (QDataStream& in, CalibStruct& calib) -{ - QString s1,s2,s3; - quint16 u; - in >> s1 >> s2; - in >> u; - in >> s3; - calib.name = s1.toStdString(); - calib.type = s2.toStdString(); - calib.address = (uint16_t)u; - calib.value = s3.toStdString(); - return in; -} - -inline QDataStream& operator >> (QDataStream& in, GnssSatellite& sat) -{ -/* - int fGnssId=0, fSatId=0, fCnr=0, fElev=0, fAzim=0; - float fPrRes=0.; - int fQuality=0, fHealth=0; - int fOrbitSource=0; - bool fUsed=false, fDiffCorr=false, fSmoothed=false; -*/ - in >> sat.fGnssId >> sat.fSatId >> sat.fCnr >> sat.fElev >> sat.fAzim - >> sat.fPrRes >> sat.fQuality >> sat.fHealth >> sat.fOrbitSource - >> sat.fUsed >> sat.fDiffCorr >> sat.fSmoothed; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const GnssSatellite& sat) -{ - out << sat.fGnssId << sat.fSatId << sat.fCnr << sat.fElev << sat.fAzim - << sat.fPrRes << sat.fQuality << sat.fHealth << sat.fOrbitSource - << sat.fUsed << sat.fDiffCorr << sat.fSmoothed; - return out; -} - -inline QDataStream& operator >> (QDataStream& in, UbxTimePulseStruct& tp) -{ - in >> tp.tpIndex >> tp.version >> tp.antCableDelay >> tp.rfGroupDelay - >> tp.freqPeriod >> tp.freqPeriodLock >> tp.pulseLenRatio >> tp.pulseLenRatioLock - >> tp.userConfigDelay >> tp.flags; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const UbxTimePulseStruct& tp) -{ - out << tp.tpIndex << tp.version << tp.antCableDelay << tp.rfGroupDelay - << tp.freqPeriod << tp.freqPeriodLock << tp.pulseLenRatio << tp.pulseLenRatioLock - << tp.userConfigDelay << tp.flags; - return out; -} - -inline QDataStream& operator >> (QDataStream& in, Histogram& h) -{ - h.clear(); - QString name,unit; - in >> name >> h.fMin >> h.fMax >> h.fUnderflow >> h.fOverflow >> h.fNrBins; - h.setName(name.toStdString()); - for (int i=0; i> h.fHistogramMap[i]; - } - in >> unit; - h.setUnit(unit.toStdString()); - return in; -} - -inline QDataStream& operator << (QDataStream& out, const Histogram& h) -{ - out << QString::fromStdString(h.fName) << h.fMin << h.fMax << h.fUnderflow << h.fOverflow << h.fNrBins; - for (int i=0; i> (QDataStream& in, GnssMonHwStruct& hw) -{ - in >> hw.noise >> hw.agc >> hw.antStatus >> hw.antPower >> hw.jamInd >> hw.flags; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const GnssMonHwStruct& hw) -{ - out << hw.noise << hw.agc << hw.antStatus << hw.antPower << hw.jamInd << hw.flags; - return out; -} - -inline QDataStream& operator >> (QDataStream& in, GnssMonHw2Struct& hw2) -{ - in >> hw2.ofsI >> hw2.magI >> hw2.ofsQ >> hw2.magQ >> hw2.cfgSrc; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const GnssMonHw2Struct& hw2) -{ - out << hw2.ofsI << hw2.magI << hw2.ofsQ << hw2.magQ << hw2.cfgSrc; - return out; -} - -inline QDataStream& operator >> (QDataStream& in, LogInfoStruct& lis) -{ - in >> lis.logFileName >> lis.dataFileName >> lis.status >> lis.logFileSize - >> lis.dataFileSize >> lis.logAge; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const LogInfoStruct& lis) -{ - out << lis.logFileName << lis.dataFileName << lis.status << lis.logFileSize - << lis.dataFileSize << lis.logAge; - return out; -} - -inline QDataStream& operator >> (QDataStream& in, UbxTimeMarkStruct& tm) -{ - qint64 sec, nsec; - in >> sec >> nsec; - tm.rising.tv_sec=sec; - tm.rising.tv_nsec=nsec; - in >> sec >> nsec; - tm.falling.tv_sec=sec; - tm.falling.tv_nsec=nsec; - in >> tm.risingValid >> tm.fallingValid >> tm.accuracy_ns >> tm.valid - >> tm.timeBase >> tm.utcAvailable >> tm.flags >> tm.evtCounter; - return in; -} - -inline QDataStream& operator << (QDataStream& out, const UbxTimeMarkStruct& tm) -{ - out << (qint64)tm.rising.tv_sec << (qint64)tm.rising.tv_nsec << (qint64)tm.falling.tv_sec << (qint64)tm.falling.tv_nsec - << tm.risingValid << tm.fallingValid << tm.accuracy_ns << tm.valid - << tm.timeBase << tm.utcAvailable << tm.flags << tm.evtCounter; - return out; -} - -#endif // MUONDETECTOR_STRUCTS_H diff --git a/source/library/include/tcpmessage_keys.h b/source/library/include/tcpmessage_keys.h deleted file mode 100644 index 029f5c82..00000000 --- a/source/library/include/tcpmessage_keys.h +++ /dev/null @@ -1,188 +0,0 @@ -#ifndef TCPMESSAGE_KEYS_H -#define TCPMESSAGE_KEYS_H - -#include "muondetector_shared_global.h" - -// no specific reason but the codes are all prime numbers :) -enum class TCP_MSG_KEY : quint16 -{ MSG_PING = 2, - MSG_QUIT_CONNECTION = 3, - MSG_TIMEOUT = 5, - MSG_THRESHOLD = 7, - MSG_THRESHOLD_REQUEST = 11, - MSG_UBX_MSG_RATE_REQUEST = 13, - MSG_UBX_MSG_RATE = 17, - MSG_GPIO_EVENT = 19, - MSG_BIAS_VOLTAGE = 23, - MSG_BIAS_VOLTAGE_REQUEST = 29, - MSG_BIAS_SWITCH = 31, - MSG_BIAS_SWITCH_REQUEST = 37, - MSG_PCA_SWITCH = 41, - MSG_PCA_SWITCH_REQUEST = 43, - MSG_GPIO_RATE_REQUEST = 47, - MSG_GPIO_RATE = 53, - MSG_GPIO_RATE_CFG = 59, - MSG_GEO_POS = 61, - MSG_ADC_SAMPLE = 67, - MSG_ADC_SAMPLE_REQUEST = 71, - MSG_DAC_READBACK = 73, - MSG_DAC_REQUEST = 79, - MSG_GAIN_SWITCH = 83, - MSG_GAIN_SWITCH_REQUEST = 89, - MSG_PREAMP_SWITCH = 97, - MSG_PREAMP_SWITCH_REQUEST = 101, - MSG_TEMPERATURE = 103, - MSG_TEMPERATURE_REQUEST = 107, - MSG_DAC_EEPROM_SET = 109, - MSG_CALIB_SET = 127, - MSG_CALIB_REQUEST = 131, - MSG_I2C_STATS = 137, - MSG_I2C_STATS_REQUEST = 139, - MSG_GNSS_SATS = 149, - MSG_CALIB_SAVE = 151, - MSG_UBX_TIME_ACCURACY = 157, - MSG_I2C_SCAN_BUS = 163, - MSG_UBX_TXBUF = 167, - MSG_UBX_TXBUF_PEAK = 173, - MSG_UBX_MONHW = 179, - MSG_UBX_VERSION = 181, - MSG_UBX_FIXSTATUS = 191, - MSG_UBX_EVENTCOUNTER = 193, - MSG_UBX_RESET = 197, - MSG_UBX_CONFIG_DEFAULT = 199, - MSG_UBX_FREQ_ACCURACY = 211, - MSG_UBX_MONHW2 = 213, - MSG_UBX_GNSS_CONFIG = 221, - MSG_UBX_UPTIME = 223, - MSG_UBX_CFG_TP5 = 227, - MSG_GPIO_RATE_RESET = 229, - MSG_HISTOGRAM = 233, - MSG_UBX_CFG_SAVE = 239, - MSG_UBX_RXBUF = 241, - MSG_UBX_RXBUF_PEAK = 251, - MSG_EVENTTRIGGER = 257, - MSG_EVENTTRIGGER_REQUEST = 263, - MSG_SPI_STATS = 269, - MSG_SPI_STATS_REQUEST = 271, - MSG_HISTOGRAM_CLEAR = 277, - MSG_ADC_TRACE = 281, - MSG_ADC_MODE = 283, - MSG_ADC_MODE_REQUEST = 293, - MSG_LOG_INFO = 307, - MSG_FILE_DOWNLOAD = 311, - MSG_OLED_ENTRIES = 313, - MSG_RATE_SCAN = 317, - MSG_MQTT_STATUS = 331, - MSG_GPIO_INHIBIT = 337, - MSG_UBX_TIMEMARK = 349, - MSG_POLARITY_SWITCH = 353, - MSG_POLARITY_SWITCH_REQUEST = 359, - MSG_MQTT_INHIBIT = 367 -}; - -/* -static const quint16 ping = 2; -static const quint16 quitConnectionSig = 3; -static const quint16 timeoutSig = 5; -static const quint16 threshSig = 7; -static const quint16 threshRequestSig = 11; -static const quint16 ubxMsgRateRequest = 13; -static const quint16 ubxMsgRate = 17; -static const quint16 gpioPinSig = 19; -static const quint16 biasVoltageSig = 23; -static const quint16 biasVoltageRequestSig = 29; -static const quint16 biasSig = 31; -static const quint16 biasRequestSig = 37; -static const quint16 pcaChannelSig = 41; -static const quint16 pcaChannelRequestSig = 43; -static const quint16 gpioRateRequestSig = 47; -static const quint16 gpioRateSig = 53; -static const quint16 gpioRateSettings = 59; -static const quint16 geodeticPosSig = 61; -static const quint16 adcSampleSig = 67; -static const quint16 adcSampleRequestSig = 71; -static const quint16 dacReadbackSig = 73; -static const quint16 dacRequestSig = 79; -static const quint16 gainSwitchSig = 83; -static const quint16 gainSwitchRequestSig = 89; -static const quint16 preampSig = 97; -static const quint16 preampRequestSig = 101; -static const quint16 temperatureSig = 103; -static const quint16 temperatureRequestSig = 107; -static const quint16 dacSetEepromSig = 109; -static const quint16 calibSetSig = 127; -static const quint16 calibRequestSig = 131; -static const quint16 i2cStatsSig = 137; -static const quint16 i2cStatsRequestSig = 139; -static const quint16 gpsSatsSig = 149; -static const quint16 calibWriteEepromSig = 151; -static const quint16 gpsTimeAccSig = 157; -static const quint16 i2cScanBusRequestSig = 163; -static const quint16 gpsTxBufSig = 167; -static const quint16 gpsTxBufPeakSig = 173; -static const quint16 gpsMonHWSig = 179; -static const quint16 gpsVersionSig = 181; -static const quint16 gpsFixSig = 191; -static const quint16 gpsIntCounterSig = 193; -static const quint16 ubxResetSig = 197; -static const quint16 ubxConfigureDefaultSig = 199; -static const quint16 gpsFreqAccSig = 211; -static const quint16 gpsMonHW2Sig = 213; -static const quint16 gnssConfigSig = 221; -static const quint16 gpsUptimeSig = 223; -static const quint16 gpsCfgTP5Sig = 227; -static const quint16 resetRateSig = 229; -static const quint16 histogramSig = 233; -static const quint16 ubxSaveCfgSig = 239; -static const quint16 gpsRxBufSig = 241; -static const quint16 gpsRxBufPeakSig = 251; -static const quint16 eventTriggerSig = 257; -static const quint16 eventTriggerRequestSig = 263; -static const quint16 spiStatsSig = 269; -static const quint16 spiStatsRequestSig = 271; -static const quint16 histogramClearSig = 277; -static const quint16 adcTraceSig = 281; - - -// not implemented from here on yet -static const quint16 dacRequestEepromSig = 113; -*/ - -// list of prime numbers -//https://primes.utm.edu/lists/small/10000.txt - -/* - * 2 3 5 7 11 13 17 19 23 29 - 31 37 41 43 47 53 59 61 67 71 - 73 79 83 89 97 101 103 107 109 113 - 127 131 137 139 149 151 157 163 167 173 - 179 181 191 193 197 199 211 223 227 229 - 233 239 241 251 257 263 269 271 277 281 - 283 293 307 311 313 317 331 337 347 349 - 353 359 367 373 379 383 389 397 401 409 - 419 421 431 433 439 443 449 457 461 463 - 467 479 487 491 499 503 509 521 523 541 - 547 557 563 569 571 577 587 593 599 601 - 607 613 617 619 631 641 643 647 653 659 - 661 673 677 683 691 701 709 719 727 733 - 739 743 751 757 761 769 773 787 797 809 - 811 821 823 827 829 839 853 857 859 863 - 877 881 883 887 907 911 919 929 937 941 - 947 953 967 971 977 983 991 997 1009 1013 - 1019 1021 1031 1033 1039 1049 1051 1061 1063 1069 - 1087 1091 1093 1097 1103 1109 1117 1123 1129 1151 - 1153 1163 1171 1181 1187 1193 1201 1213 1217 1223 - 1229 1231 1237 1249 1259 1277 1279 1283 1289 1291 - 1297 1301 1303 1307 1319 1321 1327 1361 1367 1373 - 1381 1399 1409 1423 1427 1429 1433 1439 1447 1451 - 1453 1459 1471 1481 1483 1487 1489 1493 1499 1511 - 1523 1531 1543 1549 1553 1559 1567 1571 1579 1583 - 1597 1601 1607 1609 1613 1619 1621 1627 1637 1657 - 1663 1667 1669 1693 1697 1699 1709 1721 1723 1733 - 1741 1747 1753 1759 1777 1783 1787 1789 1801 1811 - 1823 1831 1847 1861 1867 1871 1873 1877 1879 1889 - 1901 1907 1913 1931 1933 1949 1951 1973 1979 1987 - 1993 1997 1999 2003 2011 2017 2027 2029 2039 2053 -*/ - -#endif // TCPMESSAGE_KEYS_H diff --git a/source/library/include/ublox_messages.h b/source/library/include/ublox_messages.h deleted file mode 100644 index b28e5814..00000000 --- a/source/library/include/ublox_messages.h +++ /dev/null @@ -1,118 +0,0 @@ -#ifndef UBLOX_MESSAGES_H -#define UBLOX_MESSAGES_H - -#include "muondetector_shared_global.h" - -#define UBLOX_VERSION 7 -// not in this list are all msg of types: RXM, LOG, AID and INF - -// list of UBX message Cls/ID -#define UBX_ACK 0x0501 -#define UBX_NAK 0x0500 - -#define UBX_NAV_CLOCK 0x0122 -#define UBX_NAV_DGPS 0x0131 -#define UBX_NAV_AOPSTATUS 0x0160 -#define UBX_NAV_DOP 0x0104 -#define UBX_NAV_EOE 0x0161 // not supportet on U-Blox 7 -#define UBX_NAV_GEOFENCE 0x0139 // not supportet on U-Blox 7 -#define UBX_NAV_ODO 0x0109 // not supportet on U-Blox 7 -#define UBX_NAV_ORB 0x0134 // not supportet on U-Blox 7 -#define UBX_NAV_POSECEF 0x0101 -#define UBX_NAV_POSLLH 0x0102 -#define UBX_NAV_PVT 0x0107 -#define UBX_NAV_RESETODO 0x0110 // not supportet on U-Blox 7 -#define UBX_NAV_SAT 0x0135 // not supportet on U-Blox 7 -#define UBX_NAV_SBAS 0x0132 -#define UBX_NAV_SOL 0x0106 -#define UBX_NAV_STATUS 0x0103 -#define UBX_NAV_SVINFO 0x0130 -#define UBX_NAV_TIMEBDS 0x0124 // not supportet on U-Blox 7 -#define UBX_NAV_TIMEGAL 0x0125 // not supportet on U-Blox 7 -#define UBX_NAV_TIMEGLO 0x0123 // not supportet on U-Blox 7 -#define UBX_NAV_TIMEGPS 0x0120 -#define UBX_NAV_TIMELS 0x0126 // not supportet on U-Blox 7 -#define UBX_NAV_TIMEUTC 0x0121 -#define UBX_NAV_VELECEF 0x0111 -#define UBX_NAV_VELNED 0x0112 - -#define UBX_CFG_ANT 0x0613 -#define UBX_CFG_CFG 0x0609 -#define UBX_CFG_DAT 0x0606 -#define UBX_CFG_DOSC 0x0661 // not supportet on U-Blox 7 (only with time & frequency sync products) -#define UBX_CFG_DYNSEED 0x0685 // not supportet on U-Blox 7 -#define UBX_CFG_ESRC 0x0660 // not supportet on U-Blox 7 (only with time & frequency sync products) -#define UBX_CFG_FIXSEED 0x0684 // not supportet on U-Blox 7 -#define UBX_CFG_GEOFENCE 0x0669 // not supportet on U-Blox 7 -#define UBX_CFG_GNSS 0x063e -#define UBX_CFG_INF 0x0602 -#define UBX_CFG_ITFM 0x0639 -#define UBX_CFG_LOGFILTER 0x0647 -#define UBX_CFG_MSG 0x0601 -#define UBX_CFG_NAV5 0x0624 -#define UBX_CFG_NAVX5 0x0623 -#define UBX_CFG_NMEA 0x0617 -#define UBX_CFG_ODO 0x061e // not supportet on U-Blox 7 -#define UBX_CFG_PM2 0x063b -#define UBX_CFG_PMS 0x0686 // not supportet on U-Blox 7 -#define UBX_CFG_PRT 0x0600 -#define UBX_CFG_PWR 0x0657 // not supportet on U-Blox 7 -#define UBX_CFG_RATE 0x0608 -#define UBX_CFG_RINV 0x0634 -#define UBX_CFG_RST 0x0604 -#define UBX_CFG_RXM 0x0611 -#define UBX_CFG_SBAS 0x0616 -#define UBX_CFG_SMGR 0x0662 // not supportet on U-Blox 7 (only with time & frequency sync products) -#define UBX_CFG_TMODE2 0x063d // not supportet on U-Blox 7 (only for timing receivers) -#define UBX_CFG_TP5 0x0631 -#define UBX_CFG_TXSLOT 0x0653 // not supportet on U-Blox 7 (only with time & frequency sync products) -#define UBX_CFG_USB 0x061b - -#define UBX_TIM_TP 0x0d01 -#define UBX_TIM_TM2 0x0d03 -#define UBX_TIM_VRFY 0x0d06 - -#define UBX_MON_VER 0x0a04 -#define UBX_MON_GNSS 0x0a28 // not supportet on U-Blox 7 -#define UBX_MON_HW 0x0a09 -#define UBX_MON_HW2 0x0a0b -#define UBX_MON_IO 0x0a02 -#define UBX_MON_MSGPP 0x0a06 -#define UBX_MON_PATCH 0x0a27 // not supportet on U-Blox 7 -#define UBX_MON_RXBUF 0x0a07 -#define UBX_MON_RXR 0x0a21 -#define UBX_MON_SMGR 0x0a2e // not supportet on U-Blox 7 (only with time & frequency sync products) -#define UBX_MON_TXBUF 0x0a08 - -// list of NMEA message Cls/ID -#define UBX_NMEA_DTM 0xf00a -#define UBX_NMEA_GBQ 0xf044 -#define UBX_NMEA_GBS 0xf009 -#define UBX_NMEA_GGA 0xf000 -#define UBX_NMEA_GLL 0xf001 -#define UBX_NMEA_GLQ 0xf043 -#define UBX_NMEA_GNQ 0xf042 -#define UBX_NMEA_GNS 0xf00d -#define UBX_NMEA_GPQ 0xf040 -#define UBX_NMEA_GRS 0xf006 -#define UBX_NMEA_GSA 0xf002 -#define UBX_NMEA_GST 0xf007 -#define UBX_NMEA_GSV 0xf003 -#define UBX_NMEA_RMC 0xf004 -#define UBX_NMEA_TXT 0xf041 -#define UBX_NMEA_VLW 0xf00f -#define UBX_NMEA_VTG 0xf005 -#define UBX_NMEA_ZDA 0xf008 -#define UBX_NMEA_CONFIG 0xf141 -#define UBX_NMEA_POSITION 0xf100 -#define UBX_NMEA_RATE 0xf140 -#define UBX_NMEA_SVSTATUS 0xf103 -#define UBX_NMEA_TIME 0xf104 - -// proto is the shortcut for protocol and -// is defined as the correct bitmask for one -// protocol -#define PROTO_UBX 1 -#define PROTO_NMEA 0b10 -#define PROTO_RTCM3 0b100000 -#endif // UBLOX_MESSAGES_H diff --git a/source/library/include/ublox_structs.h b/source/library/include/ublox_structs.h deleted file mode 100644 index 0111de4a..00000000 --- a/source/library/include/ublox_structs.h +++ /dev/null @@ -1,70 +0,0 @@ -#ifndef UBLOX_STRUCTS_H -#define UBLOX_STRUCTS_H - -#include -#include -//#include -//#include -#include -#include - -#include "muondetector_structs.h" - -struct GeodeticPos; -class GnssSatellite; - - -struct UbxMessage { -public: - uint16_t msgID; - std::string data; -}; - -struct gpsTimestamp { - // std::chrono::time_point rising_time; - // std::chrono::time_point falling_time; - struct timespec rising_time; - struct timespec falling_time; - double accuracy_ns; - bool valid; - int channel; - bool rising; - bool falling; - int counter; -}; - -template class gpsProperty { -public: - gpsProperty() : value() { - updated = false; - } - gpsProperty(const T& val) { - value = val; - updated = true; - lastUpdate = std::chrono::system_clock::now(); - } - std::chrono::time_point lastUpdate; - std::chrono::duration updatePeriod; - std::chrono::duration updateAge() { return std::chrono::system_clock::now() - lastUpdate; } - bool updated; - gpsProperty& operator=(const T& val) { - value = val; - lastUpdate = std::chrono::system_clock::now(); - updated = true; - return *this; - } - const T& operator()() { - updated = false; - return value; - } -private: - T value; -}; - - - -struct UbxDopStruct { - uint16_t gDOP=0, pDOP=0, tDOP=0, vDOP=0, hDOP=0, nDOP=0, eDOP=0; -}; - -#endif // UBLOX_STRUCTS_H diff --git a/source/library/include/ubx_msg_key_name_map.h b/source/library/include/ubx_msg_key_name_map.h deleted file mode 100644 index a359e5c6..00000000 --- a/source/library/include/ubx_msg_key_name_map.h +++ /dev/null @@ -1,102 +0,0 @@ -#ifndef UBX_UBX_KEY_NAME_MAP_H -#define UBX_UBX_KEY_NAME_MAP_H - -#include "muondetector_shared_global.h" -#include "ublox_messages.h" - -#include -#include -#include - -const QMap ubxMsgKeyNameMap({ - {UBX_ACK,"ACK-ACK"}, - {UBX_NAK,"ACK-NAK"}, - // NAV - {UBX_NAV_CLOCK,"NAV-CLOCK"}, - {UBX_NAV_DGPS,"NAV-DGPS"}, - {UBX_NAV_AOPSTATUS,"NAV-AOPSTATUS"}, - {UBX_NAV_DOP,"NAV-DOP"}, - {UBX_NAV_POSECEF,"NAV-POSECEF"}, - {UBX_NAV_POSLLH,"NAV-POSLLH"}, - {UBX_NAV_PVT,"NAV-PVT"}, - {UBX_NAV_SBAS,"NAV-SBAS"}, - {UBX_NAV_SOL,"NAV-SOL"}, - {UBX_NAV_STATUS,"NAV-STATUS"}, - {UBX_NAV_SVINFO,"NAV-SVINFO"}, - {UBX_NAV_TIMEGPS,"NAV-TIMEGPS"}, - {UBX_NAV_TIMEUTC,"NAV-TIMEUTC"}, - {UBX_NAV_VELECEF,"NAV-VELECEF"}, - {UBX_NAV_VELNED,"NAV-VELNED"}, - // CFG - {UBX_CFG_ANT,"CFG-ANT"}, - {UBX_CFG_CFG,"CFG-CFG"}, - {UBX_CFG_DAT,"CFG-DAT"}, - {UBX_CFG_GNSS,"CFG-GNSS"}, - {UBX_CFG_INF,"CFG-INF"}, - {UBX_CFG_ITFM,"CFG-ITFM"}, - {UBX_CFG_LOGFILTER,"CFG-LOGFILTER"}, - {UBX_CFG_MSG,"CFG-MSG"}, - {UBX_CFG_NAV5,"CFG-NAV5"}, - {UBX_CFG_NAVX5,"CFG-NAV5X"}, - {UBX_CFG_NMEA,"CFG-NMEA"}, - {UBX_CFG_PM2,"CFG-PM2"}, - {UBX_CFG_PRT,"CFG-PRT"}, - {UBX_CFG_RATE,"CFG-RATE"}, - {UBX_CFG_RINV,"CFG-RINV"}, - {UBX_CFG_RST,"CFG-RST"}, - {UBX_CFG_RXM,"CFG-RXM"}, - {UBX_CFG_SBAS,"CFG-SBAS"}, - {UBX_CFG_TP5,"CFG-TP5"}, - {UBX_CFG_USB,"CFG-USB"}, - // TIM - {UBX_TIM_TP,"TIM-TP"}, - {UBX_TIM_TM2,"TIM-TM2"}, - {UBX_TIM_VRFY,"TIM-VRFY"}, - // MON - {UBX_MON_VER,"MON-VER"}, - {UBX_MON_HW,"MON-HW"}, - {UBX_MON_HW2,"MON-HW2"}, - {UBX_MON_IO,"MON-IO"}, - {UBX_MON_MSGPP,"MON-MSGP"}, - {UBX_MON_RXBUF,"MON-RXBUF"}, - {UBX_MON_RXR,"MON-RXR"}, - {UBX_MON_TXBUF,"MON-TXBUF"}, - - // the messages only used in Ublox-8 - {UBX_NAV_EOE,"NAV-EOE"}, - {UBX_NAV_GEOFENCE,"NAV-GEOFENCE"}, - {UBX_NAV_ODO,"NAV-ODO"}, - {UBX_NAV_ORB,"NAV-ORB"}, - {UBX_NAV_RESETODO,"NAV-RESETODO"}, - {UBX_NAV_SAT,"NAV-SAT"}, - {UBX_NAV_TIMEBDS,"NAV-TIMEBDS"}, - {UBX_NAV_TIMEGAL,"NAV-TIMEGAL"}, - {UBX_NAV_TIMEGLO,"NAV-TIMEGLO"}, - {UBX_NAV_TIMELS,"NAV-TIMELS"}, - - // NMEA - {UBX_NMEA_DTM,"NMEA-DTM"}, - {UBX_NMEA_GBQ,"NMEA-GBQ"}, - {UBX_NMEA_GBS,"NMEA-GBS"}, - {UBX_NMEA_GGA,"NMEA-GGA"}, - {UBX_NMEA_GLL,"NMEA-GLL"}, - {UBX_NMEA_GLQ,"NMEA-GLQ"}, - {UBX_NMEA_GNQ,"NMEA-GNQ"}, - {UBX_NMEA_GNS,"NMEA-GNS"}, - {UBX_NMEA_GPQ,"NMEA-GPQ"}, - {UBX_NMEA_GRS,"NMEA-GRS"}, - {UBX_NMEA_GSA,"NMEA-GSA"}, - {UBX_NMEA_GST,"NMEA-GST"}, - {UBX_NMEA_GSV,"NMEA-GSV"}, - {UBX_NMEA_RMC,"NMEA-RMC"}, - {UBX_NMEA_TXT,"NMEA-TXT"}, - {UBX_NMEA_VLW,"NMEA-VLW"}, - {UBX_NMEA_VTG,"NMEA-VTG"}, - {UBX_NMEA_ZDA,"NMEA-ZDA"}, - {UBX_NMEA_CONFIG,"NMEA-CONFIG"}, - {UBX_NMEA_POSITION,"NMEA-POSITION"}, - {UBX_NMEA_RATE,"NMEA-RATE"}, - {UBX_NMEA_SVSTATUS,"NMEA-SVSTATUS"}, - {UBX_NMEA_TIME,"NMEA-TIME"} - }); -#endif // UBX_UBX_KEY_NAME_MAP_H diff --git a/source/library/src/config.cpp b/source/library/src/config.cpp deleted file mode 100644 index 2a1f3146..00000000 --- a/source/library/src/config.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "config.h" - -namespace MuonPi::Version { -auto Version::string() const -> std::string -{ - return std::to_string(major) + "." + std::to_string(minor) + "." + std::to_string(patch); -} - -} diff --git a/source/tools/CMakeLists.txt b/tools/CMakeLists.txt similarity index 100% rename from source/tools/CMakeLists.txt rename to tools/CMakeLists.txt diff --git a/source/tools/src/cosmic_gpio_ratecounter.cpp b/tools/src/cosmic_gpio_ratecounter.cpp similarity index 100% rename from source/tools/src/cosmic_gpio_ratecounter.cpp rename to tools/src/cosmic_gpio_ratecounter.cpp diff --git a/source/tools/src/cosmic_i2c_test.cpp b/tools/src/cosmic_i2c_test.cpp similarity index 100% rename from source/tools/src/cosmic_i2c_test.cpp rename to tools/src/cosmic_i2c_test.cpp diff --git a/source/tools/src/getmacaddresses.cpp b/tools/src/getmacaddresses.cpp similarity index 100% rename from source/tools/src/getmacaddresses.cpp rename to tools/src/getmacaddresses.cpp From 1073433224f92a8e34fd88499f7db0f8d4477853 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 16 Jan 2022 20:52:08 +0100 Subject: [PATCH 33/47] deleted some now obsolete files --- .gitignore | 2 ++ source/gui/config/muon.ico | Bin 96062 -> 0 bytes source/gui/qml/places/doc/images/places.png | Bin 233430 -> 0 bytes source/gui/qml/places/resources/categories.png | Bin 130 -> 0 bytes source/gui/qml/places/resources/left.png | Bin 141 -> 0 bytes source/gui/qml/places/resources/marker.png | Bin 752 -> 0 bytes source/gui/qml/places/resources/right.png | Bin 147 -> 0 bytes source/gui/qml/places/resources/scale.png | Bin 98 -> 0 bytes source/gui/qml/places/resources/scale_end.png | Bin 93 -> 0 bytes source/gui/qml/places/resources/search.png | Bin 259 -> 0 bytes source/gui/qml/places/resources/star.png | Bin 1403 -> 0 bytes source/gui/res/muon.ico | Bin 96062 -> 0 bytes 12 files changed, 2 insertions(+) delete mode 100644 source/gui/config/muon.ico delete mode 100644 source/gui/qml/places/doc/images/places.png delete mode 100644 source/gui/qml/places/resources/categories.png delete mode 100644 source/gui/qml/places/resources/left.png delete mode 100644 source/gui/qml/places/resources/marker.png delete mode 100644 source/gui/qml/places/resources/right.png delete mode 100644 source/gui/qml/places/resources/scale.png delete mode 100644 source/gui/qml/places/resources/scale_end.png delete mode 100644 source/gui/qml/places/resources/search.png delete mode 100644 source/gui/qml/places/resources/star.png delete mode 100644 source/gui/res/muon.ico diff --git a/.gitignore b/.gitignore index 41be2edc..92df0ce0 100644 --- a/.gitignore +++ b/.gitignore @@ -4,3 +4,5 @@ *.stash myon_detector/upload_script.sh *.pdf +.DS_Store +.vscode/settings.json diff --git a/source/gui/config/muon.ico b/source/gui/config/muon.ico deleted file mode 100644 index 83b24830aebf680f6e3c07b7675f30e1d510d4c4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 96062 zcmeHQ2YeLO*L}O21VU3p5D)4AL$_N&pJ zjJ<@r;krLku3w1#H#mMD`v-yH62NQha6EU%>GS)0y^!hgfB3dYXE4u&fu+Wn|4%@Z z7GT>SE|xNKKAv|B+e&Q2U~}}T|LFRS$Ff8Mf8H z$$uHaN@iS(e(l883;k@0Z{gxm_$Dr7x^S+%d!O9`zIZSXXht(^Lx2tPv#|MK7GCo= zaF+nwwE)d4G<^NO9Nc9ydPiA&_{QX$F;D$~lVe$kl}O_HKfF&IaMx_o_Cq?6J*8Wak6UBSXsMp zw5(nZWpLoCg7l-K_oBr(-u0Jv1 z4mmXKW!X8WyMfPn%NEO+HQRx|3}KM8Zs^F3$(6b+`85Y~nS{A9uzP_|UJW`%KKW0$ z7#j?^EpE+L(5RWRV{T75I;Eu$6B)r&xYwQre*c*CunXqa@y0M3EZ8BuK zn`pZ^SLEsJ-p}znjwSi!NwYmvFr$Z9S;>_gV!g^)Rn7c^ZWsFVq(Ly zO1DD6mfJahkG};x_iLHGd}+A!?j*+PJMh**({~-q!CV-a8;frgIJ+C)>$XraHe%f_ zgD)MP`mCHD8i#9IUk;2V z6~Q(pRE)*1-V7SnU;c@&mWnUPMSqV_lF(7fn~l$|OlD#wQv3hnipsCEzl2V_G91h; zg)CR`>i#owXq<+|Z8-8LX<1XyvcsX^Y$D`p>UgK(E(yRG=XiThCC#cUL4t*B?tX4# z&5GH5Gv1XMzbp?GbARHSeG58~C#z{lc6$EU&HFEcemOW4jE!5p#lYC_Ml~V<(0e>%S!a?m&uP^&rhroccm>Z*jO$4X)biiMp}$<+>Z=`Tz0<_Puoi+-^}uoe?diw>0Df9 zy>tFz&7^bx##fS+i{b@-lwg=U4W9Z{zcu?VD4yDP^$M0_>e3ZLped>xa;%4hNN-nP!EqTY4NrSVz@nxiG zH6^FUoc}yj_YEDI+E&IRcED|%p)(x9-z%Te*aWfzR?^#tWxtEUcT@)Nx5e%K$pikF z^k`6=(RS9bibwJcPfO2C{u%$;g^4p0d;i4WBny9fX-H9PV&F!9DPII3t?O9 zgfr>@$q8?ThcnV5V68(#&@~5Hjku$YP2HMXcEBDI$~;^s=ln6LIb!Bqb%x)8w<_n7 z>^5QRfxMt+j`}9!VGmAwA>BBb*g;9mhnMT=T8hmh_WP^knLGSG_zML~p}gmx6YmrH zlAUM(=IsFF>yqaJ-r~0&@SwkraT=r6CL%UE5NH354v+rq{SLk;(5?LQD!Ae;`pu&9 z;Uig(H_DE?`zYD@ZPxdNc>HsMJKli9b@WkZXS{*_GA8Ifr*CG&y4|2>?E~o9??aT- zx?0Kp@595}+lUp49e9;1*78Gki|$xVp1EB~Vz2P-9}0~KcFw=R*m&4p?!4Y(_-WPs z`K4l6uc1eu&SKl&pNJ!6JeJd3fnLNzugjKkaFcc(WlT_Gr@k{cN$YQd{ME6El9s^3 ziD9ARVfAOAZI55#-=Z_g{=8?A_Q1Tb-w4ux;`EK)?&_~By8xr2A zFGRmlRGz#QG_-$c&uCpQ2K~BBuFhRUZmXc=|84_*(8pozqGZAQKH1gVBcxrr{*Hc0 zNz^N_0a|>troNnSI&_!ol)UB}D)0E>m52n}3_v33TIC z2b*pRO*7}$+~@97TJE~h13D7?8HWdXr1>p*mpKaZ%`;^3cj!6Q#!EL%aE&V;4<<6)U zGOD(eWehq;OfYUP+R3lMZvebhfj*A)98Po33F^4i_qCFh-Oet3TeEPa6Kxa3 zeobATbUe#rky2tEwfUOkA$!s<7s@wD9qmr_H0Z}^>8K`1%Q_0QA~@dqJfkFck5VD= zQ4?$2=k9x@+zX#7b=qM4J2=2257ms3FTKcZ$LYGQuV;hYcVlsbzV&O3KJ_l`+$UlU zGU_N#vi4qsJv*h@O;K_(O#M9Ad$|3ban5s>{pg4{(32KDmTtq_XALif+!zD;x)GRYuSZoU+4%L@rEPyr zsEd4Uecl%4`S|b+NmpbA)<&$`OWw)cP3^a^5&4-`OoZ~AKK1r$pn)~wt*2Tex0Jj= zHhqnQ6j{i=XWUTvD?CDZ+e)`W{mpoB^+Z8=qmh!|`Zzy_&)xsMN19a6CtrJia>U5n zzOm3Jypnf9S?B%`YY!?J;`!C_KAn7%Wa^tf$M?36L!^$A;LCB8-8Lk}tv`GmgLHOj z8+d0a;OuW5)@CBt$0_&3ZA>UrUlVhq#H+u~;BA0Plo}V`>6$z6d_Cx+nmD#l@kU*d zJg;z#7>RpDiJNUXxxYsmS1l~vy+3PlGF_dLXMNozx!*}_u9lv`8tL0` zwO{J0mO?wiDVq#Kn?seWK-Z?hhULO9L-`wZ4Ar`jbcL_spOMZqE(v&RRJpkH@GjS4 zWeRlGX5J2x>ywiDJ`rn=#K-{8HtqGqT2Jo^>DM}Iuy%4>MfgoOYVn47-;Nr0xy}~e zpqJdN!x`H)AYRJ+KGL&a_a$;W)mt(Z<4v5I+c@r|H2S zXdHc8uiUF-PhV%e?d#`}dn;W5eyW$>#;apeC+2a9?W^%^5NnU+HtZ+Fm2Ue6IHoNn zJ!2S&Yxd1}M~gMiG3Ni3vw=0laWemDi4JR%R;@=psS+6)AM&q8mAx`lC7r>UiMPq% zPj9NR@>FdlN&Wmdcmw%UvHh=%9M)3snY&kMDOEX2e(mjyH}ccRZjP0YV1Lu$WhC^> za>Z*)o{=_tGqKh@FYIYswAb-opLu_Pe=F;-27`<+e@!>fXxk4PZ@$dN8~Ak--Sb&< zDhWBVk@%(Wg)wR#>Yy6id?-9K*g3SrJq2HZn{D~`!5(ST zKnZ1e9o`1O_FLqJGJ(1RvG#a=>F3#`y@vPsz&rh{+jQ-7cVc2=N1p<)_Ws0;zoDm@ zqbGFyaVKfo3LVyHo3Zyby~oM$A>F7N%0zY25pRRkZn;f8Ceic*rH5CBcumx6mtoGG zX&c{>{?g}xx31n9TI`U|Mm4x3)sH}|J$VtZwo!XNu}0t3w71W`9%`Sn)$sY~<{NU` z5%9Q7qiwi%ecf}ZBOjjnT*R=(_oY9+ms;V(u%4@%xRhZx-u@#Kb8`pWB; z4IWcYAAL*2%YEXVtHn=e?-cPoa{L$v?M(cv@Z}eLd^boJX9o zy3iBe56`+S*G|*SW9oalc}LrR!n@;xg*f1K*i59QgJb?k%F_o0ieir&W{;XcHx)UW$^*Z$!!5PV{s6WFg|we(dUn-ylk^ zj;Cu>mqTsQyVb&IiK79zt( zQ4={2o}-OT+c)FAkiK`b&*AKMz#m^vJ!AOei7BV;3-yykwYfBGKAP*(E2Qpq9vShX z6591xgT~sw@1Ki8j2ZGPJ;-;1KZ!PqUfxxPkBV_c-MsS+`K+rqK|1>4j5xG*zP|FD z?;H3IzIOC2Ojdu(!%=TL+HxntmKa;Gh^XArz_U+gzvq+r!19t0eMbDp=I&nE@vRrJ z#vb^KJwn^^5yU@HUuI6I^&KMh`^1F19cwp0zN#8AtZhhsN{4CIvCgb_;~4RqX1p%_ zR8BZ!JAGQkiQetl?>9#I8BX@ab)*Oy+bgc`bdepTU>k z#XC*tV`W@rdtZNf0a$M1`&ORteJJ<)UY0vNPf0b^M9QfKa=EGv`-?Zze}-wt*jWjl=0WtZknEz2iJN&0o0ftZVfWV%prW#=o^w{UvvI2cM7)d-l`k9Wkql1-HEKpg-gYUTE?K`yvaXQ}Md=z$HZ>vIx^T))5z;FH- z%GeHPoiQu1=Jf1|umv?zFUg`0B5N}t4|B?gft*z@qgVrdY^|edbFmIdD03Bwb3TKt zPG5l=*66>wMLp~s?*W@uzNzJmc-bxwxyN$Y`<&RzD|N1^;3&&G&3RU~GdAwt$`?gk zw{X-Eu*S*IwR`XZr;oM`!`er{nl_#zarW0|4Qp$^P|!8scEuWT_^z5PG4ES!ZKxxY zXT&v<>(dhAMb1@?avm9rm?5_q4m-}w<6n`-(yYcMhK+Rs=tfrJD3oWDx85B6AmWZA zYd1MMeVU7OyyRXk{#1^^HHpU*QYRHL4 z{Zb$D;tCe`%Igi4On6-x@s>_GPbQv%?SJd5q~^6zQY^ZHv_^~?^-sp>G7fE+=QpJD z9hPb8ziflUO40R=_|9PO74F~tYa6AFk%c~5DZN;OUZC|!alNo``2X*JPiz2h%)GA-mzsQwjb=h-AYRIYsCy-fak6PqHaLW z@s&z0yQHk#6xBo;t5*;Q^`W%%bb}4|TZ1OP@0)7)O+WR{Gjz@Gyc=bpXS)pcB+5w7 zKH&8T{J?)Ars|}DTVmJ0okFhFDd6~YNLc1QpQ;_3Df7hoymtD-W7uF(pe22D4Kz)g zAGK-zz)X1uxA{+kKfa2(UnXJf-DunAY6)zvU?3sL{lU&5uN{V15?|FA$@LX<+}SQQ z9Uu=H`Nq&a7>}NBQaK~GBhTn-VQ0QtV!yjea`(DYa&<3-S|nFU%sZDGvAa>P6ct~K zOGVwEPZaDssus2y*eYSW7O{Dk7nI8{zD_Fo?vR_+LvpuzPMZ1NkOyJEenh<|kE;*l zaZgw5yUPFJ_y4Ib^00bWs(2c~?+{ttz#OmSgbsSF!CtXx%XSQYcz7GS`d7+oKcvNP za>V`Y<~s!2Gghs)+Te;c##G*LNhSFsgq%OO=h5y)`&%^PJj~kS;rhEmKHtPC_X|@o zOKdY%*uXC0j;Y%)XQpaN4{8B>;5+lmdgLyz`_jMXZ{{*@`^GB=E%~Z$@0p&zog8-! z?7C_5mw}fP*uut|`gk$zYNza28@V#r$ zFUlBg`|=4Txq{R}3K>f_`(8$`Q}y!5z7TQ^!x`Uj&z97@)J*k zSoq`Tx?*h-Waz4@sZgd*@3SASiQKI5E_rtmrd8o!js6kpO7?f7o^8~)iGZwXy*KN5 zy#{?=)z4$BhZ9vZm&6bHSc^622i?d;0fcZ_h0&`!$ro>-VR@8|1aQ)3zT(CqmZ` zfU^WU)_CtfCN)m;J*D?uoUYsOl``^Iy#Kqzh`D7fWV;6bdU^E6Gq+`++T}{yh9Nhm z;f?vy<=c$5zSpqm?zE9~Jqhx+(#Ey zYKSY=s6RAO9b`RXh3wA><(RbrRl|G{%bQ_-eQaz&X{kP!s5<#2)}fBMiA{4)9XQwL zS4hF?G4d^RBYWHv--U8%=VquO0xZP#yHZ}hC$uDr)mMr=o#wbhxQnr?YJhz!B?e(C^IjEBt+-x9}~bqb1CkA@x} zh!>9cjRk52^~Zmvew3aq1Fv-(U+dpUKUv#8<{i*BeADLKXJpUXMU4GqoB(sHeeDW4 z=TM_QE7#b%?8a!rHf_kBar$@Jh#C~?K71FbqshLiCkx8ruKIJW@96fs6S3PHd=v5N ztf@E>G|tQer~Edwt&(rYj?>XKwqfDm(0C|n!d#2<)2vH2Clho~%4N*G^FoggsN2Ui zF+f+Ae5fC@Pn#?GN-cAxZM3zOEm%6NdX?7kCoS#x0KV^+kgJs*zGvfy%)z-;J!;6B z6V$)Rm6$9ADijO zd{Zt%H}WC|wMUCoI!U|Z?T9apdc2@Cc;Z?33X;>{4SrDs0ELD%;?mAPdAxMVjCAoM zr*|XH7{lRxK6NcdbG+y;CqH$%b`AXTkEqVBSfkyojp~yjTO0K{%G>JUiws+;*}wGe zy-o5Obj`F04phI&?Y<`@26cT&LwMiZ@GW$HFtk{dmE9myp>Ov7&@K`z*U&z;{I(7c z^v5VG59^jFL%*`>w$y(qKeOilJx{mQVh!@wOQB*7vRw@w)>bc?;5hg8eur{QpSX{) z+ob(g8o)dw_=ViQY3lcND=J}bi#cz)eQ&i_PbbX4Qu*Y=|@1H zt^IfTo%@?o^1SL5&}YWxwNzigS5?rUB_;5jQ0z6#|9P+m>Te;I#oia{i`QT44eCFk zAC7kKc6TW$idcnwSNf1ofm-3f9p5`(d@zQMD#I28*(Tp~+`m>m!8)*M=o+vSat#K= zz5P#zwT%&s!zF#csRG^&V`3jC@|sq4g5!fVh2BvU1Ln<+H^#NqjCvqIrVSXsAabPj zT-IB7;#Tlf)ZGoYmZkZQysmhW3V{CcfPS;a;ah5)sEbhp@Fm+EJM=LQG=_aK?`_{x zkJj1Y_)e6&mw%$cIjs{cQ~$x8fT#{nh(|`{ReHWNB0-H2EjgcOZ|Wo%1z3|AtbCC2CT@pbvGi zmI3WgjCETAU9cZyy+^9yePL@?&lQqfAC)k4+XvKZTCDLKc?I?y#zndHW$eq8n}XQ? zsFT)-4XC&DJM2odRYp_4PLU5u51Ehexh*&R_U_MR9Z$2i?2##tX|V=6H9n(Q`*k+l z57xO($8XLN?SVSpY2^WoX;6<{WXvUNjPg3GjB56Sb&y-DZye{%Pv1_<1F*HZ)u%M? z7xo@_C#@rYrOvEdqk(eIVc2OHUp)B@CH-3~sa6{LH)1>e{R_-ToS^_gT= zwLElp1h7V%RmioJ@m=N_0@(n(NZpfHZo5)RxBpYZZ_9jd@`DP6OQey1>~q*nElRho z&3slQ_rt-5yQrC3tg-Lp`^2UFnbeosLyphg)4d)wW9FLH@Cet%;XR1=j~@dqw8qG% z;EmsX4am;qk@n}g9se<@i44;CsUm^3#0+AMeiZNRsE1(JJ8j>X`K<-)fjh1jKp$lk za7SAsYkttz@cna2K2q}>=Z$kmS-fiTvRb<1HlCUFH^xf1`E}`odm8$YsS8q;r!G|V zhA7GXHR3ig9s%QH8AHR)4}aB;o~hVb^%?j$>xXI9@M6q-de)Kteey$@M%Q-C{U$8j z+vjNvWDMHPoW>~Rc3_qD{a6nxx_p#eS3=1>s*Nkwh_}|NC-T@*$KT$+vw2J#d^6Z9 zhN^wqep4^4g_>WcPbi@yumYJP6#bX}2CEOAw7)6zP3kde#+Wi4zJIfJVmM=Pc*^5i zc@6e8ES{1v9=c^-?+jt>v053dp=|kf&x{$yin^b-ZXWpKf7Q+#amJ0dwm0F^3uip- z=aRm#KHSoe{PLGhhO}R!J0`t)5&9-`zs&yG_sp-D2pi-^_~<-XPb-*wW{wGctrbv9 ze{dUR=vQ3ZQpY=aKC#=dd@B9a_0_5E;I!6StRW`~KnV?N@G&&h**w<$Ff85kMA<&3 z4%T7R;UxlXl!ISY!yV_1^T=FY=o?yIrUI z8-2W7m;QFolaBFGLHs$UjQ3wun>{!y2Ve#_bJs2hiH+NigdRksLrI6Hl?9>1;P zjT}C+U!m?rY`9_O1;3s6i0dT3s+M=Ikhut5uf20SDcX4{(NVI#N zEg)a3<&N{lIUJ()O4DlLub;@Zh@5H)(nnMnah$Zbo3gz5-nu>Q^{QzBLq}pv8tYA4 z@n!w}4)|zHSNAobGdgzE^;_H)K5e5PNk`XU%MCdWeDd~#`Eiev_WLBPSeY)YQJ1dD zH3-tVwo0gDNjlLSIcwIr(*3?4d7I(b+77_Zpb$Ui7VBZy1DjuL#H{G>Wwuc#Xjs)F zd13cAJ| zsx<4Fja{<^IaDae3;8&ljj3o3i~N<8l|;>Dpk_VE#A6b@R;r&|jMiu>)rOqxJnV z<2U)-dupoVyb*7-wUsY)RY0t-*8I3U&qC+ML%vZJ=cg0yA?J@=7Of+g>koT zdJTP~hMX8-e3{QT_l)1TqH=V|HCrd@*LL}L;JSSn<p`retD6s} zHriX&(-B-(CCGSlzL_7+Tq=`}>GrKu563u6-Mjn+8x><0eTtpIV=JXF%dqmxV?={G~N8<0a!BvIcOIx$G-}c`p<8PFq z>wZf^*AS1k3w6}O#o9Y|y2j&eb9=e=A)rt26}GGIU_;EraZ?X@q_5iSiZ#}=5615T z-UT?JE$!W=dVeD4*`RAFJd|-^jMumpYXF*Yc%+YaB3?Ei{y1eEe291Kqc%DAnQN=+ zu8Rb|?Dt?CF4`*Cy7;Yia+W-W>%RsP4^oCa-De3y@pk z53=`{$E*+iiW=&OHRd43e4xKpcfX9b(I$5b@W$K%-TZE!+cOPKBVK^Dcf;YIJQsBE zavj#Du3U|0hgQ>z>*9G4%atzzvHIbR9c|%-N|p-hkEgAHaY4GVbZhI`625P{%?t7u zeb_1%@kI^t8M#l)X{Dc>d6taLC=6N1$;ZUp(Hm4fN8V3gma3y1`FA+u6Y9D2KipZ# zBaHvGkH=3-60}$Yjk-5ntl=8UZ2QvUZC^;W*ZeipP^SR#dZE5sB+sL-)F~d(q;ZC= z4Sqsm!9JF5$Nt<=*yADFP_B=D39*rP#29sjlov8X;ew*Bf}DDp-w(z3amKe8wT@h5 z2T#+yj`}EVBK1)d{cQ13V=kcAtDAG5iB~hnwU;fH7$tK&o%ZA@U5OiC0ptFR z{rOt`V%UheX3>-sI~n~KjM4l?t(FdIH0rB9BEDt?{CRK=aW0H2!9Yj&?(yJu=dO1NkOqjnT2axTlK9- zkB961fN_QO;|HnV9OsU68LF*~@#bBCv0GGg`2cZeqfwL3js>@4#;Ny#@1M42?|sO% zhOOS-f5wVeSB)KG+PTi9strEsfK~hb(tFJB)OUAY83f#)XJ&~~ibkD2osk@z7Oo)c^=`TW<_NLNgZRewm85|^d1O_=XPJO9)-;rEDXAdI&R zR%_4=Z|2`vL#__|oY8NhwwqO!<@W(UsndE6yo>aVMYz{cRxcNQ zEBx{Qy5g;s>aMl5@tdYT`50(XusU2OjzZm!$NC@b)c2wqBUZ?gOGf`F^QoNf(^*Y( z)MdjRAM5$Kzb!3gDn-c@d{?yB*zsi^|2M9fj6kgo9Ss_@X@4OTJK^q!uGvl7$2YqB zu3b3Fu|M=dMebx%ndGh5FZ}q<@s_qB{9UGlP%j{-UH2!$Muz#FW$ix0xSmaR!>UP<=HAHwa%= zGp_;G?$BXv{OV2GevuY1XNhB$Rrs<#m+`xlk)~o4oaUccx>4PI#^%a#W(-tQ^(JuU zP7|H(8BRODg_s%_``1n;ABBx>u#23@nz`Y|vsuT){+l^%jK_4sm$jYick1u}+5U}_ z8NeCw1|2pU_uj9&|AA@k)AVn}r?6pSZA|<7MEn?YLVJo~Q?bfCcKMEVXs$0RBh?{C ztPvM)s4)ir;JDI%6{tnzlY^{$SL$N-xH&*8ywV*va9j1^xH<+Nphm|Fgk$u-_tHAmVh)La*rO zVeMpNT<}cFR;-gnyTr0j{P{-jKZIPqtG%d6S=#VZ`s)L^`{VCXFB-YHtfMd>NbZ7( zH_BD?V?GOC{&j_~GHM33gneIKo0-qC z@0rV!XH*2^jPU(N!=A>xK3(n}$9U4pby}6>|W3JmB=h%83 zZMDs?&OlqpSIk4E{ThxjgBN`P`tC(ttJv?al)NLaHR@%sRz{`#cS%pR*75#apYk^E zW60IX3p$tJcwVIWs4*{~lexgZ>%uR!pmSiYh2(@cwKxMNPK@2W|DufG%X;lm$Ze4Q zp4VY*-0H2UH3?P?+;g0pRLgw5fPQM`B=cLd(s=uC`u>~W41YKBZ#jnc`ao9P@Hg!m zm#QnV*2*W2b8KGI2XQ2|N>nmx`s#dK)RAbHW6d9<4g+jJj0s>ot{3%gJE&2PJd$)$ zDd<>OE6?;pn9nu$tkD`%3$?Hyw`TbJweSqyi!lVAwwGdECWUpL{bS7auXXbeTztnm zq*lCS^f&7NPXsgq@ND;KA1OWKG$haen7i&*~>jrLRED2 z$5U5*8Z}1SsJ^aPBX6r&;`*R5UT6A*Z}8v%CI16oWDRfTE_qtymlq)uI>~V_sD1|C zMq!OB6JORn`+BcxtIzqgVMjZLA)G^7g1R$SmJVtIoM~%c$*>K{l{1Ph`}KpdULSDw zxejZrZF(xMq%rT5lQJD^{PqxUeHZeVbTJ5L=Ga2_h&lS0K2-~~b7#(Df3-d6IZvpM zgmK~a=a7do2beXObag!#k5vCg)Rck`h;ho^mKQntKk3i7N>y`>A29eR^q%x$DU|Dc zZ41dK6MO_*Tgs_FtUVJ`J#+Y|F~+nPT~}1T`+1v|e?lj?%LywPZJ(WZi1v@(I@&gN z%{KXO{0(w_QTT>u`fG8Tn9%N7R|4-s`xx~p*8ZYALwg1NnA}r`jD?TdSknS?W0y@R zSKNkpK3#2W`yBI_dh0{L0BsOX^B1iB12sz+muJ5}Wy4A(QrCLn`&^E70T@qY&Euo4 ztWbN(d>8r)uDZOs=y)aLMp!$`$%nwc-ly96>0}5zQ9BPV*ToLJN*c9(SzD(R7+40G z3Oz`_pCH(^klRY)Ie+W$wsz5IBQDjbA8mUF#?%u_{O&1hsfy83qd00>RQAVsajmJr zZIv;P^vSWl7~>4+k8BQFS+O``5K%KmwJv1XI`hW)^?l;<`{&Zmy&VhYG3E8wA(sck zl+)k2)|GA@3)aLkYO`40+lZY+9v^LvhK>rna}7Z1Hr9FPcg1z`bkC$*rfWCbXvd@d z(0ac}{r0xHNZubaLrc?uvwMPJC8K}ecl0ph+CI}^ZP>a!vT5l5Nuf%q@uyrDj(OGh zLZ=z{yx%s!d7=Dd*r~yH$$L#KX!rO#b3_=o&zj8B-$MPo8kk$G^T2T?9<|q52&OVZMUG|MURyi6I+D!{jmmX@RE4{GKsd-GBt$n=(K6~zau&sRL zoS#lV2G?$I%E#v4=_^Q2%o1%QhQ49NZw7z+kPrLTpz&IohWW2yV&QD;p(nho!y4Px z&*)*`jW#gWP^63!G8QznDALywqfe-h(}lJ6YM}hkCGGpLra9}^1kkH6=iB>4fuJ!d zCg!dCu4*=F)<>>Z3hM;k()bb3w6wlY=$?beZ{Cjq$b6b+J_B-_54=?COBlKKS2;1U zakj#j6|dyowXTM27-noO=l5eZUt5b{G~`RlT^Yd|V|6L(TX7W1Z^jiEe3bfAnE1Az z&w7f!+Ii%&=}UAp?HJ~~u!(`QxkudYZBDdpHr9kc9hW)ljazY(-rua{&A7u*=F)l& zV`iC`XMZm1GV1Ek+UL^s*oY_cImYE$`(gk6fO<9Kd=zq{?|%j5#U2B7IHTS6#UZN_ z&nitb@jQaLRt~Y0#NgT=Mx>b&`y6G}G3%+;_B403C)nqc$CRfkM%|XC=2`-3mPaDy zowV^KH7M+FfNQE|wB{J=I5chdrVL)YHx1T6&lV0^pM+%1v&TE_&w}4IANrw<6Cb*M zuOubBm2L6XroIQd-`I|N1x#kUHH9l8Mg)tU7T4ryfAB%NCt$knjCF~i`WH3e)JTwNiYZ=qjL#+y_ zFV?;_MP2ykTu1t-`!YxFWIca8F**Xi(@w>WeM-J;}LX?{)G34E!{R5 zaZmroR|}XM>pW%UZ`w|{#wgcYE*D$X@P`vi);Uc3`?TDRwVAn=qS<%a3yWQwv3g9* zW4f!HGU`XuW}No9?si?~F3?tP$CBG|F60_iY0yx5E#9b|JIF{A`>p#eTj0#Z-Gr?N zXycu$!y4P>VLixGaYfF|jX6izX-~Y6H$Ho(k~>hVrHh&&W7JXYoOg$P?#=sCvBvjc zojJyFxXrEG-{=#fkAZdcD=6BVPimj-gh4+a^@PSpNkg$-)g6yMEq#`5(c^4=(r&Cx zR=}L&?6gOYUm@Tv$q8>iE}e~-vs~F4ZzlHXH>WSXdZ~-0h3ba<^)&%=&sd;(s#Smw zfpy!2gan_>3K?MI}0aYuo?1kXcyMq|4bYF7E!3P@<7|y z<@*(hTAX1H|An2QN_N7Ry)Tg6t_R-!a>Cp4#S<}>QRf8SIOl)E7DxXRYhhK*-N49! z@vlj6+K{QZPOK4&o??Tho%kZGV`1jtotfVdu&185IH1lRYoO65T;+-aM(!YM<_D`Q z$Jk=0HRaeB=3saqzerlX*Hs3tNo%W3nYYuBi5{K3_pfZlJMCE82AvrFZH7&&EAU-@ zSv&#sE&80nn?dW~+oC^~>-IFMuH=5iUoa2;9@Grs`kTf%Cf>S%zE$!Gd1A;|gB`Z? zJ|5?kp~qizW48|yYOHq+2gVL$UcSwPx;{J9KS zm)5S4f-}T*Bz-z{$H8okGZS}-f1XsJzi*j+*X>E)PRHd9m?P_aW#`|dWAwjsUBs)4 z_s;tYIgXzx{f&Iz2EcpHNL0%O{E5EFZp-%iC{9xzAN z`8pSVvsNV69pc{JU+Nm25gVXTvy?h!8oaS)+syLDI%W#%&MZ!e?YG}YcT7JUYu9tF z?(5Y(##(92K_J%XM`KKl5kCWZ%ySvjGZ+`JS}DWmkKz)BJ|p&iFg7b;mf}neX^(I1pc4dowLqRi8sWgP(OVW z?{~_4U)_H8@}-D>Ym|ex6dOu7xcnFE4*a}invQ-2v_Y=vJ7L>F7@p2u`7Bu9<2FNI zSfA9y&E8A=jar*1JLi0zgSRm7mOQ_7ImYCk; z#v{Fr@o|;mIDX_0yJmd~|JJ$VPYp-b3jJJ<9GL!!B>aL}_ZXL88+3qSz*-*N_+Myk zlXv~Wc*|Qc9*M!mjenoMVukFR@eVKtlaTE@Ki`iJPkmMv{JbD2zEZ~VFvhh7a_lY$ z*({vz23X4r8pj$AL1`SU~DFM!F4%uS;plB*p285 zlFlA{_9W~#NeLZg)uM4SdF9%$@s;xaOMtO@6Sp18(!9;A;(wX>-1trVXdmGkS);Hy z#{IhEaGy*C?O6Wf6iJ-(mHa;WG5Ig9bf(h2Q*p%+$8xXi2G&jb#> z-7mA@n_G;n0nW|gm0|MAaPbLUj5d-o81Jt!-hYNNKThXRx8SG8tobOvZ0N!gXZ|fY!Z; zd06Q%M`6j=)_V{igV*nuK?WXo%Wz<3_;FDY8ci5qmDRe!~RI%DNSGT zUWwScqE=6_ksEX9m>mOIam*UQkX4wnIVg@r>G( zTog3#L16BE%yj~`o%kKpFP2V>p2GbP;@Uabe~RZm3E95P$W6(f?^o?QZ^kxHrh302>`ZZ~9|+tk#*ClAH7^mXvs zyYRc_)a{4zV!cB(u{R6Ngw~&&^DgXhdU3=IH7oJ3n!N3xibK8FiP+D?dJi+U=hz=| zzKsj}+sK*!ocYheKn@0SFpz_R91NUS7{GJ}{7Vct@*kYlw*M5%ml*%d=bpyetz3JT z|ID^Tv?+g+*~Zh(oS1UnQKOB45crqUHs5Gdoh)tsOU;Y@=l$(JP5CV6C8o6bpX@)c zv)NXMCmL<$?NV-NwEbtE=D(rQ=IcHR2e#GGw3T98;Awb~MB8idMf7cfuf~^4 zw7o80E>QwsSKsErd4WT~K}g$%r5poijs4fPbxM@^ws%twZJq7s)k(AupHjNEQi=BA zQ!3Q9ixLCT!ahX0Emxv_iZDqLZu4pG=S#FtIVL@)&0!4E&XI0RBRy}qH2BlCWek() z|32^?b>=r={ipi|9optwujB7ddU}v(KTq`ZB^263dSwT`6aBMKx{h|T%}yjpi|vD| zYcptj=fIb%!)xaUwsm4#V(>Pcq~}qAFAQdj^8#Pa&+`Ib#NQV9A`o_PZD5<9uLgEH zh5rV0x|9FffLX%5ct2|gOr59VY2=cT@JsnoVJ52=&dX1<+Yuruy=W~hzZrQFZFp>aF2Ev1K@cssMr-$SE! mXWIN1moiQ>&oel4ia2?ujg!*Je_Co=$}xBT{#hC_+V=l1WBMKd diff --git a/source/gui/qml/places/doc/images/places.png b/source/gui/qml/places/doc/images/places.png deleted file mode 100644 index c8ada27d9b6a612405a6563e54ad54f9d299f66c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 233430 zcmZ5{WmFu&5-#qp!3j>#Ai>?;2~G&^!CiyP;%>p+-Gc>ZaS5`x!{RP)bML$F$D4EJ z%+73|mg?%NufM8}R8^KiM6v|+ z3_fn^qO)Bp+tfysXs$#F~{~K=iC59LM|@^Y&dAOL{%zhkjuX`fd+ZFv5v%oVY+~3Soq*y`9e6gL~AZZGoV{Slg=+wNHG8b zoY-#Q zO?<%`L7CG&1U1_7isv8+;UBWd(4T~HHle>zrHKAwV89C_Od8wuUgGXZ%TF*bYJkU+ zlERXL0S!CZeJV!&bAMLC&gHCg!ms0t662$#Zj>T*CH!eS%JRnd^XJb%!&7N86FXo{ zE{tL3hXGO$(78{%h5)%j1Fi*M`4b9NaK*=>>$Xu+6?o!5n@B4`eE>Jz)S)X=6-hiP z!6jNG-(X5nEI2qZ$wYHs&`$YqYd$SbcyZ0oq0-;NBsL=N9IN*Px-EC#jq19j`3R06 zl7aumb37u3<$5c!^vQgpzPsw?Q=KDyu5N|~UD?-PTmY*gUA~4WLsQ{Isw73rgZYIz zW^Hm0oSL1@WurkNA%i8cWHW8j0G!Sip;VPT4-DmJM7uXsMggD5-ct zPJra%lW=RmtF7QS;wq7S4x>6(wjiwMJIGY*t6;&6fMVd-jl^r^$q%i9`ZUKyjNf?mpH4Wy1;vp*KnGFS z?`g?PHN?sl)f+x&~-*ES5@ z8bT5eJp1d%J?&xF6ryb6=>+T$zAg_q)d7-#o-D~uju97Xzo%B}kRvsO)dU;neFxvk z-3h4>M(Y&AIVF{r} zB5_BqkTfD5c2`a!(cqu4{V?T1f_X7!ku-wfWCf2fId{*bkxAj8B@Ixn;55WfzeCp7 z7n}z%55jQWYL4#&moj-YR_RcuSqzued5&A=mf3^X1n3tJZ^#Z_hid+gXT;hVAvLf8 z@2s<KS&GH80cONym=`Y~X&^GplEi`ncPJb(h@0FO_`50o$e&b}5k+w*E+H z+3yw(YfUIK#5?)5puvE5-{6@^kv$o<_OQ8q=0VNnt&$)97lgj9*A8@JZi1tfy{BeV zou?>on-6D-atC!wS%ckR&X;E)%zD$Ns7f;(-zU1amlV}_;I^6%;l7aZ{(heDM2#E? zcWVqTurubXF#~56`gI_WqRGjm@6q#pqrD1|%$E@~((!1cXPYT~f=-?9-*aPcT%C9U zp$0_5Y;glkBqn>JnM_}Dfga}_;f<-7*W;zqUMuiy--^$1b(-tGFNs$Gc6i+@9fs@U zX^_Y3_wilGJTWpYZnV;Lquu)+=7yyf7QT}FeIv)t-6wwy&Gvq>FY8VJwUx}c0As~7 z21`hYJoAaeoT&&E!NDytlAe4wHQ=71>wudy4W-WU87uFpPnj9cj75&BjAPFl4<^mH z?aNy=#nzn1`JaTuT|^EpI`^w_eUSnGgZGR3v=SZNM`GiLe$3_Xksn|cbQ0?rmHFb6 zO$ikgCmNHdhh~O?F$5|4n75ah*bV9G6t(FRtMvV-?%%wbPL@c4^@)+jHDtW1Sn(4$ z8!=U$K?k^4n?8ti*TU}^D(-e`+>XBbo}^ft_f@EeRvA2?xC+~kr`Iw%d|m<~-Hs&g zP{Em{@!3qfaI8#HakJxZsl7hdDbmgI>%Q4w&5o zh#E}&5%D5PV^&A@4gWY~Ca6mIA_TDp08%k5O56uBmmd*{5hw8ZR})yh^zPuDK6@X& z`}u{J?Sx^SU6yUH(3>DwS|Z?ef@HZ?D?=o2ODy=A#mRSk6|`RO)GUvTR7guYe56Yl zcpxR^4Dm7*H9b~2{gyAo?}M=-xtAHg>Q6%ner-EW2_jr)-nUYGN(TC?7u3{7@tV)%cnsFj%Uc6-KJHh^xL9yLZ991my8vB6>%@BR z-%(PfPGciEr>l)g;D8%PufyHuuFZnzW!H%hNEvUvmWqlKGZJj5dg_{XQZflS$(rzj2)9)asAvC^w(;zokYe z39T|j;h;AzHnJYFOsl!w4g@8_1T#>LqGaZpd^@VIGU^OcvW(z;8~r_{JIwcHgV5ri znB^D{lG&1d`!ySQSY0#yTo4Qa)70R@oA6QJ9j+JR#$M)nnGJ*i& z#GwrGnqxyf$4|9vzH|+M448GJr5CIZ%Rhv89P~mJ17nl`jKqCd&#+kWSnyC;<)feI zaGEcXkD((5N*gaN|TVP`D@o%%=4>lyR%QdqI=We2*{KTz$}uBN_bj1S$dN zTGof9Kl-F9WurEE=&agM#_<#K1mds5`A!;^obICO+rcgr`zLXDD-Gs^eVGfW54jL` zER%V}0GLV&>2P50IrPjfZJ}I{hieIq8p5fMaa%3qz`+e7YB0QSeX=M1Res)C5_2H`;wa!f)qbyu@Z14O^`y5z4jSq z3A)wZL{=!963+}?B*W767GbuX6p6G-u^5s@G1=KVf|F~AJ&v)d@R_`g zD8XjJ(Jz;pu%&e&e;O8enU)|EsMdUbs~gMTEFUV0m0*T1mW(AC^c(X678B%z1rw)9 z=c4mpNUK*zf*wNee_h!FM=YMysaCtQjBWrNxc8Nmlgyp!&Yr%V&beT&Vfu&2t$sUj zb*SJ-Crsng+$aZc2yt#S7T5ekQq)Rdx&D7Y(y7IP2BeVgLOL9_9Q+UM^T{K#94?EH z;Ns%C%wuCwDvXLf8GDjJUU6M`<9G31!OwXAdC`f4=l|CX11-Vfzp4t83&nrgg8Vrx z-$uV?L}gaq2%Pf* z1m573g|9;moYv_dSC;eRG8UD6XusU?DkWN^ zBSXcWqYT^~r_%lE{q{ml?=l?DM#a~dey}BnGb>KwG$C!|H35Tp9(>>>JNu%CpX@(^ zSo2Jp!t=)2`Z7$koAcTI<+#*N14E0UU?kC{_WS6^3KobM+7(o&m9fldUq`g0xu9Y+%?VVbY9|j9WcdxgE_Ai z87n4y!M~r!oY(KXHWUn)6SZRrMbEx`!n|(3@5-&L^+YCN^WvuHuub0QrA_w^R55zSSe$4Py3sBFs7pkKa0W0pe=fLVJxo_}Jun z6TtR0E^pFgWfyb${$m%#?|sNPTo&2Gt8ZQop6>)xuk&ZV*46!mc>w~B%iGRk%P3K; z@92(iO9)HrH>Pjbo_R8F*9aR=mhWSipa)K6gy3!9GV?1>-t&}A47>rB^^k6M!Yii3 zTQ3jp%Nr`M>11Tp2;*es^zDn|^DvJKa3St0mBKGMdcN+3X~T_;#K8|6^w=sw$p*!{ zHs`Kzg0alq z&^Ir4zrF{t{XjSF2Fs_8xk*#3233>c`xihKnuI7O>fim`-tGt&pdnEAq-Ga1k#_k; z!uk=NlA!IOxfl2eUG(?*m5{%xKel80ogGS|-v)d>5(L>k6civV|N-c zR`U7QVjjy@!#Kd+CED|}>-CF!whQ`F4I5>owen*jkMq%H(;*zK|I5Ov?#*A4wx=Sl z#ANeH+l@hmV-M%&J8MpTfw-^T7AD(hqBgML=i0bS=N&@dEx)B7k9@Z67jf^otGUik z0`D;Kz^|AM4%Eoi}Dn^k%Epil9h>v|LCz$TBLfH5B}>^tev@!Cx_`*m zr>Iq8X0TktRE#DYc=y~CCtSkF37Y!(0^ac7wrH*A%~Gp`SxQ+c_ZfCEMk+=4#H=rL zq%;4};ZQ4tm%n|-L5$pC>y42LaAgvyHX7mc0FAv4cO{c(H$R8Nme57*rZNjt*3EuT zjg7E_y`WzfvAA3XzB8uz7h5xWb19~bS3u*5vZLT(s2AZdvF`rGG#F_P6nav4yY61P zths02Nd}7aK0gvJGewMYm0P$KL{W7tW56}b(VcyqB6GMagjtaqID`otY53|N*h}24Zou_f2LDFJ2^@YC zDl9@kVF+}cFgIwq(OUDqXRT-z9Jx$;rybv42E#lC2`+#LoHAokqZAb%CzIHD(>I$c z-=o>OEYk1#y6!!}Y=Xw~TaBJ)OjA3!0o}1Ved8UuAP~NTrQ2^*<{#|Oa7d#t@a8ey zg~E6=l)st+lD&Tz=uln?vi5Enx4j_59RpS$HnZLmG4ou>^E|!WmH$yTxqhS#vTRAKpsZ=rjCvBE-*y}yz{a@~3dUW$+q*cGtp3>J zUjjnG!e=nTJ05@w@|wm89GQB-R6!6B(djlIQ4y*VGc0VGn-Af|V$4_5N>~dj?;e2-jM0x>!9Ev+NH+nt~ zJMO0Eb^TPB5=@G9e1)cVe5V2P*S3GG9%&#np1RaOH(#}8+ews~DNO|gz*2ZEu^T@p zr8zBB8jZ(#ux>q8X4PN?^+$t%la8a#Cjv(OE2TN3UTJTP6z%p)Rgr&wiYcOh6MR+L zcz;shJDAttJ%}P{XSpSQdj!{7NS^xpfAqkv^}+W&zh89T|6BPmNKO8iuXZ1Opw)Sj z&(ishmSVH#5ve(TM=Idj{sEPR_@;4zb#CNcY@!%6D&}_Xp zU}(`r_^^f<^Xc^9+Uzc?`vvhag0j{q~TZ4Bti) z=8vU9DZyWtH*pVX@17x?Z2aN#2@X1t%@C(D$Z7hsOvKoL?-tpT%Ro_dEt>Pb7RC1K z*VsWJTg3@5RDCq{e-Xi#!GFviK>d5re<4KzYG{9gg9OCwD=NY{cNKa-o)a^2%+vot z9*p&(!-Io^q{V|tA^-OS{6E0ql8l4u`mdy#{QoNn*~I(@bF}=I6#RcJ95GD$+(Txl z#a{DM%D`IDKSZ)pG-s{My9GzUX5?Fx<*aj*j_D04APDvXnl4mmjW}n2fz-A?vf05J zC-TM%`RjQd_fVO@wOHL`GLyTW7t$+ICuM;%E^_||lP9;)4X0r;-}_FG`7nU2aYN*O z&1I#@8rOEQ%8M@3Yvkzo=NGgc_Aj)M9?}tOX+e9V+yKY~9v+58gk{pR)&kyN|J_x( zjbZm)2SPMSqY@j75^{FrkY)twm+MUt!G2($@&y|xG)zpF^Y#PhF~(BW%7x_ybJQ#z zM~BzvZm=I)z`aL6>$ijrNO8zVqv`sCY!{4SQWr&_vlE^SL|Bbs4&JwyaRFVlQ(0f^ zx6vIv2daQ+*&iUJZ>=R$-~6lZ8#QS6^Sx{<4Mbe3b8@xkZ99Neebc!TB?Fg9?u0$Gfz4NN zfJmiwHO%Ie0N4y7AF`9PTRnyao95c5=hj~&z55CjuhNKHNqk3R9+zWtP4GOt5HXby z=G+{o>N`M-xBfXXet*i{emwW+&1&u1V-aPTU4qo!waUT8#RWFagvhOgEeH%k%;8P> z`Z8n#1La5$df#nD{$e=1H!KTp)r9U6L z{%dP2d#O*cLx0Q{gO~TMNxQIyeBcigtGSZN)5Dcx`?F8$^>~iPvNOPR(eO_RD&Qky z6Ze2m;;Qg1nN2Bac(X00)?5hfLBmn8Es@&l7=l~w!)R;UYkp})S^LNee)jFQl7Xi$ zouW7n*Yb5Vh4X56Ttn?~p&3D=!(8P`o%&I)5M)t=$1-%=Jmo-Z*BY(2p8Qi!$S{*~ z1U$%_9o8kj$T0x2$1-;by&jOGca-NT%Nk#|hDU3>ge0i&E|;G@6HwoFZ|&s0Vni-z zdoHRcW4hiR(Hio6davxsjc=d3E{{z=SFAp4rS*St?f+i zQneW85guLwlW!@p>4kAsehcLAM9A9s!5ys*t$_*Z5AZt)k1_DTFFjOU^=2~e7~T)9 zZ38T^C~XpWaFQc!0vrD`h){;^Od^c6o3lF!jpd}#-C($nw8Za=rSr(~3yJ zGKEvee{8f`1aUEYI5W>Lg^ro7)&EMhWV=wmI|6<%CwEY?A5 zA-wk;IZqG=YnfKwEoUz*kg`a&c&YAaGOe*9k9D9{jhU~GtI53EIiVtV&X8t z-Z*j;;L1{Klq`C4@3d6hl0!5Q4s+M z1l&;j_t@ZCvdL`{+_MwJ)VVsf-qDnUedC{{2`^vVm}WwuToysBKK^bz0_wJ2ZoINJm9q>GOO!D!+$bzwlYHD4*Nl?fHP6 z1}5gBU!)7hp)&~>aLU95ld}7pLwWr{9T3MKtFxJm3w!?fGVED_){e`%TM;{+5R?Iu zHfYF=R(auvXcpZ~4B&H9qPc_;KA~)lKT&|y#vgm*M?!y1Ow~CBoz^2Q=1C7n6;t4V zo&Wq!6=bLfFJ~NghZg?at~dunFpyEo9+i9r`yL29{zer3U1Qj}+-ys@WE>#G^tHy0 z<#waPjmgy1wEBwVi`};$KjKendvkeuA1CdW>$ZOQhI)OpTWw*vB6)|n!TrCswK)N? zZ${@`M+%z8u4HT?Jw*5WSIa!Yf4UWF_HGaMF_fFS=-baUS}BchEm)0kz{~i!*PZ>P zBCkiePQ%T5v26aA(QAJ9>ty3JNph^6ryK}~h>zQZy~_`r)pULyg)_ApfB5UJ@&Y|aVUl+{%-m@8uO0f7__=xB3X&SjH z-t?8CJL_=THUqb|D*+dC$g2pyYxk*@JSr1XPp&!X820<)K^`R7=KD04mwWp*$pe~z zd;ncPGy;Wv`p%AcoM~EIAY<{jwALFtqq5Jm0HP~sSLyUY+Rv?T5zGDumiBcAIrG0N zDLirJJ)%KL(cstkU+~jDsI3e#pIE~dEyfHaFJ*`Ha9gb=;p30H{(n*9s13D`%;_yzT ze-N%wmIen64QFHL@u1{D{qYku*-F+qQlh98Z$1srGL)UqXbzdDSGllx#z+8K12G2ic}eW_Xfw!&cn_H3?@Y`nhLlhQBe$|%jld9c61_=UN(0^ z$KEhO$!2CnzvnfH8ujS%9}I*O(sB=h))JcaM`cJ;;TAbv5Ci}TJ9Kzs3^u_Xx_vIB!QamL@K}Npraq3!D^z8PQ&kdM6!TX4ieJhx2oIH` z6ekW{{K%A~>WkV#mM`Xb9av~--f=NYg{{m4 zWU`l~&=J|b+|^|_GQOeW+W=k4Q|J@SGR#V*)yn)p0~JftNkqQD0k^ZM6cm@qcql82 z7^Gmz3RzUc+l)^chhfUXmUSM+uu^%pWqd7=n9DWCcBUQ`(=o%XiTP&V`Maj=;uz;7;`1dqElmVfyz*^hqmj>veNWX~0n1nI+ zDhVt&j!=`t3>ct7-qf!aJh9{pL&8qAfhxT6R5}KgSan8#29t_fZAv|fn=fdfxmwl< z;YSsMMX{{84caP40)7f)vNc-*3+VV;7*j4(ixE2S6*<0q2?cwZH4*^~xkIXmlP9LW z!)_u9i-!xenJmhFD6biAEj(f*zO`B6Xee+EIQ(mca_xP&J)#!PAm?f1kw2eAbliMS z;GXmw>>G|4D7ZfJ?Em}owp=!2Pu;E8oHt;5xG?8Fq>;JtcJo%EUsjDpiS&z8?r2+c z_pKgME(uDr{eqkY3Qgh>pE+r#7#17@a`#EZa5GEdk>G5MvM`d>`Wz%s>8i#og;KV} zVz)|_e-e=xd;s(#KMjk_oPK@-B+~q(j3@gbmWU5YZn3d0DE&Btyvm{0+|t>qLWelWr)ee@`BCOjF8BCFT+_WWmk#qHGmW>%P%5nZWE*Dm3WpC?)i5u z%yhxYu+uH5U^>Z~xOpR09~Xqm5@BN1Zs@EsHi9o;n!2X+er_SnyU z7IY^Tw2wiebCQ=`u$b=|+o+bvZuI_w-n0PoOPBYW5#TenwUUZ@tyZp@hjcG#wyMDV zSQ4-HPfhn4Rh|j?r5Ut9T^1AV=rZISO?S$!JU&Xz9?*Jl*bgqfPoYbGl#Z&c2V=H>7m%3wajIk=(Q!5%iF80-R0vIuc02)T$QrvC>YZ=vF z@Lb$Y4vKSPI6p_i``oImJ%*s`u_O~*9pbNcm%FY9P=b+y*=zG>6!EkM>Yo()Dk_Ef z1}wf849;~9I~j&6eo+!mE0~SwnemBC1$!k3dEnXfA6g5+jx_wOmxy*Yy}7!*$8i@* zIXb?!qd&aThlghQngM?1owAFzs%}eY-j;@{s=n@Bf4-Ee%b5`n#l8P(^A&-o9EDaW3<3ZGI2uXbhmnn`X)e3XqGN3mGgP;9K;9oa8l*gm;{PG?=m4XQ1gNa~-^3;e(<$~@)e^{OI%6@O+ zZOT4Rp&E6?K&q~VtevZQ2Gk??16!fiLI&hDB-=*Z0;r>q@DE(e-Igez`;mjjB6Wm? zF9`&+M72LF#nf=kt_Iowp$mtO4>{8s)sYh!1%FxVatuC&6RRap$KdsVZ`bQl3YOit z@Zb=uIDwd05v-lsYa_(bvC^;aeP?dwyZEyPCi~h%_K}(s&iV3J0a~?cwW<2O zYKQ0PhSJ(ieA3}HPnw_TkYFU>bEHG??e!7YNTX6IQ&_$gxjf`56!R)~>-F0zs1Yj% zdQiZ-N~qz|aC)h)KnpJQIgqj=WqQ*>G8dEx5pSp)bJj>@B!9g^;UL3{Vb$3qwoi8F zTmK;)AF5cAg)CA|_)pl4tpM{a9qq4M{5mH@{mA{Hzea@{zBO8c@x-toJSKhqN%~?? zo~TMmY2jxJYI%;tD%D)#vrdiSpQILU067F9YNWF_Xvqig6Q@muRiNALp)Q}Ic^nIo!(J9O2E77s#yj<7 zA4)U0eZ(d>%5>oKLys#dMHwf;q zLoFQ`3}T3SnCq!kHj!SJWe_e||MvbSCoPSj(^U5RTnO5&Q<*jCH^fw{-KEnSfD67|A8$l)J_JBBI?@n)vTQP(Ii*oaYNdb` z^3nZO@<&;waxpLYqb^q9&Ug`L#)U!Z&)L3U2g`2H&mstRJWAp&KdRcPR>!*&*wwjg z_6qy&1t|zfUq2#MM}%v-LoL-mKcT~lrXT$TAZ1z1j3*)C zMG&{^F4(4 zRc9)(ijwJX_JgKehJ7)=JFKo&0)BI4a}xWk;X0z5zL^yz>2|8TmgcB*%06MQU8gn9 z7)?}(n7#-%CxIY}l#*-L6cAybX+E(kL=97H`ikwIdR`2wfL-I)L25lozN~Jn-iZ(d z8Za-)6>IFeFuDt!#cP{Ezzz6f)m;!Mm6F)Ffh&ovrS!`RS@d^3vCi$M0-8&m_V-ZV zOp9;2bir6ya9j8I)XawrV&^ooGJ``V?Nk*6!cEN`(KHA`L+yH*ki<{BN&vxUpH*vu z9=YD013mL7Ne)~-{pvE}8dFp4XquSau5fv!#7voL3l45waXhJ178cd2E|v>c?wsk6*tIJ8=81b#D9GnK#;}{4o>w<>^*K zp<%Y+$Hy1LYU$YD_j2Zl9c{uPi-O@4a0z1QHKwhhlgJg_>%U?AR^jdh|XUGFAxi)(+OPKElX6l|#ke1$7b7WkzTgFFU#h!W1Wiy?%i6`Av~wZoU4|U@kDSN3>PgGUw+&G|sj)qd z3f}k0*yaUc%q0~hAboLvT0+LcqC?J)*3ofGru7j1W1}=0qG1PB2m$wZu}KvOSjgi` zIC;+bIn`f=1o8S%)Hy>gWL))AHKlYv>;zohcGX?zmJXr|=&+;`q^lLZoRht)Nv)CE z020!SH-@$L0&AU*AA26xDK27b-!Vb2=N?Xm9!A24cfFXEqMf;c;qtUp6ISF~F6kXYbLDN)Lyj4G0^R%q0w z9JJ9Etl?efq{Q{h9+WMOk+H}_R?>{CSr1amggJ=1)qEc7{D`AT!)hZ4$cLxs&}z03wM9Cn!Zk;d_=nH(Ma+jH`| z@`}mvQ_@Cd1bWpu8Bs`mOlhZ6~0+ zZVt90n&X_;NprWKtH&Uip^}UvjuyRuM@;^AqPXr9d+R}=lDGj>$E%5uGpm-unt3HHN4UN z+@Uu;y`JN~d|uPRk|=j_7zS9dV%OsOJRd>&!R7-lA74wSWlm7r&ccw#`qat%7Y6zfryX+toU4Z9aMn-_wmMc1$Ktzhh zvN`&lOzAkF;qKLAe@6TH#X3K1ksu(T;~}``BM!tBso$F%;a51;jrXB;4gq) zW_(H0x#wsy1UDO}_M9~f0^wH14NT6 zeNO)x+CBb7KvYleWJV634%Wa$*ejn&#Xo-DU}h@%dJ}r^7nOiWS4|*{ray>wT8%4I z&&mf5$FS-EiXj7LT$*E~p?}^Cd&zop`Bh5&WdN93P<`iR-qIK7eIb|fLNp$m7wrJZ zaK*8zjZ5*$6`@XExVK7A0krEu7T0Xi5IQ)=TCn#94ss!L|4))Mh)qg51NM0 z0_vkq__L`EXFb-{ZW?}dI_bc5{EgRXU7WwMpsKN8Ti3J*MtJe z!{_dvZ!$Jxq^#x>Y_>!Jx{X?J?l$D4g(x({Bur_L=8+Me`#1o7kvW|VEsY576_d3y z=d66+MH#-!h^(TaDkho*{|56a7}qE;6Dt>zAT-;gT#lj?@XS>7>N_Ns@b)qv)v1ec zp(+>*(_M7K$7bi+L%4=vd|D*&CHBF)2C-@Luph)g7wh>?W+(#*RGBkE#J9vM!rWo@ z`ZOAH0A0Qai2}#8aBzD{ZM)^7IB)zU>x9`73DAX61yDfWm>`{y z|5R2mG(}I}kL)g$lQv%Hm%O4p_hBxHh)Za6r+-mcZ=Fai-hwEN)41DH8vZZlFPlg- z^bmsc!J<*sk8&mKiu^pX969tRG}v$-okJ-n&P^Z!Qp1I~|HcA@37dqSS<4Cjsd&z! z)5qfdsuVi?lhZ<+!KE<`niwwc3Xwj03&ciZI_Xb@dhkM3`bwABka*1V0CGZpzF)&tG@XZvGPXFH$x`{oP0Uh-~_2Df`wvGzQi9u*NrzEC({V_`_vN7<-9 zzeNF*NXwnA5v&;z;s;Y=b7&kHu-IR?RkqjG>^u}iDyg6Av26DkAso%mzfM5iuQEQ$ zs7Nw`uLgM;YNXeZ^5`yFObOI#S{Mv8hJXGjB(P%gP~lW`pH043B2#CNk76c_DVNe9 z!4O-7$~$Gh#u~oz@CO&p4s9W-a+s$A%o6ZJZHlD_sayJ%W%u&>6rC`3yQh31lm>x` zzwc!~KsxKY^f9&O$55dHAFS(inYl&U z8U6Q$vyb_*0WBxUTn3>DQYH;mGxdzVKuH1tR0%px-jfZl_Z%-_ft3}#nPNP*+P~b0 za%>gFquN|R7p0=`*rXoCIH*NSlY;*i5D4a`YX=#Wi`UpoA`56#lt`o~IQ2zc<~hnufTEmMqzIP_U|rn&a*pSd}045LC49GG;o2SnIb zAVP*r4h883$l9|T{|OqLKtUc8qbB{gS7Vu&y*L&JgbM<-fG<^Iq!_&UR7CD!fjBsM#Mz>*F z*f{wX1V&$dzv@Zp%5how zRW|o#0~)>;_b4#sR&9bidcj%=k}?E>b~ORN)5LTsBn>+Emt2lMe{mg?%-p(PpmU!e0o}si(X- zVhfJQ?vJt{{N(8IX}h4FcOavW2>g?=WPxI>a@Eq zNyZ7>Y3m@VIa=KPada6NWa`k|>`qF={&n3?__%U7qX&)5M5A>ljD)&P)H}mjl5UFY zEoD~*K1QpE#n%I#WLNPwS>Q!k^ZLJ6I*?TjImAV5@i3iCf)h<>K8=H{IA>;8ATNA0 zGhsWQOH-Mp0%rN?LM>!rlmuY|bZ)?TQ+Q!cRX<3YT>T@ST-$UYG^f4yR;bPy5PmwE zIwwXhG3AKnzA=)xT^fEb z$#$+FjaT-JQPI|I&@ufLzk9S!P(kYVDg>0m8Up-LEVV4o%jP;8>F);zN!W<_^oY(R z>wHnjE*&{m-u)AIHnEZ+il;9T?=Rlx3!=B&dnC z7HPYKgSZ&hhL)-3rGj~{DR638I0gU%Tf3q&uVFQksyA4s^fS4hNRF~i2#D|@cV zU?`vS4+#RRu>e#YJM<6vdo`HC?~Uf&wDtm}yRiWc5GB+M4#RyVeQ-FC1w86Zy-rV( zEk#SvO`kXM*6L)+@SqXj@^|J!W~_4r70VLt;~Jlbjh#0R9lxc7K#LZADTbOmze+)K z(ip+MPF>Hzmd@>>O}D>w`eY7`CM3;0HKH7udKM*UzvA~){haQ)>AOy7lm<#;&DqC~FGtK4CjOg|iy?cya+Zh|#nSec-wQ&jXiDhe{q9bg5|!Ir zq|s4VygGB-qs#L6@wq=+4&R6A_Ejk+$d*939|$Sx^qm6Is~nP3AHr+~8aX-v_WnBm z?cfvM5BySPlCc=Uzh!1{8jY$a^93ZGxMWhbyTf!@TAaf@3QV;1D)Cl7bLG{K)(x=i z&NW_D0|&47^9Va~{NvI(c1ezhJ~}x;Flae>l#BRMJtWrXK{!ghk!|+!I=i+=+E1}q z5l&Kam$c#3+D;~Q3hdCpm6oZmtM>k2nZu}Bo3g(**K({?<&DphK$8Rv{>{uY2?>2Q z4(4k!elIF)?1Mhl3W(+PqB@e|3qw#pU9nB#E?C`pCNE&vYCZs-if)EuYWa-GieZ%| zEw&|O(ahWKEk@)MY0WCOFC(iZmVTvh&;7>5l3<@8YG3#J5BEP z?jjmG2s7&f9I^)aKoZF`zQC-#F(h1CrA}UcooUXmjR-v|&0I5MKojk#gc_bNlVIoQt_-UW-v4W?r|GAli#{8d>qx8fa7I zpUhA4tDLbWa;^ck*KDn_$I#W8R3?eF`LtoxlAnpAvW(y*j)4sdhod9;?n$ZUMWy{@ ze-1Lbr)=hb7z#9)X7DAW&=+@&XvIQk4%MW4^_s;xVssquHZx%x9LYrdc}WiE^kt<8 zo8m}a0=a%!)1t=o1@$F^UI5v-f9@3K?cU-jK7m_v?f{tbqZ~)9cTR_HoFejc^gSrU zkycV({yLla{F2hk;RD9<(X;eW*eZIGyc4OG%9M}g9eeg

Pb1Lp@&0tMd0~NY>*W~-);C{LCUga(~Nm2?0BgG7lO5gA}6F_^~on? z1F6lrT;qa{Bsdqjt59cl2i-_1Oq8DJXoz_Bgo>I|-HeL)(MJ})AEi5xOMY@LPG*=o zG=W14+G1&t!i28Ql&Bx(I7+oCjBhE7G4S`a5dtZJ8MP0qOw=o${9B@nx2L-i<>!nJ zaGwcSKyG@-Ye~BpVWu<2O_fy&y=rF&|7<6xwh;Xwyze@RZbVnD@Fe9|YO(V|eUa@& z2)Zg!0Ccps2)b2qy#rOG>vleGrwn2xGR*@c8(Xhdq{U$J39_}|{(9Z+9L^if)#~%3 zvJgjVJ6yCREHR1^06l%~X+tA}=#vaaE6MQ2K0M_Ot9m)TzYzBd>cY0`vx*m8 zw@xj^4?pJu!+9JpiN|_t?#5XMZ2h!YtbNPNgdBR^p5$ zTHF&lr}iU@ zL^#C{kH1qN66NPClN#U?WbHdz)^*QSj8Bu{_BaN&4W@G*u%;&HFrgf`7}FgqVI{T1 z+=kdfEgEriZEfxp)gVu_ti$IDNxQkr{ZngZ%I&DV95!P6#1+?F#)6Fr5=7be1R^Cu zi|z2;wI90(*UJjZJ68e!Ob)k=`*BbfMZR$)b0A(Z=xW_E%X%_!s3swla>xiNY{h`l zScuVA>w%exT$Nz7K?}~-WVWFOSP6(!xy?~c{ic>92kLI?JQKC9<|MTu54x*P1#=m~ zn4WoVVYcZ;Y+}N`blUGRd+8$Cr#D@cIT@U0S`DXC<_aZ>8U{{nMLJ2R&D~N&Gfka; ztQdj%0FQO7v?1NE4-WVn>ghi(HuH|8h?GhyruA59xzF3afkf44FCr3jSiu_0Ls+N64i2!BU_ zX~l5Z9^z#$LaHhEQm=yw=%d`%Li6A&`;6Zx=d3q#2f^;ET6joGEU-$Oo4}1Exyz`tV&j|nFK2Icype^D^P-Cf?H%7i_yYsdXud{ZIG0#Rl?$A*jK(O?$* z4<=GvSpsK6+k%tlmwZYq{GpmRn4eRb!;o_JHBNWS%1)4tD|v0z%jB#oNIx5$Nkvb* z!JX8?3$>Hi_pb*Q6YNxwwZc|!vB&9Gs?q_JB137C)Z^bALd7Xnn>c=&T55!wT#1<8}m|O1>c-(XF!>z<(7fzU2vb)}@ z*A+HY*@=TE#+$s$>PP`TD(i9&7(zVHs$ZElzs@&Oj^5FNUD_`9N~SSW>n7=}{rgpZ z*#T|KH#}9Q6=jr^hnftf?-_M$4F_5F{5Sag3+Xccl-D-Qm_x2X3y>yBs5x75z% zpHVlP{)jaJQNFL~ro9QW&amFndbDMB*Q;JQ3INwN)~@pjj zMy2#~bCqyOtuTcMw+)g_KtYQIt81cj)_F7lmj=;A_}`Rjmol2PJ?PEr z4`dD*V-U1P&_HSDeLFzHRI z2qgYlS^cP4!fU?dgh>3JWuehy)_Up?J%A+5c4JQc+_R!Z#SIFH>Am8fsLk6@CqQ{v ztqBh+{TxCtjw>E)nxb+oD*9C@*8QpEEBrsYO8EHY1_S+L;jgH-Qn(k_K?!3wpMaHS zBo$|x&8%s6<^~owTd3DmOpM`ofigYa>)U0Ui!6W{rfj~hpK6iL1g-KxI`ev}oF2%f6JSmaJQJ4tPAHirTp&*a} z#~6mJ#yM1r)#L5wXjD{M$~u)p4We_7_qx|oI*6X=%o|j4e#fp`{*NaO1z^Y^(bHRg zyligNS1wbV+DT!H0<6u>dd7YA{M`nE*ook-1r^GVRcjzQT2wH%0TdRbXJ)1&Iprj7 zLc8hik?qc_?D*v>(J3Y8YH&~LdN29>W%Y1_FH9oNRS21+T5n)DY=3g~k;a0r-N?OR z`J!#XRXHk60z$B@3Ve_!7avm#K9<_XgoI2r8zs;XX>$|f#do>?%t=IDEsoy$%a0CK ziW_z=pIPtTILszq&$51Ixn1N`(CwX?B;rJS=QJZSQ&B+axBdIp^4scN6Q9n0x*qHA za+7aeEx;J}MAq(6m}r|p&Yljn=3N?0C(hgt=z{2KZB+uh@pc#RcXxTUu zkXq*Fy=IbT(KHQ6(l*wp0|BhnFl>Sd0X*gRump>Zj2C$U1uE;Gb0yWWtfdt=gq9cg z2uB`hHVTgzpdw^YT_lAZbGhRE0hN!lc(ywgh(ms+?EPYB0quTV?qfb_nJy8o3edn_ zd@cT2bMUwWfop50mL=A_dYq80Dj(Dl=~x5GoFzS>i3JBvpl|{)?vSB$+~mCN$;}@t z1nY9O61N#G3X8NE%bW86jDf+aQOBp1EkC^wX4b6xro3)v#J|bIRlOHSuz`}VMF8&_ z<>?gl80={}KAsg_X{FiN_aObfZQHoz(~#UBguqQ}qVT*$aH-PWeU#mcG6fk@t2S&iWCdcVO z7fD9>*WOs=m}-#3KL;E2A=A4sXr0)0A<8zL#nNaPPIq4&An>r1EXPl^>Wx&W@_E5W zZn?*$tT)$p#_|xJH=fe(kAL{0#VG<~U3qu?Q_oij)HjPBTNr`(;+A5L+nrl5tw|l$ z)3Pq1q)K6=$b%h~%vkcp5;wOb`+bEY*!KFrg z9t*?%Xq0D!Yqae^qzjHVJ+g{x*2N@4QkdSU^2ck<^{XPwHhfX&4k`f9@4%i}M2ShR z*~{5seS4#FsS$;NShhh(<@Iu-!&ZXO5^N>MhfxF>wfAG#UoblhlV!UL=f|{ z@ZtBWR=^J}3fl&4&SxtmGJ%iLA|k84U)h@3zu?g#Dny;l$a}rBu-$56+;($T9V4HZ zE(v!B{oIGnolU%a;yI_h;nZ{e_y&I-&n!E;9}`%^zn9^KE=4d8|E`k2cEKt&q#+fY49pp!#ltdN6{{d2lGo^K-5e@$-ag_^~p zlf7FKLyGa8dfBnc9gg_Wtvso#{2m{A{!+`jjodRwe(P4Ao}VGN|FOU@+KdS!wby&V z#b9=*OeLJu3s&ONI|r&I$|@$Uh%34%W$YbS3uaEfg~||B2%a4 za+O@qpMm!#snxVS=7TUwaSYS^MjDg|T6w5KkhptdioX+Re5KUTkKXDq;B&*gUIuu%-&Biv znpv5UXU}Y3PrI!jX{s|I73Sh|gI7)&a?5&h#Z_Mi8El$(utTGez5f*G*Z+xVTvQ|x zC72?W3GUC0?zqIbn0u}9eeKg9Xn!;V{7$x|D(^$T;E!?Z^{*nVtA1o*3xI#iY-r>a zs7)YtuSK~fHs}|KkdYyXD^{T1l&vPd=7l9b{-2#W*-|{Yh zccvM}1$Lo$7OTQVi-@Z5f~kTvZ*O_n(%I#$XWbsU83FD0^BNZ#iSH$=;6wcD*{sdn z@L$`*8fr#4{?i}H>pdF2eKM1%$k6Tp7CCZ}PEO}`6UcDOOkF`M=IlpIR$q(@Qs0-m z{<}FVM!|b;{cz?ahAGt`jm|BBm%mJczmo;8frXctUw63|R?-htdwa)+f8{-q0eY_`%(x^T;9cR@ z29^9ds0|~x(Alwovu<;o<_-q+bSb$F1@DGl?B^EcFwlPqJN1b*GiIuVrpDW9%6$D9 z^`H1$bvcA3FW`g6R{%Q({uKSo3STN1?SZ(IUSFj4S;F}02kUX{jR4#*v&|=Ml1Q?a z&$WgWIsuv5H*xmx5`?QXx_T3wUbv7^z)c!jgq3!XLqgbky6cJj^*lF?z~;_#oA|%{ zwXxrc3|OclwBt6+VLQ20%4Y_o+2$POsZz2PZkg7Z=dp;-aD8|1?ek z5-lA0098Uk{qMFjzwk549@kj{)ZwS&`b{^BW9#ahnMr${ka$8h0LG$f_d9GiYFYlW z-OlIvkJ$awx3;H#J3+pyX5KTdzB{k|;~3~iHTD>=B2E}X*wD-_Z}3pbnmdM^h{LGv z^3HPSzlK@M9yAzjWM4U0iff{CN4)83t@D}dZq+lqSokvDAO@I8`}5S);zQ2czB0I~ zubx!z<0r|)fz8J>WLGsz`FAL0_oLoT4WtOVJliz9k#R029yHRjAswJmME_iyf&{@e zZE(P6SkVOxS?`xAd4pmTV-HpPN8`8O0}R{h_J^1x^_*gY#D~&9?$WGEllcovrW>wB z9#l(;%e!2QC17EJ=sp&QdpKYE19o((Pjp_!7+jp#`_`3)x`8>HGU9$p3TwL=ZLTzu zbp6jiiz7NH0XfcL^IF@1!wyT@e-^V8z(a0^0a6p6iM(KxoQo*nj|do8X>`(2>7SB8 zsW4&2*az+osBaP?75Coo-L2Jxd(xEES&rPn7t+AObQ1_`zGn;-OBxLKySn^8KNC+u zF8b4}i_@3SabjtCWRWy96k@{Br)#+4v72)m13!R93qHUL!zJ~L@*@28rSqbH!HYuw z1sO4b@jdw{cOHrWaIxyS%NGfjd!RLz8Hyo+sK-lMc{W*ne z3Z472+;V2R1%v;|oN3hI4!$e?brk3)V5he>asMAubJ7YE)vLZgK;^C=6Fv8{%(Y_l zM=~(Z#9srR61an_aEz<@d?Bq=yN?(~Z+WF^^c)Jp1@ACiq^cpPkZ`;2EGSKI0)^~tiVXAj%wWkt= zSw-q+Jv@(806e)cs*OfQEsh2@J*s6g6<5^ zE<^o)KRaino7Ar}3ij*tXM5lJ@>f#Vd9Rjg%fCoX%Z6}-VQW?3YE*_|jTk0}8_*C{ zSO9)nV9>Aovr!v+d<&ae0SK+L6^bve{Vcq4AmFedQdXDGabx;&hHMt&b-okp@<}4d zmK#QE)p_1TqVMoZ@#i1^x3{e`AFFR7ggb+5myC6fxIW?PX;Rq448;Mrc!DcGLh*m~ zfnRY>n}~8t9RApq7N-?|M!)IK&pkZ-9|;#NT;qlQVXEbhhbEiT4EaLxcyNXpvX?VTsC2|0{|$K zz<>WbX=+3pn8?&EU*T^0Cp^gXe3UJ>dV8aP^@Upf&LSF^2rxYl zUmJJa5bBThmyU#=wj+?FzIrN9K@+)e&M>L)fc~$bl>^CSClV8J9EedTg$X{rv&Tth z38~MMe{fJa4QR6<^|5|wL@KXqg-V;ltXkCibMHr-khi((J@x$Kr4!o{K1YP^ua5%1 zkB;cJGUJs zZvThYOcrA=cM#TEQ6YNLa=UJJ|0_>SsaMcMyfE+rwDjw^p2jivAM+-I01iG%INwOG zys2AO^b5cQugx1p?KYg`?Ki_yaUQAU*Je6EB5SvemTu@i#KvLNwP2bv=Dz1Y^Io$! zZ8_f2ENf@@WGmRzf7ki%CIKqovl5==n}oN*|J9D(ibpvX3(Ee3+wa8Rtx!wPhf&L)r>oC0`bE0=BfpHho+N%JG z&%NPr?T&=+j)dEDQ#)LbP7_?!zALQ0pm9H6^@=9&a3JyT(X~BW!+RCafQ}<>%U;+U zOU8k#h#zl^Iml8w=`Zpm(@=7OA-|*&d)G-OhA`7*1mB3MlMc0EOJd1ysAofsz*VHd zhAaA9JXa|5fuUW7s4~&8j!E3bZMNa+Wjp7!yXvaJl#ws{JR}i$#Va%M=vtlY1381u zZS$@>2U_j_nsC$yr{7Dd(_A_kegS?HpTnbD29W==nr+|_x4FccevVN=JfP#u(dvEs z?KH}A#fg;^@_r^k!mbE^V#!%XL9bG^eJ*b(CZ0z94bo^ zPKXNI=JUifLuPxFd;Dl(`hJ@?nLCTB#%k)S;1sQ5wB;d23c`rLgup;gy7%`=aa93{ zDr@?kIF1^HOg!zhOj!MaEWlGhh6>XIb;^=GCHZdZX23BgO6?ECwo`&!?BpXjuJ zql)Cx`6+PU1_b|U_d19bDDR%Oo$ZBp9=ugoPcwcuzSxwcsH*#+_0Icci}-BEnDiCj zBF*8^rs-l*v}$i2W+tT)#vo_vU!P|wDY;Fms2+&7G!`R2I*q@|9Ibl z43Qz<3vgR4wq0*S5l6UtDTbz3Gj%WdiWaQ_C31ky_-;W@A&bfy78Hrf@-(?*l}k@W zf|~WvOX;(PR<2-=Yg5x-#PDDMAd8KXi*u(*(Cb7o&{6YZZZFM;;V^_ z+o4F5fb)sg$j28vLd@MR7OE$_&!*pe9T`^am2#@OVxyD^s+O^`|F~LhUy4f8_fcS& zXa003RK>mUW$zKQR+VUR6S7c2!FlGdXO%ntJxwg7F}&2`Dq!e*n+6WoEx|_cKdfco zN^g`%8%O)xHK@38K;+VO5VQ9nB)_%6wwVC3Aj-Aqm*wXUBWH>EMlBp;;%@lt{=TO^ z7MkkStW99y5Iy`McsCENBrqO$9X2h2!w_L33gJ0)lu1cIZOU%1Y5d$A!GzAJ;?;d? zMi=!6Z-{`)TkLWM8R_AI9xI8UN>H~(9aUN{Jw0P`RWDn5mca;R?0IlmRi@68Flp6q zQQ(rbZ6*ItFAlHSsT! zMh_>taPs{K7q2$hwT@k-_$R(#YI|8ty0T^!1&!r4qH@N`{xxAo==s0C_Z=;;L&joLujT9*lTt7T9&h_)SCykFO7Y5XY zobX%=K9Z7o7CSHyLs3D$pf`k`#!g3?gw*KfweoRcK6b2_w4!u@d^S%ylWT9UU%u8u=|$YMlCgG zI5{<0@BjRt8$vO(hpsLxqmcah9sn_%q)ir{e<7uh%MF-FOABKA$)JluH>YIBXH1ow zLHb=S$AXI5i=f~)7JR0(M0khx_}eF>fv>x3p+|d1v(Hj-Q+G2Cuybboq;Cy>zWNsu zngrfqLPu( zftQ8_duHVxwQAzmp-9E%g2Fvx&5GeXiNet?X;9iQgynksc0>!@=qh3CBARp{ULLKbpQerp?Fu8mG8B z!ySf8ac4M`0i(FXU`TP7;?A()ZbOC*cmJS;4R;wboZcENe7P zxh3TClEfKPn6Y$Rza``4BbhhSDSMw&Dt`TFCfVRx){u*tQM)Vs8mx|L*ZxX*^3hDb zu3JO!0_4b(YF;%$cGQJxhXk`M$J+5h?=cbQXb|iq&0{Y*E|A!jEPG(KC1|0E6= zlcdDB1LL>u4BZJc4Dm~-6Lg0zxNs%3@p%H8RL5ty{hMi^ zUKZb{f^k(_I z7HY`=FWgKfsldg3yDI5aw{q^&R~rm)GEZ=Yje#+Ht)A4o?Pkj-+BlT5ZRubkjtxgT@ow9<_|@jbdQo*dcbh9Ca7?U<`~ z`99@?sW7-5sN6T+-*Ea-aB6GCt6(&LgP^~b3#3ajNVv%vy%*8>&89L_l&tO+ej^=z zB|)DWdhhdmID1yag>^082(J~OjFVh=QV`enu7Q=X=~5o&uGA2kKD(e4yu?6U(QM~W z-~wwE;vHQ|0VAe~T1#?#iAw?e^J9sL1fEf`OEfq^y3Iw1N`B-2^|~3pt@By}P3D={ z9oYr(QrgZ&a_VQ>eDquefs0D1&6KmNQYtWV<~2;;9_thqJvVM!S}&`jOb3z8uIcK0 zPrqH3pTE-31l{?AgaW+=IA9IN+iIEZHWfE&ti#rm3KO zWRlmPqoM(Tbm`GCXO_FgS~uWAgQc?ojct`Qn;8A9z37T=I0=xR!}sgyhWM0_4cnic*JzIK+NXt z5VkqG`Sv!~?c2rl$(Py3a?{{m|->U%Cj8LVnqb0rU|)&x7sFCw=yw@c)m zo&C;VPFgy1&iWH@gmWZ?<0w$j!el~Fl;@xiXNJG$HFB8{!t8sKG)n+C+ z5^2u2u*`bU?>2hL?lxM{OwU`AC^8r4wcc1YoN$EDNjf5 z@Cv0}g>(7Xpw5&A4)#E|8XWD|hzLp_*$CPx+R{;Jci5TB{W^LN-0UqX6i@LtxP~iv zY8{}|9O~yTu6!p>E^+HTv`(wB&g!iQC>|1<9ppZdMYr`toR4_#iuP_{iAWy!B#j-; zSc`43tP0{QVGW z>d{bIlo=8XYJ_>-R6L!L8C$YY3(CUq5a>>K?-k97*o#NN)wDR|`Ve&e6i6-Zh280W zKJw0cEmSLLXZJp9@n8>#LGOAhWgW4siO4p2ixQeZK_pkMTaA$M;Cmb5OMb+nP@=Q) zpIWmtrgRw7p)=EXTEexafq~6v$&t1Y@(;<7DxT0!tzkYNM)K(ttk0v^J{`OUjl2G3 zmZ~bp)|;}sX_?}84~^Sec?nPDmeKe4uPSop4*%ZSONza!!D4i+id*wDA2NoWq5iC? zXs-6wzddoq)%$iu5cK0eFk4K|DA%Dr&h$_qTAq;Zky=dnd8WK?ZnyxYwZ-lW&|VnwV`f@`BPq8)pWo5+`ISk zgW^G#<;Ia8*vHZb9rTC_o_6jogI`vtMvdi#@l^B+nb*7s@3#O+%{ScHQ(`S#pDrhx zW{sz}WP-??A65XzQ1JgMNo!}vI6B8@0!A{pUFl@YZQk4~WL79E25>Vgwp8kCI5 zRd8fA=&bgBRVx_D>}6bfCuj2+t;geu4024h8SUH}x9ajnSp81x{V_3wdO&cQWA)T) z*}ztH?Ev_5)#*YaDb|MX(?*QDf>2G(>)518ph5Gnu|UHw1E}-7fiT!?y!PmOyVKT6 zgoI6V-&he_Tm}hFI@-kTQ=U+G=%~VD0#*eL?dp@Tq?<`N)(~Lo(c|M6URQy)9%81% zZBgXw)#?kAoMof=9Qb=%-8~%wHtDP1%s!f~0Q*vg$iwnD>`I?c;SOe$idVcyzkVr! zrhI2i!t~50Q4?kZmz|EC(BCe~{2{A3b;F-mIVNqw@e!zr!2_XoN&Png#=gVt_uDW2 zg=`EyQnc7G2`f&T)h8}A;oay~F=UDMbAVU=$Ta#Uh2@M13<)Pnfo!z7VTsp*k|R>S z;N3yyPihz>dYAW!49(Ozt*hN2f+^Y@I-H2(C7DX}%R##lplDnXOTtLuV3$qVTU zs6fR@NYM0CVcw8apTeJj-{|%nSb<)-;Uqg9hTb+fmY0;fMUu3!bklw$TYZ znnq&Zpy6;wboZrJ7g}rZh|r?(aH8b(?2*T;vp^^W{70Klx9d=mY&VvymmFb6bDZdJ z1YxAQVAMg@z`8H|45uu9z00Q5N#G77It57uG<%HK;D46{Pf*k1ZxSKDjD?xlSBULI zFaxpu-;<|{F@Zy~fr-E{ZVCU8AUhHW@j&Gq$k7=YhDGkRsFtH@!}{tY*`Z^G1jK#0 zbx7Q$yr)6A+W9_8X!oXqe#j%?Ag5zZ?w1cHR3s1!q^;7WSpvjti^^k*IbNI~7W0Pd z8HGFRS8UWd&u0?uC?wC}PeUzXHnRDE|6haHJZ z>qD-IbdnT>C4B{kKPza6Mq?muSkr|~f6-VGbdNOP)$O9-2^i@ggglg2k3?KOqZv#V z?;cDm-g?`-EccvB7dK8DRqKjK9olfvC5f$)D7Q?}jjU|rm{_P(Qiy@F~y{?X=|$hs?wW z5k+>0F-am89&`c-A=N)RFeP9X-`i0VcQ1yBw6=B&?uofO4jHpJN6dE$9xz#iyd3?`wt5}%90uC*k)IF z4BW$pZ|qd`?f8vjRjGE(8*BK{^5&7Ig@;T0@hpp+;fAzpzKerxrwNPJ*!Z%<+vt3_ z@NN1WGl(b$$vg2Dk<0(Ao*<`c+z9l(J#Psj#<8%VZU455wRb)qFvRCc#~<*rEhXrw z4x!#nbU7V)H^%p0V|YREF{imbgT(3-<&FI6;43mC^1*K{Bh{4GXW{GX-=wZn=?A-4 zt(#$HenzG$4S=BgEYlpYF8$Cu2Hy|a7DOZH`3}Y!LX^Vm=VgzpDosF7c>DO z!%Se7&^Hzz0?LUB`jcn;u)qTJ{}jH*r_zg3B9!thSZx_ep(j5qj(fy`Aji7W@3qcH2iUS3c8$ zGTE(SQgRbwNEZxJCj~K)yY9S$uzJq7QwyGnd;X=@ZB2`xqrk2%B=F#eYFk#F2Weln zgComx3YkVWx|4Rlvla}cYDq>!(f9%8Ies^td3D00%;(h6EY9pXA~=i<`*Qr#M#uzr zCpMnM1;WPLQ*g)xPcL=B%jBj-(QF@W@I}%^aL?1`?uP&QFgzlW;DF!p4cz7PvghuF z6<#Mu)EnYU&!#zYWzngD1~)87bxVHVH?wQY;8|4_?mnl-^A47w=QIehkh9!3bT$dE z6faizwIq8&17(^Lt|37o$Q~m;Y*PrqL{L_D)gWsB-cNk`LqxzoA61nd{zjdP)~ATo zIv8yENI{%Pi;O(6J8OR-LV=k5pV6#9lSMQiERjGubk&f=11|QX$rEtOJiOXr4q75x zrV$Do2na*Zo(QZ(hu&VVM2gobb_QvmI85EvJ(rWEm$qJ{vE)0|>X!xOMjtHzWb1+%z zA7Q&pfCa@Z1uV-wOzomb-gs@0rt@PgnSw$ny2!F`>EmAU&`5*Gqk5h!Ub>RI<|#qT zDoBv=DvnqIqXRra9U9B~`a&kFf1?0Rd&e1*rP2U431Q;YCMKwByCnn|$M2O#RGS6R z^gL_bZ7&8tc*ZRJjDMo_LyAkl%=hzS(kA`Dmq_hoHR{%LTUX8h!+%-v{(3VQ>-@QF zabSj6_;%_tSr56fSYCbHFuS}@P&b(ki5`Usx5+8!$J*eY8rt&`gCuTfoa-^H3#H(( z(?u)23qfgp4;XaDKD%bc44s~lFCmZ-@o*i$=c6yf8T8O*RSNPRc9`8`=G^zHE70Bz z;0L-NX=d8Jaa)d;ESj=UO^V|FMqH_S5AArur+#IV`7P2fzj8UT6|YvP$1N|o6jm81 zQvAyJQH!$WOlhfuO6R3ao75D8a_^H{e;0z~=^i<0TX`~Jel?o_PLd!3CPRO7`=y^lI%$T~AKqnlHha}I{BI>smJTrioi*fSF3Yi9p zt~h2fim_p~!s4JU)_C;yISW?EXaQaXv*AdY8025ube(vvP3)V=G&XyJMB=ZU)vcwk z&WCG+m&O8~y@njk3W83|Jxqtrnh-+FZ>VNqkMD9lNBB=nk4x2qNHn6Pg$>d&!k6$P z5eKXK-A^gVh%{uUAa05(qdp`V$L4ii&+`g^z z-1>II{QT#u-Q|v&)`#ld!ug}!Pn(yKLwHHssliV;CqX{6UN4h+?Sy!vh~JFsk$W%C zH^TG8DMkD1bcbPEOF%IqeoE4yASST(Gu@En-QFHGH_#hh-LnIiIs$PT=!E#G_g>=p z_q#j0RsjLSlAqK9oJVE#!K z)6m8nVdVrWb3Ffx{bZZ}P!At}2@i!y!W$(3f3KG&v}^ZM-{*tk&LFN?01)SB+AQji zL_+<``u7togn{WmfcRbLrx7J5QG&;;-UtitmZo7QCh%CJEa8VQMrAn{CqXTi0?P`* zROe!2R29So7)>2SRE`>@6rv<&^>K6;jg2TpCq1)EeHb~Vv54CEgwO*NR~1%q)xVxZ z#R65%>A$uO&?L>tHgj)Gz#t0m1|6Y^_{K?i&=_vqbuD;84PX8-G=zKYhQG=jBn_ zi#Pi~t*CA|celSVr%4~nZ_FR)R^5Rr4cQ~GLA7m0BpelW6b=zuf|_3`4Z_DR+@~yK zCjx7|55$l4Pp7%ze}S23PaaO$qEyStBsgUG!D1d7h-`|~ku!o6b^bSczyObTpG+ab ziFIC=I}c;$DREwig@8aZqZ~@4&Cr@k;6cr4O*o%^ zM%$kOfx^!MltXC)fjKCGvE8164I+^+R+JsgaKE}jo5!ZU~ z$=t{jVXycFdc$zo8T3vTzc6nu>j1Ge=md;eFV_-$-2^bQ3Nq=!^d0R*PBV#E#asB? zjPOQ2aJvpz-7I*pJeu|n5vfz~?p|}R2c&k4s;h}+chpZfG%K=o)Ul2IUTxEmOS1+P zOEgJ+&(ZUlcKxBK3c~S%YN@xt2XdrMt2kU33(dz{$V zp#uA5w){my%lMUJvp++$2C9TA+GeOn0+D}m0}9u2sTyn+tnIr#<8(zA#`STGmz`yGVyB5T;l$gDWC=23?rX_H(_bdbp*UlfAIV#_5*GTY{kVbkjRpGp`K zi;;BE%MBwcjNks2*ncrs({Ef3`G_jAWsymGl)&-Wjo7g+gYViGS0Z*Ikgw^|%NL6n^U6ooKh zA5`=)D{y{qW56i-s@@kn*Rw!)y*72(lywYLDi=*Apm%L(ILRx6Bs@JzWm4$`xShxF z7ZMI4-WCoLQ)49t8-w_r!d3aNI;={L8Qr6RmI1bQGx9EUdq^I{!}hJ{g-R&vRsDCy z3ZP`JX~wTXFbV|fZ@=X<$#6hvbO3cc6hWL3!BvfNBo&)z<*x*&Q%7x+f_Foz#<8}x zVmG@p*3kKk1cxc89$$Tffz;EWOIG0=#uDml>`&cd`Y&cVvLxkDcppPL2YdRT|Lg+VuxbKC(Ffc#L zg1;8qeC~nk?ngWwfW~sN44=S6{+m-2W?pM z1*L&no#F|N?9ysN+Zz%7+Y(w5vupkTU44Qr6VnYdcYUE@w)!#{ zsH0b4H@=Bmj)?Vh8PL=$QeKaiDt&Bfvn}`RF#-yRJ)rJ?N%3=%ahmY#)~>I`@2Uhv z^4paNtTGm&nr0K-DpHP&(D@sBkE~gyW(7;(Zm9&-ZV$q=F}goQ?6UYpU_E69eCjtO zc=>Ustt+jJ;V**HUD&Sd@-3*NFrgr9OS~F`m2(#zOO_s1 zku;(3Wp2MQGny$r5pz>Qjsf()aC_UlkZh33Q3w?}k&1;z{&!iLYTQLB(drroZMiK` z`THI$IictU)R~qp$}R{Za06jS);ZG#b4c-o8bMjATBoH8wX21wM<7JtWPrj$#+OKE zPtM-RIa0eDO}8>M1rTju&iV=oKlL~N5-gvHX*ZuUW|soX)m@*2%-HqUJAhr|2SS`a zV)4s@(zaO22*9(M#5^(hB-Xh~%?;ZO&IUrl0R(6WqdlW+7pWarCzH~N%R^kF7O|^m zC`d5`2dIcu7P6olbz(Nmu1TagLZn2iF*(0i z{?D8Ep$9T*E(Kxhh4!|IhCck}Ev5;^q_FFTWp257UDv|GE+p{KVUrfzfJtzj!&n#G z?~|Rmoo;e;Lc_9SjjFnSM*rRrnxPbSLG~MiJmlPre0uovNo-d8`;2{42va` zD7x_(Y~crBHEB7;LfY;_4W4I<1K-G74f>+B3jBLxer?r6T5ueeR-!e9V@jaV zbZ#x-I(miJ)FjOM5~E6?g(f*zW!dPu7jBxu@x_l>>!qh8qXP55&durEO?b|L7p_V! z8T>2(b>hhA;t-GmR?FjO{P}oH;&qwcZbP>-2o*OkyXM}*#FFSByQGT=gTXnlo`cju z4;e;n%r2PC49Wf5O~&l_WBo(fMmXJAG@8GK^ow3HAH@trS*H3pCBjkCi^OI| zlt;+LJy{=^C$jOv?NF`4&Vw5~@7^z<7eN)p##vT_vtFfPBUHu5L2-YE-&j=wuUq7B zUl^B@;`ax5N%BiuNazOj1$Td}aq9lYTR-2M0ZPT`H*K21U~qWDmC2S5?uL5-%4H&h z7oO7v9IAY?D176EmLRwoBW!e`DBZZZHlN0~Z@1TgisR!RD>~S?1}Q!zs0rYMXASfv z?abt70@%I0v{*4&VR*7>nQhwCFek!e ze__Y}l7t#;S4|TdCrlktQ)>FolAy>|)FiCHwB$+Nm3PG7_zVWcixNqJ(a0q*ZTzx! zY%<|6-isy^H^anjUrf*z0UA9M7-=*PA+~NRjURlyZq%&k+E3u~!TE#4n$f+FtTfiY ze?|y<9@mDPWuxrz%(gv_O{RJ(q*F;0sR$weodnvzo8Qp*r)N1Rwv7K~#NrcoVJ>2W z7Y@hNF~L1OfNZdayU!i%V?X=5)c11xhJ0Q+DzReCZm9WTY}Z9O|Dy|+eZ=a=PDBYL zvQcG;30ALAQy6H3eg`fA)dG5CFhb99vy|IyWlUaCFNy()j{u`h`I(+54MOK+FwqkP z{|TbN`G#OBPSgeO*v4&=(^zu*qd$ztuweNJkp5?mYq$Y~6S5p(rE`Og>Qw*`amWmi zGhMk6bG?$uLwLbMeZta)C_Q+Dag^VB&{?g9(71wbNh1)i zQ~tIAG3lcTkqR1QbiTQ6HaBgh2zO0D-OpYOg%m(--(kKq_doKY?Hl|$ob|Wsytjbd zRgEYg$q1B;i-PIP!pAleQMKU&(fl`=lMh>xPoT6sn9dcBcIyVF-BQ@9=@>RnY$4?W zx%_A(=yS;KyP?_ZfvGs1>Fy|sr>{grh@!q1|Gme2MO5HK=QV!eFRgV6)9EH0G>waS zW|b$iD3(gc+}4uAX9lDQlJLfIk3x zRy$`8FR)?+tI?J&9p*pv+4oRVk6K+EiXS|#A%wKS;2%1}Crl(8tmp!s*0O|Nu$=If zoc_;W*wbpyd;6CYyFgs{$TDrPK!UcRT$Q>@&(48ei>soKMdmwIvp=n6E3g=;XOx*0 zvzN38wV0o|GakBZ^Bw;07Ly37+ar?Ko&KGE1O!;GVJW#{Y%)?5D9jN;2^IM?xO(^Q zS+@i4lehEuVWR{OJbYM%B!Rf_hXgi}Ax1s))~62%JB_SdKrl(2IVDB6r=z&k_Z)%@ z#XC91MXzjra6J)-xI2Kas@M3U`_=B23_C8-*wM)Ayj5j~4lQdDugjLK0GudFXghv0mKD_TGRwZkc9D$$wU$DK~43wnL}6aIBLt60;$ zUjz#*p!)DPd(IQ^)490x1s-0MtQ<`XffiZh=jehp{Y>^?X;G%{TyJZQe!AsI_{VaOag zX5WTtO3709+A4$=+f~@&@ela4uw|T!VsP3ZZZy1+Z5u+~gTM3;tSpGYi~e@vaOT`# z6L!)0o~lYXesUkoKFQXz=(>TGwosH{YyO0G^gBWwA{5h=11O8kdbovxBY3;?Gdma% zt=g8{m11*UdWD1ivRgm>Oad%U6UC_bt)9wu9R1CvAlq4EzWHG&c)IxsABCVp51AR| zhrkr^wy%YJKchZRE)VeAa>!?;hyOjei!KDh43W4rCu#H$`6YkyA?_c46T)_hhxj7c zzNu9??=K0DFBsb;pLoPZ<>}y_+LB?~%|z53QJ8!b;`n%A`4w`?1%LwdL}tL^NT3-v zA$x=^)E_@*n8q+UZpze~B6fZE&j`@6z97=0*m_!2@dzM&)4(X-OZe^=h|yRmiSlFL z1zJp5DOgnz(5Sry7~l=z;slf|BN_^D%uHdf$p=SNK5bpQQyj<}zk*%=312TH9dzj` zs)Rb;*|BI_Y{Ad^#it8#SE0od4ioQU_qqZZtV$xM^DI({Z z%iw#4*v;i$5?HDNlnL9|irVf9txa& z^2%(6$cQ*Ef4uNwTN)b8#`oEvHTGlI`}^|?AwL%h3R~KoVlU~(IM}kLD<}FcC9YK^ zvHme(%Bb|bvR?%JRbs(@Ha=(R#`Q5(?vf)ZPsv0%PUE5WDe-%=9_(ZTCZT8XOUU#f z1N-J_u;zBpj#;r(=q|buQkVv3Y=)S)b=w3uaFn58+o|WsIOX2FzkcNuIs3loF66?| z8FXoQ5+AoN(cLmguk8I~l=Y z;{)?wI{3b$HjWL*{=Ij~a)opGl4SGwqKQ%KF067OQXkMH_dR$Gp0N&eYLHSiT|)mY zD-H6z>GWYCRT@zjiq0bN=xyI7v340_G`bP|IZDT8Mg;}q4cv(1FKh9g0*)B~Bfj{k z6cbaJ`QmFzQ*>pXLkV=_N5+x}uq+yFZ9$@__7~ucKbQAr^+S%ZCpJ^!jEOYny7f_5 zkGS=be~0KtN^?SeC%#2B3$DbmJQJO;{4h)vcGQHcM*&+;dQPJ9J#-a)0V`eEw5^rE z`yTg!e&2tuJUC`kHR}N`KXx|&DKguB^y*l=f*6UXd&q*LeC3h7v}d8c*{XyJ$CkO8*+zcn+|amX?ZVV!^Fkwbo6i8_T>b->-$CXE&{(X+wBg-vKB3V&Uil2Kwqi3%}f zep_EZQqS?ZI}cWc;d%{9KmLvR;HKTuL*jNty7YqE^?EWA@b&dZNx6BgX%lV~+*4n6 zu<#tThj9`lz8j*sqm}gOvR~ep=;NLo65&T+ASt%A>nF)h9)#zE^LmWx=@kO)QwD>B zUfP`nGo(MK5p^zJv_s>s(onEbpTMu(=n{OdUYtz|_z&c*5ev7j9ycZ|NB(1-fs$qi z`@T8>1SWpQxJ%v71e;_YMRI2I-Hnf9$B8YIJ-LuaLI*vp+9H5-?%PkB&YlM~ zrhI|Pp@%yZX%6gZcHtcMa)1Q-kM%IR*yZ*P0{EHBc0(-%Q{2oSvM@Htm+*w2mP6qx zdXYpA>ObZ;`Y7#~rcov|NvTJ}OO&bQQ?3%^^an){kZnCt$3dpYo#KQ=P>|ErVyQi0`v8I z)>m)zfZMU3&zK?n(~QOvDchGVlIzf@E8&9pYS^v3yV4DLW99BPpUwHp>F z3(x&{)7%cQ>B@4P5?5&>q-q`+f|edxv26tm7LxkuGIOnvW(W8=g8Vn<{sMW|&VPS2%= z3X3Zgw6r=_LVbPouE>=Cmk}J1X*Og&tyIr8<{I_#CA%3r?95P~21%*Kh`nd^$?~t2 zNS<{W&awfLdpL$Aok^-=Moot_g&8QDVDk`$WSL6{Rq z`}e=UQ(F_GwU10m_=E)59c|v9+PFqaCIchEPQ~TqGE6Ja9QU-W^ez; z{Q&Q1c;`ty3Ljgc#S~eb*QJWj*6X$E0v(kS{J1a*Tf-&AvLqE^&Hng4o z!S+>@WB%~3fSy;(OtLr8_^Vfd-08|Q@}O0;{wqybcQ5*{Cq#!hBP?kF4VKEki292i zK);#@UI5%`eR^#^+&S}b$&!9iZ}z&~pE+I3-Glbl5Uvets5x6(i_#8Jp>bUvCco#- zmBrKVhP(U5+J+E{=@oy~lT;J)Nz_aSqU3LS#w)i<{bQDLXSdeV(w$MF@B|lfmp#6`vH6oKU=(vP zp2S~%5T&tvVTOx&{fT?PfG`M?Cez5-ZfGOPS=b$qJAz7~}7QR)fB~IP^v0r{u6bdmX!9buX;d@rGVLHWoLKB_hSv)sBOa zlXYb9+vB_Wux$EQ-6Jok@%AasBYD&pebW~1w0DKR%ujO#o?S!9VJU%&wxw4yQB_&V zX|uvz>UWm;jf2+a1tgVm`8;~qT!vp2eZ7QVVTj;)d@ou{OE5<1ikfU?GAG_ceuC*S zkXkFG@y1M6`VH1M?~K&eaO$_F*!60IP4lD?e!QtrW@yD+)lmMGflzP~@Unq`USJY& z(4nnMBJM2+s{1t4qUb}92mbB;gWU#S0b{Fe?EJxhu7DMp^6cBi!4K-HdOUquGJwPkW6kNK`X{f-9~K{zWZT7jXiSR zD^V|XfZ`U@r6Byr*x|KO+|P1;74sR4jM$&L4hE7KQfd^OQ88K#F7!T?(l16V&3p4Y>Oo4F z5q)OQHEL&gLJ&rV&rIJk+w>{bR4|4(PM*p5#701+ZQqL7w8=m(y6YSsAdn|ktiz<9 zurGa4C0em*(4%UNX`cH!4f^U-O3xqi;MXf^V3-RRq=V^L25-#@J0oSi--VrtH7#KVzz0MQKj2iKr}9c<%P-Xge&`8{YmPLZPSnzYn#y}xvF%0M2i`9$8KA)50kSRfn&rBhqMQ{_GvOc1Mh0jUm#P*)zk^3=E5Bo{D zbpP1G5HC3 zS|793`$Vg@?B2hB9A-eubmPYV1b&OCH~j?`YkL&^?2$+u+md_`FGKlsC1NozjWXQ@ z?996;sjXXkyqx48?ZQ{2Sii9DY8fFG|{(9+~w!{_s|-e_DkKGZ7OzxGC3PG z)?Ru4BLQCb8nf*_{5LkH>%?WZI)8m%fcIZ)Vr8qi9X=P2F-*zq;AbHwGG5pjrC*-# zP=t}W$u&J-ssMGU;U7|htiSi5?@{+fVi0LIVR1)2v%gEWy0!??PeVy+sm4TJK;dV~ zX<#5mq)m}i9DwDT{Fm+T8otL=cK2NSTM3NCGsZ-@%=rl8R26}0*U0tUQ@vPznxAZ( zAC3L@OTeaTdN(^@C_~zOwu^3%@ZHly&EkRAd#W4bT#Gu_uZ>T6HNi~Lgd8`v10$4H zu`$GP`r##`Mm~=SC9s5?Gz0{D09c^@XIHdeNoeAG_zW!k`9BDpi_lV?`P>9{U#Uab z-;zzzLegZ21z0oJN)v_9O=Myex!b{ZgS958c9pfNA~(b5+HhyZO8&dBKH2$~AFhB= z^^3vJA}AvF&XPcZeN{iACu-&n?n7OLWhDG1`HPaWodgx^vJ%IUV{jYw_Ca%8tg0hR zfKE?{NU0g|u3Zb635C@@+7i>|($79_HAVCOdo3eJHsYO6eg*f!kN%mBEx~Na(?!w&jJf!y#|Z0kscq#!cQ~R7KF7loNTmGz<>UM-Lz@*MHX!I%YZI6&X|I~Y(Ka%2`mX26ES>jICuEG)9f!$CTq!TdZR2*H22N4 zLmM53jNC>Y=SlfaTJ7v+nxO8~v!ycy)|2$8F`rx9D&m%`>+=-gHwQ4&pu0Zdq3DVm zNNk;r(vThd9HQ1>=tT3e7SNx4sy8?+zcGSrAoA0*8 zwz^p8&I&4HLM?(#NOo@p^haxPm3NHcr{~by9(0#C+5z9&-Q+f0hbgCu8ZL%$OyChT z{-NpeQ8dJ$AP3nr9Eb_mLd?PugXs>mbSx{_BBBj^LH)+#3(>mtK)_sa}A_3(?e z@i~Tv1RMY%I~>oBRbnbBgYU;SZ&gY9%nYUf%Dc^&?kBU zQZ`WRZpW#DxP=aPJCp@W5uz0md_8%b8PTA0(iN-mPQFNeRi5MuJfi-;DzItM~`boi7Zmc@J=JvaV4G6)-WDQ<1S)B4qd5U`tcj@pQq{m^!mpZw^v%! z=}{MoU{1@V$X>C(WkCD%3?%z9CTfPTVP~rOZ1vX&XEt51{G?$iz%y5m9$U0U=7F#MlxI?9nz6#iFm}Qx%5@9x$aT&hyfmw7HHl|AvEj-eR1Y&X$#oLOMJ4jJoKoY zy{v#D4BPjSYCKRu$&a(BOYbuC9RKFJ2B-Mh*grDkf~G}qP(e_z6CGw3k)b_2*LqcL zNF+|w9NTpSSDeRiT3AK&po2lnrOu&Ahd|>_Gv(oua0(8lEDSC8Ap^uCvC=G6?A4Mfl*Iya%acCgrTAY`@)BGhPNmHMo8fYt{!KdDGs|a88D&~bVx{Vf2xhyO_ip;rv-t_wa z2niu?^p#aegiGyN(Z2Pwz&GG8REY~}(u%e;>uvej@&gGs0-F*)NbHPVsCrrowpekr z<$yZJZ^~=n+Zhv|>5h5bx%_|WqDtV8OTj+nt||no?W5VEO%nye1}8zR0(Em!9QV*# z692rve-*&)3 zQ=bx>l<-F_Rx>DDTpTT%c{KPW8%Lcld`o@k;XzoM@ufYF6G4R#pVfmepA0`jc0VK! z%~}OSfXYP$pMv3_hI~>#Q3RbTRR(W}_4eOZH(_nd9i%~BgoEFo&=D4Ch%^2n!9wkG zF-+ev`wDvDd(fbaLT2{4-kex?kx!n`b$nQ7OIxM{Qr>Jrf>2TS0?1z4B zp*q*dW-8d@R&Yo)5soflkfYI*uGphaeiOZwN&BNQJE1$6?Vz1z)46NzR{n)kc?SSj zpkYfUsO~6=V3OL%b15?ZjIH`+OO?9w(pWVp{_I^s1tfq|U-E_>wXTMB_#3GJ++dW! ziZ^WIdKV^iL&6iddSK~c`;fT|6|gd`@s}x=3lKwa&kYQ6mlw~VEU}36*01k zCrDv;>Hx(Q^GoC{I_`I33%`QlgjSHR5ZRUtC@0CcRwe7cKXxzeUwU_&-}(*)gr~U9 zO?b1P0ZjQuRfD9=WbeNP#O(lwv5mutJ`o%K2`mQPL1-V=#{<4H;+}KOZ=#Q#S-OMu z(gHzWgn5xmhF5F2trr3GkRQE&{BP%u|NXVz>MA70|MQjIhMIXVF?{MPnhx&T_v&5z zY$IQ2Uzqh7(vWUgI+Q3yFA43!5Kk^;sjB)*vPN}BOprfL+8<2fKY7qY7BrZ$InmiQMCrlWY|aw!>&BR>=`!#4 zYr^+6pN*d}Jl;A~B?A%5XDEJI?Fex)%K9lb= zRrv03Q#&(R)nV0}tViMuG3*zQiwB+qv69#DiF&)i^D!tTg=Nwc3Cxoibl0KkRwmY# zqZ<-3wZjnStpleBeF8z`!6jP1amc0xMTrINv?sXDTOoP9-->iT(vrI97IWhGk9cl6E8zvdOf<`KGugK^uR~pyO3oC>f&o4?|3tu zqhCkd`5q9@-~jsv5FY(F!u2~LE!>29^X2gD0W(%LEcnO&e*8cnH*Z0|(@k7$hVYyr zIG%^BXwa=1;xItqyQiE}D=QkDaSdwG+|&qe&4}UnHl8`?z|dtZHcY6RhMhY!*tU(; z^&vv=IFr8+>o_{|xlYt!-?OK5*a;<>IYf%Ub6{3?K+tv}&e%^BVdnwJ z+U41BOu9InY+xRTYxf{48f(xd1c)?H`yMmJPUW0Me=k3GvkqYNI!WOnr2OZY)tW__ z%h8tTDGktcs(}>-9_0Gv@RI;dqcO34XAdM<1Ckt*3$nTd&t`Ipf+)?EF=$2wLFXqR z?ns$SJ^ft(fLg7BO2t6GZ)2_HK=DK9{yHRChFX6G^lh(ChCsdxE-ZIJL2wA+u}>jv z-3hUABkD^x007+nNLrMtyFfARMotNV@7nC*<9Nub2F<7-jv@rUbJD?@3Hii;vnRVv zu3fol(@|ZHq02xR$2fd6fN7{`G)x$VfinyP?T(H0c8rUqTcFG3&KE#lynmw$`b2_x z*>i@xjW|jIQIa9mYX-VK2TnktO;G8|T<%|J*!>Pvy#lkkfH-C&`}3+eavaCxgH@(N z#{yb$%<=4gGMJQKC<4y~Z(TMPpn_)bUgb1GMkKSiAt9 zPy-it0TO@{bY}iYZ1|m@LRL@9N(gD~E%PvpBS^A3HT^fw(1~iyZ{#XUiK{rJh)E0@ zb`jf80sx460K>=M1G#w%%*9uOlbWR-isRroo;iRY`R3?#YA*$^Ux@t&R?u9~VOb_> zwF;_L6aD@WYb_U25J3;xknBEG>m{fx-wb!{9z?CXi+vzd1V<1Z|9>#-+y$w6889Zy zuQYGjkY-5fc(CR&O>PoL2t2oti@OnIMT6hEAL&I&rDe$GnHa7f-t=<;%)_pxNALp& z2M>9uR&*>bRMDs#s8%)fdjqVsY`jRh1*$Y(pq_;y|G5)=F2Y3!_yM{-3ym5pWAQwP z)3!IT|KJ+rfd?_Ud?ZQcr_0 zwxi$9F^P#kL~$uBeO*doL}9?#GM)pT=UMaAV6l`YwAv^PFzl|wu>cRVJ6hFQFbB8>XbC)EU1Q+xi%}Rj$r+csrv+L-$JnVEpVa*W!qb^u;rzRKJa>B z@G`3n_^k&4f8>`ZF5CiV*g-}0(d|T7S#z+opuwt`s8%beRxAt#L#(wO@O}h6=)kpm zQ1we;E?x`2{Sd;|cL49{sn<(E{UZogN7OowSD@6dMz1|>S6})Zl*0F%to|vhI!t{5 zln}&G0B=tIt*q*Bj*mo|c=JVbO$TlSMIulnf>zH#y=H>r1aRO`uUApA40O5!bb2l> zRc?VYG0bqH+u+GyeIn1(QuaVzwV>-F)I^?DmPKseTF2329n=jDqClYKJrekQ5b0rM@Yrkuu1N21PSiS;Mp8+I`51#+uGEdM?aZm<4p-D=vTVf(X|q_}ZNh zf=rwPr|)RuWmlgEPEhcukg9S~%_aCX_$jbM@<}*iVEaS=(^g#iv1(6ei=U=&+p--@os1967oU%hYh?On?%LyP?O?q# zUhl+C%s6Je>xhlm*_nwLM;Lo-)&qD9Mi?6mSO_c&3n2mG5J;%i>Z`iz%=5jE-~RDt zW@T1p*3n%pM9e- ztyY_-pIM{PXi*deUd7}3Q;W>aRS7bKRu|f>(y+HMZpOXwpQE4n4X|Fg=X--Pc1<=u zPjzPTie*rfD4^TgBn;YUhSeMXsqbnWTBbL$@$|+aMS4XcVHz5mrV<1ZPoG(%)9#?C zDsyvnP9C2_RxO&rsFTZ;Oa|`6m6Cj{G}$t~%f*$}$VIB+nas_3v_b_%+dFzzH3QqN z(r&CHL_waV2kM^K30YCG+$wH$7J;DC+#vMZgM4rjhf~{Pb<-{dzf7mhEjKqvqUkBD zLI@uG(ziIWQ0Lf@IgTyQaqQ?EwYrCdK$hV6(Rq#?okLRzNmMFjl|2X|96e!cD`TS( zvN-2pI}S@rv&2!v`ev6fj7JP?`y{=SY;W@JV3|`CMZtsqCk|y_htbxa#R_M+w5qeb zv^}LeH{+6~IjfD3niZh#Xr7Q|1z2fCJQ>%L9c}fyRKtU9C(M_AXUvVQs6x{#dcj)>N z_uO?Wnp%)t`UtsyncGh!fJEZHl@ESc;w3LS$!xuxhxlgvk1Q(3fs&8zy7NXPhWf@I zoV>3;eCKsYlFZUVosa$1L%j73FGp5nF05>^y4K*=fAMV~QjC|Jb^9(JZ~>+sbcp z|&hwRUQjwc)U4k zH3r)k-fw3r-|nj15@p=eSfgIEs8wBT$KizI5C$Qe4WGb|NzzWQMQ{%LnY zog?BTQP@F}mEO=oIR*N~&c{byf2ZrpL2%rzvDFD_S_ZZ1c4T^Fv5IZ$tXyg`=cQYz55Cx@1X=p-ZTGIRKX?aY@ko(cVbn0?Sp1 z!wjU7j1{#UQ0W`RmV479=tC$H4qIjQ1-^Io3HH+*X`i6;?Im29=6K&&i_Ihq=bro1 zN~YssIUb>3M#x1mE?ku7rKpcAD}#Q^GHv1w7-KX+q?8u)R828k1)!l9XPv^aenIif$MrNsJ^?5E_nG zM^Y5*IK=lOF0JO6X25LS!FFs;IX0b6m(_J2T}g3_@_ZT$D7dqO)s*P1&NQRUy$%y{ z%Wa`X`rzVz(44d^foJ7hT5Vxl8oItsAXU#IOLLm7kdt#2y3H-JEWt2sOvNRR0=mtE zORE~Djcz%laYX2MNRxP9wJ23L%D#G0Agk(uiiJ=HRpofJM4lz&c|n%veB>|7nv^7g zVQBo!d+$M(qOpOu@;(wp+J(G#4vF5%dFVXP^9)th2I)$GI7#{7hrclRzisPG^FR5^ zzyAKHI+g$cAOJ~3K~xH181wA8HQs#h%gPmcmU8mMB6r?#Gym}ef5XCDmATm}FL~if zUU2gfEVo*={q9G51ImJ6`Jwb?$1{PV$;81B@f|`AdYXUXv@bl3LY(x<~ee}#vGc|Lh@|7~SEKifDC zID0E zq)9Zmz$mJQ=Q-3hosEr6&Yq8`RxD=f9-imox(=;Yht-WPj$UBtWgqgSwnE*o#=3#3 zehtOcuq$=)JRQ;e-U|cA5>;TR1#25V$CgK3M`r2{8=GC$*EXotJklgOP|tB6{Zxb` z$z#38eIc<)EswISpj-B!-?<;e*lu;CA9(8P_S}xjf?+TyUY6Ei3aX;;vfFP!Q`P343WTLj^<4h$5fU&xXv;I8{^6$g291P3ZGZnFOyKY$M zmP4MU6Z@UxC>ZoK??l;0Za0FAAdaK_yX&jcW+LAOD=t+`95l>n* zj3(-(2~&?RzV#T0;R5Ppf`0woFXZy&29G@U6fe4Exo03-?n@MOSeUOeQ!{zVt;?v2 z!ed{5n%iG|oT4c9*Ts>>1*##FCB=ZC^Q_E2%j)ozX6Q>fK!#%)nGDO34u9c0WfQ}0 z6Zhml8Py6N>QhWsK8Pm!6FVI8y{}Z3)5jgU`%qMkB2NcPq*4lW zsB^=6B|_TW!d_7|bju;Q_=!<+mTjz)zs$L`zAHH&6uMgW084qm%E~4eE^ZJ8A)0Qm zurR}^6ARSqE=5t$Ty60GJni#=Ga1_Kn};l_rdP2M38HyF!IQsDeCeYDZ^3>9wp;W( z+$LFm-U&r_o1hOny)nM;d*8*>3TEAmZnwkfXVz%9I>?H`>}-wePR^4HiDsY@XA(&! z(Tx<^k8n(CC}2aZVuhBN@1tkEC@lnu|^bh zrXDYS6hff(a>J^sqv;;_^W=4~v5M?l_R@laKu?qqCic5!V3%i1Q9*_jGw&!-rg zK$RyGt)`o})fs|r>p*?bhUH+G4w5XD?Rxuc>B^G0BvYfD0xo-=HvtLTtHM5F5?PV? z@W&qPw<;hI+<4s)UU&DcUvx#j3}9E}W?n6^uFVW>iHy%5zt zL1%q3fvH+4G!$I;b3}9K1T=2Iy8iwA^<{W)eeaHx{iHW`gQf^HD<>-=*47g?wn7%> zTrRIRxcTTDYwO$5M1Mjv^jnzTop_6{Ct81qbn5|#pPl*|qWvI2`$4424`VL81=Cp~ z3Oa)&uIX%d%=Dp~7Qv+<2XW^m5aj@^`Gtvj$x_Shn^P&>l;lrn*sAPWg+(H z5o6@Oi}N0*pN&wI6kXYV4~FH8wU=r7sCVFgJ3TZ-;21d@n{AFC+g|0^mdM3$MoyPDA(6-q!7`qUbzKba@GP?v1p!RxvGiSEJWbb7S`={YQ%X!G~9b_fnZz zKokX8nj)(TG9jX~UC`2JUpLjbRntwp`W*hb4A;%L%6KaAdJ8gsog^qU$Pivo0r(&$7DO#*bnQwZJlE(h1X}hUH8x=Jm;1R+K^U zZ5WPG(C`yBw>r$uY^V9==R7*yh$t19T6yld)tPeDSQHey423{h;5AGK-7rTAc6}sK zSb7FdC=AQ8f~xB1md%;?+gu8sA?!>JJ{~FV=he~Mhb9gsG{Z#KO=P81$}5V3A_=+v z#I|ysqUwMkPt$=;o?Q?cu-{|gMpTj_=ig9nLe_R~d@CJ}mX(r;R-qbPFxb_4h1FVKDRS;#iZJyE=Y z(p|oBAF{bbW#+|uHsDug7ie$oub1?Zda^R7&CX!+8h@r z(hQSIZJzGgKS8t~+P=Yl5#EjO=cDIC9@%_u$$1#MTJVUg(GxJ_O~wZ8M%j;CnOP{i zGkPcUKyJ0$#&mANx#4A`?QfHA+>Z#pHT5+_=V7AG!$|I(m`iU)GL8+@@nAf?fwqM1 zUeDIrg|dKTxf9h24-82R-Y0-&+PI!h5`_mAVggW=(srvG`CPnIaBO*oH z;`l6CmJ;|O?QTkIJw#V!OjRJur4G&Tpogre6Kf}i=@5thM7MC)%vsy$;@BppS>|UY zNn&o+VLm|9hJdnVwf1FLy>1libA)wH8C%oCJ~jHQo>h~ zWr{rKV*U(q5fbMiLDr$Qxxe!(i9;&0i&%w6mX&GBVU;|mGBei7si+yMs*ikcWu$M@ zefCecB_f6(*X|(~8lgX)(os|mQ53t@k0wC~fe>Qs_z^`xHe^$$8y1dRL4v^wYFC05 zf`Mw?aKE#nN{B)XM!tvd-~W9T!N)|TNrdB6k@jHzBnpT$9ew$IB^)Ld4S2XLfCDis4DlmKSdODcqsgveeLUm{$KId>MxLYzcbjD zM;D1!KSOo#&4k@HLAPAK_b2AMXZ~<>7{q=l-i`kgA2}QF)yBa_ZGZoAIZ^m8Uw>_# ziIbj?j%HX?>I=kScc8H$L_yeX5q4Xc&N1xkew{2hL$dyNi0<@WYSH});nQD1a$kl% z_eQMw>j?eMczVNq$)I~94t-3=n;5NK2}FOzB})IgZqY^4&7NPLbVX$CnmOG#WOc2@ z?2JPg#&kLf$P%@Rfo)q(y7*#cWWawoi^&vrB zzlqBmGN+Dh8>Ut(7IBiX*$K(>OQXX=z3*4mjMCwxZ`>UEgF1^ONfVXg`pC142bv!} z&}TIXj}-TFSL-cP$Igc}%ljzu47sQ4tmy`}S4RX-(z*B{NGGqH&G|PGOi6q0wVJ*X zlv1hoU~;lCq;&(J-2Kb{>%W@z;4CS}x@B1+2}_yLJQGM#pM*zEV$-BR6lI5pVJU|q zob+mUd%0H%c<-HqO_K<#a+0DDh_EOAQ^ZKJS>~lhO4fLYwEbNa&B2?0Vd?6fXM+RO zw7s%lF^PKzsm9IKA7Yv7IG0XeviEU=dmCBvks;-`g2I1-Wa}{$YYunjrgA`~Qm1qJ zKS6iM`rZ8@yc>RvKYKRd>&+`WDAakuLtT^4KVtLR>#nZj<99z_N1flkG7f(yP@V{J zRJMjWUcEP+woPDtiC0;xVa?rzQh7Ofo{y&!z9mA&SjI2 zO{1vdq|0c+!EsE~p#qp?>a4DJaP-NaTi?CLuwA;1^|AM>s9G5%PRch6IH}z-b-xaR z3;ELn<+z>LE-IJDsVpm~df67M8z#0_C%Ett($$YZF_}Z8>OH8Hmkolao#6r@>3UKF&~FY&&Yk81A7iZYn35JfR)JDt?svTFpL#szjo9dvC#sl}n2 z3UQDR3WP;2NTPxw2fdPweHQ>x>>#S>Y0{OaN!I@w zwRR7+BX1^&LZYC9s_7$n%_Is*q7Y3txp(HLNaAo;J%y*ck8|^_|CVI^v!q*Jq=H`Axyh9Nsh z)w{75--M7ILcdL(rWB$;h+^c*scNO7U6v*ML-(&ns?Gqf(%y_|J1B})Y7?CQC`IEl z?3SIEDzC;o@!#>MXMCRQTsyD0gA(ihD@IoeJlBM5JF0%9xF0uLrWW6X z?a3_6*6_5^slqfXh@+H?mm3%wc*gGETj?P05q8Iq0mE`A@_gb*e_yWjFkDGqrM($d z)lfAZMJxM{Wkn(Bo38+6ujyGev~_2eJ^R65rh#*mT}>U$N1zgzu=1B?^HI;((RmcziR_Pmdn&f66GkG zgk9NwibL*pny^oCX}Q#%TqN9yDCnYUvlz#Jg?ROo5PfgLy@tZ1!bdbdi{JPxlJ_d~ z`Fl~U8j9*bZ$O|=)O~FZT~T<0^*)3UY~`y+NO(o9lp0Or!Sc{reivflwIr*bAZv~b zdu#J=Mqhd_k8UO80yJ47J!Hw&K7Rjl^{S$2uQoS`1oAwi$TKXbLeOa*$b@uwRbno@ z9qs5l2`_z`y!9YV8Xo8&51vMyGGn!02k!l1zrE0oihJWfBkepv zvi>>5(BR0R1y53thQ4Icd6;;pMGi>=*#y}tbJ>c8BwL`^NV0{ZyVS@j(l&~HlH5-b zSp-E&CNffyqDTTs){zu<#OM{-qzFzEp8aF$>P@_7@kVC7BU}h_&ILJV{fu*d&Sr9e z-o-=0P9ZH-FCAjyC_s{=()d78@!O3(C%mSiuXUkn2IlM=v5&r!;L_hxH2)qkp_rq1 zFG2`t_$r>6qYm{D?{_F-H}nII{if<(sk~thCmZuO3G`F#bIb6Enbr|D6MoNhZ| zW3!8HXjDA|$FVRBgZX)bxj8W?F1ohD+^joBsI6w3l{Ft*FPQW4!R4plb1uuuP#c_v zB%8>xj3g__vOEYpCK=9#etXbqHH`hFIZVZ-rY~+2vNnq*skA%aBJ!UkT|Y-FUd2jV zjI`NY2^1G?;l1dycM*0w1QS*S&lgN3=n>Ob0YN)MlEAC0WW7S+PDqE`xzWdP#1}^a zimDBYL(^LBh7opKgnpaa?5)`D3+QyeMzH>A++bTDV?fTb0mXzIrbr=AA@2;56vOfD zFg2x9v}dLsRz*baKMg$15?_KXXekwJ^LlQzujeJT>v4|XNH>=`>*t&ea?be~XZ`#@ z?Tm*3({i^}*@U=iLHA)~X-u~n6RH|k?bX;v-a@+dCE}G2jnohH`8Oje3P+Y^xwO{A zP*UvPG~VvI!~1|V{Jl;PtA{I!ZZv=&%d+WCC}Zl`%IFn?HdPNNvmI;rF2_cByosadl}J%KOWpBo6AT_ zIkDzA2G^flV0Ep{Mkm0tGVFs)NKHUb*?jPyW$8L@mQU=OKa~}wCk#Iw>OQ>y_X|Z9 z*t)<_1)V4%igV^AnW{EQXK9+#Yg2QB^z|sK7rf$?zMXZhX4^ggUK_P0Bf+N%#bRlSTL{S7f#;8dgk)j zR>GrO={3n;8@4mn-UX8fjr!XrIrZ$9yj4{vYkhTOn?C;*wwgX^9y4FBA9jCls`8{7Om6~jXyWsBG3^}9eJEvjrZbJ9dYl2l|#l(BhFo>xK) z{SA^NhW_sTpYd~U%U8*AiP^eSrZaZr-#529<#37##}=*9Ft$goSDKC*Mig{<^14;> ztaKL2(gedAzliTlb5yh$ZmYe9sPPc2eiHL4FRaKWXvdJu6R7qnH1`G+Ymq!l$3IIQ+uFpb%uH3g{C;An!Us{1m(zd}*wtRH*B9u9Ao7dtob!ZmSupOreXVe% z+6z1LlgrU@lBk1W%`kuLH;{@J;iXR@{JsXWTndax^5E~%*+m&_m!$GZ-4QvJi3+g*jB>1;L1wPF7U%Y&(J$$fQM;OjMCom->uL#VezJAw<~~RES=oxhysp zL;ufv+w!7J+2r~5_BR7i&Kh1I8c!t|*uVMB42XLETnexoLKvF?Jie#KXu}`8p zH=sGk$+L_sOG?|WFd=K7-xpUDd0q}&?O|T~{eUV2Bw>yapj$Es$dX|CLy=`y^kGixpYD&cdbK%><)1>;es1_t{eNu#A^N`<+#&?B(i_eZWj8^1 z{sR!6WfT(5Ex!k{fyhIOJVq2TB2T#3%n*7EBEcX)OV_`KmDu9Zt%S#V-603TP9mMuXM0d`9>#9nB&GI7J~EA2ST~T#3e9vC zbZF^kh&Nt=v0BG6Rc5Oewqs(N<u9Ewj|wzdLYE~p8FX3VrWqA;u}ORLVa)C$ zXvyyKn$`Rq)z&$}*2jp=S8~_v-MnM@CLY~Nd9;ym@d~2qNkn=j(er+x8&)s9u}u)x z%w2qCYqa)p*($Bhw8BAc{V;1Ao$U?>+rqTUpZWPRvhH?68tnu{D#=>cim_D2Xcx!c z2X&(v6Nr~mt>jd^84PpVeItouI^B?FJ4O^`AS5V7dt|9JTvikbS?c|khyU)~M=pOP zN$&lYD3CFYQKHv0g@rknnVLb8q(pH>6lFAn(kD?>1d1%slu{h2uXQqE*Q=@dm?PE#iFu4L9954W5OhE-~VXu46ldpi|Ga*@ra{sV40`NAyJ1tjx0iggmz zxendEkphK0P0H?(EWuyDcvaJ)KS)qV)aWRCoDro=pJ6Kli>p3FE>QK!1pQp0C~`F2 zB=S20QtlJ=H0*Z*@i3sMI>E(18{4jWFTlF)H}U<5mY)rL>-zYbp$!C=cH(Bw;Ewtm zxZ~*CSlRq8!Pb|VkH3N{rk^Y_8OzZ_aPc8FR!=eK-o>xocn{|S2_w&T9h=_|`5p#2 zPm7`r%OPHSWOSo@8{ayga=QC&0A9E7mxG&9*~eB3>>V8rBV^r+tmj{?xlI57AOJ~3 zK~&~SqtdP)(`dygQik4(tjCY+@h$y=;hoaGv_pm2S)HXJ7wsg8@w;WanKdY{mRkcR$-IF+f@Z02XZ5#3@+8MezT1U*%0?nLITYN4VnsT|M>c(KKcdsI$ zB+FOdg0&B5hDDKV!jMXpY#v3My$5Zk%w5{H!R10{Sb=;mLVT)|@l+?{z6%j|)K7B9 z@{LsOpXKz*LrCo}vzYC^46kI*QfWSm-})Gf-koSOcjGMFSlSPT-2=DE9cJ{rlcdY^ zMnUFptKSvIadNfJ={*z(VY|a&jI8y3@34tsS{SCq>})xe*YzWstr*C$dY*)hY?DHo z{J9u;m91E1d8vx)I*6j6)$Y=4MdW#gsTFuev9DF7EWx-6*dFJTm9y3M>H0BC3snqV zMboDBxk{*-j;iU{Hq>er8e1(cZv?nTj%{3<^CIlFa4It-ae(bs=sfiYqZ;i)Q0Cr+ zwe(gx&5eOF;{T5!f{y&0JQKJzZE}vehuw<5hvDSC7y2i29CoSH7icH@Yma%ZB52cc zh&P6uP>dyJCJ7fW zH&ID&^n&N$Gyq`6%?Of$OP4pv@-i)An<|#6qU+_4rfCy(t?M&Y9M@!Ry+gxKaEu&X zJ^UccZ*NgwI7+bcHzB??)J;&irV_VZ%oqG$R-zMlZNm2#T8&OX4$-_Pe z!KEr4vy5`&DphY5H-Hck@!(0roU%5Jx#WHn%4R!*pyzyu@kSt zUN}V@`YbkOR-^KH;r_)XbWL>S8 zIJSvxZ|hym)+*S+OKG%jMOSmqC||+M=a|!vasAOFD2hrD1f0Lvq+(qgg4+wWUJQnG zvO*%yGyJYZtAH$*$O{Qwm9Z=p%TVz=8&xZF*Sc9#X?`xW^jG(XW)!DQhqVTamFCjG7cS4Y z3GOfm@7t}EZ?{rhRpO5N&D?SPMHu?e@a)PzV*8I!OP`+lSh)z9=KB##WcQlaJ+czaLQL(qC}cSW5tTE|Fy^?O5XS zM!@odL$$W;JmPsCH`x{&n{77R5w1}T99FJse|l!K!83m{cAKQw*e8F10u>=b4AUmh z%R=Op1XBAA)D9D>W}q1+nr4vg!aue*$$e$#bLoTr^dis6vXml@Q2V{jX;O?t%=wU5 z(&)Cy1T6}2V3W-&#cC63HE2x@|=~M{Uw+mZRriU17^tzcuTOS2QRH17>MP83CDabbpv8*pi@ zL!4!}#&{9&An@w*1ke5fdH366w=8mD2j@#DCnAnrkkie<-Wc|rzmpL zET+gy0xMlgic-~1Q3<-OYtBECB$rlOhJ_GM4(HsK!ix1e+7#uFcgy(2Tl0>WHA4-I>7tRGa=Yo(=TnxFrKF1vk@4~D61kvUrWUWUK-LFr5tX%li zJAVhAzoYHFj$gdtpYV5=V?KNNaQa23^*#(6If|{KXCIx5CXUx@2W@f5`DMZV*x$dMzqtRw{ zBf!uKbVZ=6Vk%ir>Y(zfb4Z0x-hOoKHf`=+wEC-PZT941hcsPM7#kB$(-=k7P znr@=18igpzZjU&kC& z)7(1$)112TI_|p=vKC$WK2IZOMb(gHLDt$H$|=+tOy?9&oZjx<*jXUlPyTr~7?z8W zR2-3%(U>0$2+7t3o-HG53TK{O$8}7OF4tLHsL^c7Y;JY2_3uyq`D$S41%@W*bOM^~ zgd+4T9NVoS;uX@(2gY90Jo~A`7A@K{pKMXDyn|40nS4(Y3@*g6!)s2ki#BIft?I6WAwyj%Qc?5z~JJ zC;aBvbIi9s&gJht%^QyX4A(gx_g#pH_wn8D#~?sAZPKmBN490oOZnCn`Z68_aVBG1 zCPD}{8(kJ^pj$4QVbX1Fua0cJAW9?7UfAHsVinUgSw3PCM-iJ1pH>iK8`I@HpN}xq z0>drn#)9viNydtZedvaPZWvT+uq+CqD5ld*@dKT1nxaYxx|-nC=J22Sk7F5O*?SpE z<>jnjm|n0x@V@uROyoIc#Ty}LNs@co*7E4zvWzU1y4Pit9FoM*SZd{3V?P%oRaPYO zOc41wc14|!Je=NX!AplbS6Kd)gq_)q@tyOJ}K zigo?}LZ`JcvaGQ6g3IeZu4_}RR@iDr{D*&Z;kv8dt*b`g89NSr{&Ta=9rc%S`^i_* zXnd9G#-AbQqX%v!`X>3Ae@(UiQ@sDySMl)+Ay2la7ZCSD&Wfs`$`B5z*9pbLsocyH z=dSJYGA|@_Lqkzj!XQLf3-T-w^163UzE0-i0%d)VnQhVADV&W)8QY4b*H<7|`jXl4<@D74* z3&R-KtL|gJ5%i>7bLh8lYqLEes-7KHk@p;sic;CGS9H9l(wqChe%@!0%cyBwkR=69 zb@v{*JQYaJ^xL10HIr^@lj`guMV`}bZS~wBu55(0tSV=SWV&95q*c)uevCY4O#4@o zz}7Pw%?`7(HRkFT*WVoTt@P@Ja}EpreE4TBMSSjZ#E&1p4e!*yAiVfNoaj3v_f?93 z#mzrvHTWL?{Y^j51FJEAducpJxL<26-Ly$sUmck=(`!G(>28LfZJ$hsoqq<1Gl^=o zOh0w~XkW^Anj)y$IUC{kXkVDcu^ndW4vtl2dD$WgLpHX2f-uI`e{hIe?G+KTJST}# zy4{F0lQ47{&(*PQ1Jf`DMy-7~wt>^@A#Z*6(_@BYQuTG9Ef9BBcYXblIe)Y3(MXk2&2BHF*CH2a=5r)fcSz{xq=QbgRKANtOs8_i1Z~+K!KJ@O z^o%Ga#l<@Ht4Oj%k*pz`N0IbJ5MpYvLI}{*^1zPbj8^g7ex|>Fxk~(mJkVj@IbuDW z4=)7#*K;9v&%3Jz8AY2kgGy75NtyAW|X$`9;$s2dj9 z);C7BJ!k2SRK~H(sIJ+LnQ`_e(~Y>dOqW5D1N_**zc_Q}6}i8w zx`C!C#9N;qY%`YLh2q>ymglI}aiS>Y^4S$UbNUAnXEKgs0)mx|g!8#M^}g2%{eo&A zlLYmL@z8q0N>K2gl$y3RP+3atEJTyTGkU%K%fWQ|K4L~Kk^HB?n5 zY;8{u3faV~y@V%LI{Sa3D?m|5=$eMAX+&X&D(}AI17h9*N%leZ>BbJ-i?g^+mxY;G zEXyj1ItbX<@(IHPTQ5d@6n_w)s{&okaf~w1Nb(%No3PdNDGG_3ZdgQBWRkVN9($}h z_g0W~ET>WqWF*lQ2TFS(&r<4jgU8l#))I}|yy=2q-w#ZSo-ZdB--%|p!4CP+rR`&W zUm;wU7JF(vU#W=xbAixrV|i7QI2v1;?FW`qAz1k&^pxXdV-aokwOm|jaQe(TP^K{Q zVtSq@D!4DITUV@dXrv~zT$3p{iFJQpvmkR&mdZFBtC zJd2BUVqww_6|($!m>1j!B&jScdS=d?n^Cng@+>D=|69aPZ5-nS*5aFpf)4G*8gb~O zC>oWS1>EW^hUHAu3b`62all=3F%>1}{*4-bevQmh4}drhCX#bI*Z9ZwJWb*9miY#^ zRJP9nSyA>T=pq*b%d6e6o50fd3&YW2+dVVHjE|sW|2Qj#G)MR}w+H8*%n|aL^nCNg?>q*?>p7Gc3R0cerHz$i(~Q8~2fS zzKL7iKS}F`P0<uHYbkFv$#+vE_y`0%Z2?10j_HR;y@k0qDT?R>Ui|5&A)A+5e=nOa2)vvA?UU? z$VPvAx!TsBq^@$V)4J&-kH4Kakv0JtK{a{SowYCE<02NRtTNw2>9%KWgppq^>ovnHowiktG%njf4=RN#gy>n*furQyJ69fq znULsY3Y|=0CDQ5S<=<%`;i>t^&w_sKY9CL96)qV@ zl8AyXMV=u^r7kg&TnfXdF}h)qG#^D)JS1xlNwHDv>)1+V8p(L~hOK%yN(BMPg>u!- z8by(jr74DKmL|1%bWQTZlH5U(JG8?Jt#c7o&tiUN7Ta++={Wel&&H;YC{k?w>NGH( zOBj}eNY;=$Ul_k_>79grYb+|(4U=SwZcZ9U15F)SQP6a=bYc;LG!FMYh!ThXn1GTh z3F=x#U7LI%?qmwxOyNSPqe_CADfhcloR4k39n^S{-Q=F?>PW}Rr05y;Am}o^vA3C?mi7d$|nubW$37`2-NIRnE_00}uZz(KE<+3eJ5)8v6 z7bfqYJdEE>E;m&iOg6 zD)EA<#to*ReQt#~jB#roU;M&Xc-?#6h^;Ejp>S7KqH%U*@Z7R2;mlNtY8AfGOgZc4 zytu02u3ltwD`itwkfm2pWIl+P7n}rw)5yjWU;o;-(XA>s->^itxq+-|X-(sab~^CZn@^iuEmm_;1=R}~!C zdO@SvWq!WS+^oauYC^@jb`@_)ZX?NU+Cha@JEB%KnXk{`I1Y~E;CFr2Hhm;9nW#$z)?{tZyhfcGGn=eutognPA z`z@#Cu_;7&l6dhc(xgckoIwTW7@YBJRX<3r-XUl;C=Oi2j;UyO0xGu6XeEzUDUM@c znFh^Pz+x?6I_G64R@mX(Wt2A@DY&|1(tP14U;Wne?AS3us#1=B;Zg3o=N7KK_8_O) zDOVIsuFyW8`<*Z1dJctx$H|kk?Ay1K#CGY_qpX%aN%_a-jDW^`&areD9 zbKs^!oNTAuQwsRZV<$K_yM*1Hi`R7#=Zfi_n1B!_&%JP(=U@B||Lh<0CAnOeO| z)T3kM3wibw^0Znl<`>%tovb2i!?gM2pFYO>ZoQhBZAA>zqR~$I)MviQ9q+q_>kjPX zJ5RjKxw$2N{Qg@>;t<0$skdVO?DOB`r+)l)EGhck^wKb~Y?lWgKEmrKX4h@!?wym| zf8X`QLLd#BKlsx}sW-ByR0_e=NN1Agj*s!e%P0A35A4Kob0l$u zVY~d^A3w^ycV5rT_DW_rWtjYzPd!SrwK^)E9Ix;bKYAD<0m9&S|LB{vJ3)V))7!_m z`}Tw6+#I3b!Z0nKc;;1pCA9|;qH^6q_c@P&Dpff z-D52*se#o*F4x?k);R<=wlcLopzg3mpNnYnSwDx^Lr0{ zk5BychfvcyFa+FMTgEOGdBM+4oN3SCnTMWa`}8=se(YWd16qIlATPailI!2QK-HLP{JjPrURk z1|MFxPmSj7`o)jYF$GaAyCEj2z_xNEtz(=#U*sF#`ZoXQ@7>P!F-@F1#P9z8 zgFO3^fYV{VSf=j2l@(r1m&Ej&0XP-X?z&-E3o_ zl5jnH;0Z-@{KOo0-hM5kBSo|pym0h2e(S%S;vfE=H_A;_jF_4ZMDQmiz8HM5Vk!T#jS)AIUZF>ajC?^hXX;%)2D1;<@i1=Rf?H zukx#Z_ecA#f*n5s4R_vl5P+pxi$DC6NBFtF_5rTkStdzh4(^}f|NX7c@!nhaF*f3H zeyPQg7mxF||Hg+&k{H7T;2fHn3b zym5LSQ>?GwG^EB4Rvw3zm)ksla*0!?=Lv%V$IT+J%Uto zK2V%;$~@bq@8O&`1t(9QewT+QVk>&G?_OuxrBc!~&L%Dg9gM;?2)WX@aK)}MUi`ruJo(i3$>lsOE8Bn9wI~z|=xCNR za{)W1$Jkb>6KRV#0?mzg+{E;*ZCq760e~ePislI4fA$PF9@@jT2X=Gh#S@sO)lUdr zDjZAEYz9POh?n!QZHIWE1nzQ2&%+>$I?{ffg~sc=di)HFiy5=D_})eB-g_Iem5sW1vl32)QolH?w1mYxYfYVDAJ6_D*oc%*Z;e`HEdrT(fVI zEA~$Fksp0O9Y17oskO@X)wWHpJFtTTdndT_efzoLx;?!3(g~ztki-$y(Hu8kez6~BsEJjnU^<)P%GfT|RFSE4NV7?YIdzrfjgH+SP%*l$DcXD)KSS zCBE?BlUTMxlwRC*y_M+MkHm0^BTce-d0QOcHd$h!5pX`0EGWtEH1qt5-9&5no?W=?9xXwtd9{^r z!-wu*=T#>;b?gnEf9fdb&o6WLeYdi2|9(z)(rmpt^ZK28`E{muj3e`fp%+Y?q#Swr zC;&fr=_DV#=O#XQ_x0;0*3@e4{^%|NRLVKRu^ismU8IfYfK1bT?{x;xA06S-pZ^y3 z-hB%IQIZlaKaJLDSML)DtHKXnILi}HXBMulc8CA|S8hWJNx>|0=6D;|wHe#)kR}f2 zKUL$k+0(?8v&^YeX!IqQ-r1&RxgBKMq-CMrrW)CeAdDKqsNuKwvAEn}Y&1`~oX6@~ zfu1^jo~NIEg(OL-HGHH|q1`btWr{FjZn$9$F+I{E3}gQ5r&oq0c%IGQ{iVM`xwtR-JuyPH`F*u_{fe8%|NEV{9pt9#b}(BH(Ku)XsTSP# zBe(PWzx#QfIeG>qgl8Uqkq`XXJ;Xv1#R-OK5D(lqEYskw zkKILDC^GWUqs*OO#&a!#&T4|5oT%_uf8tKinkeX?(cOs?HHxKc=@GPu&hWtfd-zws z{UlfKo$9Vbpq8FPNE^cx#8HB>Cpd7+PP_yA@K2rQ8(+zW@7mI%WRCLfr(fsl{X2O1 z`ON-v|Nb3(|JgI#@}W_dqB$b<=BB-9GOb&6b;q|mdL9PPR(Q6e(`vG~+-7?FC~1=N z}JX>>~HyJ&n?t_Iuy^ub^C5ktB@pDBYF9zV&IdnS0` zLlu(x_i)BPP86(s2VPWHwn(Lax!HS)L zWf@#|a5t8h$YtfxQ>NV znr17+*@6+fZEBuOZGJGs9rLX+<}X{48%Hdr>ho;#44Sc~7AqXjMQM%bhU}4o@rerO zPM&3aVgx-hf*nOHEj1{PlnB<0I1^HGqMh==yRPH4*U$3$$@!s{ty!IOvv2Dt4U>A) zM_~?Rjx}TMDL(q4gM8_$S;wG2k~W_OD*b0MURx2oLNHo zF3&#q8gZO(?6ojJ6YK>H5{tGL=%EYp&kO^Di7@ajC&ISMQ?UQZ#)* zs%=cm;Y$xaffRy2`ur>Wr$2s$C`y=~u-RQc!tT;D>@Gb+viuln=Q#1gBPjm_pqZI+ zxnb8?K63AsJpKF$mRmMPVIR_)S)*5L_Fpx{q3f>XtKZ0`F^#zq|W?iu5joAz?##p5WI;&_=A zr&0>f%gQu8*G6w(BD8CIq`y6-+{A968FDKlw#wW+uo_ zPqWyq;Mi$r(ZsZ!@Zmy(YQ^I{H($+zUw;PEa#pRo+3fJ=-*}GiJbAqT4`C6;GOI}y zvQN@!`z3C_UNTlK(QI|lX%n3WsA!(OI})~U8|8QY^H*7Z@g?4P^m{!1_$%CX&jFh8 zGDWk(>n|;_eft>q|Kxt|{fQaw{fQYq{No2`w*zKRbSPMrH+?L#2pZBPL2JcK^=5WY zyoYV2>)zCI$DFI!S-qKkGk3Fd>=p{%7>3;ZoZ5)krN|=6ojb-T>9skQmz(^;Puww*f-5crNATKdJ)TVSgXDOHRS#9{mKH^Ig)A2B!Y+HH+zi!);hzCA?8!sF^ap6U-iJph$PQn-z7Gq-> zPp$ey94OrUB_v$ltz{fTP{}34Y09zJV?56$2qUJ)ZE}Tamgmo0@bmxl-evyxQ$>PH zxY1n-mLtXaLXnUC%ttu>{a1PYwNp5@&F%NxLTT?Fo?Tvfe2apR>#x5GAq1yhKf`s0 z_AztA)f{c5%ms>H-`++`m-pXxZFd5V$`UJgUdz`XIl}y6i<||P?J+T4Ax#zM=2p*Q zOj3<$*+@e&HBrfuTFj$@v&i-f{M1Kp<>Bw<5orSrsNf8;eS}~B#Sinyljk}9>Kjx_ zEWYZRMKe(J~G2O$V)V0SBj zwAQF3;v*ltg+KVzH@M@y2XKv*Yixd@&cFMQUje}PBa~MB($9a0B#9Bkc==Ml#7}Ng zd2#040{`}RR&VPs{LH<0j)ydi?t_*fO(OhGlhJaC`|df!w;o#>zQCz#(J_!ajeDk%+YH`hteLw*WZ81pLr4R3M!uW50{WrG^<45@10t<8(d=i5=D&=v%9y1?2(tibNVJgo zOAF}|PW&zA-D^1Or_AJz(oX8sqIvwZ#gx07f>lAISqjgw9GwRQRcDHdJ%K<_j~3Vy z?|)Oraj|8y@2V-HFyzeHg`pjVwwuFobA&;Mv-KlGma>AuD0s7T$jucq=dx~%d=h7! zZo?j{^Q95a%+{%ta@adhEGh?t%#lf*HGVIU2YvvYL{1rHF^8v&kcGg8Sh zJGadA^cXDs2}$cEtm=n2y|}&`&N5+o#|*+6L&x)+IB}ZMlE(2LLq!YNlON|yV<(oMWV%Lnm#tO34*RI5S&Yw@xV~lVf>;c9Zhh z6emv3GFB}j(h#LmynK<<=W3J+E+!$C<5F*>1mQ}Rm1#=GMhXZNhGCMb1j};hwCY%H zo^x|`woR0Y!*;*K&dn8AtVbkC3cbEWk=-P=PmK_^>o{JXx%n2UN~u!*eW#=YY#)oYY;i)*C($_MF*l$7A>8dpWcC9C32tJMlUl=Pa{JGqPW~3r`Oh&a*X9@mX8thf?V#HD$A6PaG}IJHybL-)V=^^f zAZXP|l7uvkaioD$GP=15Md-JPL!Xg?#F8myq1?4y@Uwkc2Tjmvc8$%NR7(abYIk*M zO{Z1w9)pN9O^JdIdD|fG7z0}_Fr+|hNxNCgMquR%Swb#}*fw6wY*W1gUe~ZlDaFK? zgYM>2lul7;_B0i?8<>_&r&*`y>C6s7O2#H<@ckCa1{23O!(d{t6+p3=C!fy|#}Q{{ z8&pd=BWR^GT3@Ek&EXZwfJUV$Dosec zKhc>-NaT0c)nRAEw({EQbqc&f5h)D(c4O6NlO)c}xk8^f3j2iL-=9rtle2BJFm0RA zZ<7LX9O1W{-9fYlIhoL`FXQI2ij+9$kdw&;Yo41vC~Y%VErZsaovl;OYtpoP@7XqIyqP93Gli5l zP8?%$W)EQ)QJZ~(J;e+2MmrE(y*IN@m^)v`AjUSK=?ly>(HN$D^Ag3oP2=cdD^YZs zuKq%M!&PBpk`pp(_=$pd9zkz)USO_RA&J5*Sv>ZR$*^U|af~-{H?8?UTQ%vt+o%qJ z3ePiYube|0k@H|=eYwavQG!~>V0v3t36eb;Z~c5u;)ur5d8)Z9kVS)23s0?k&qnRQ zmhBM7!w7n70fFP?F$|M-vxb*1W7;-x6lUdaS|g-E(3MY;I3kH7{8k;)vdNc6u|khd zv(|qiXx10V7YAAV#P|L0du^2STq(Aqsk z%|HC;L0Z1RkQ&cfzidB(iLqjqbW9bsrq4vT&@70+3|a~K%A1@lE#9^K3~Wx)hG}i8 zKX3He@TkPzEm11tq<2aq&sNA;2tlD-rPHc!$t->FhSfVBQffM_1g$l$&`3@2v*oe-S*kL=j_OU#`&sCNQ{O0Z3hV=3NF zbIZ_g5&D}C;gHh6wCpY4_y` zbEA{e$fO9z!?0|UC_pJi&haqJtW43%mq?O`G>%v6u-zMI&~B2n>Z>$PAq2VN2<_(b zfEFzfLL#I@N{KYBe!X#H`8NiK%#Z_1RwwiWXW;YmU_kD(yR#>(}u{fShp-CbP)1p;hLz?xemnOA<$Pn#*{(BH_ZHL+zoV`(>7I0t6ZZ zcjj+$Zmxl2DhkCMw(Vfs4kIIw#4+uTPqP`}`w@<*am?Y<%vE~fMA|U)K64?WE>^~9 z))rR17RHiLS?u09ie*{dW7PXjH3&(P#H2||suZ?m;^kJ#5Ch+*-t;k~#54^|LtvN& z2#I57EZb=K#BoHY6Eiwmq)>1v6kPlure1F`U-u~$S9FgkPRN@HDh1nw<)(k(kyl&6 zyQ!0KGYli?D7bjdY7jzzX-kq=VOl@@D0(AYY%=gds_ET> zh?XAZy)#!4skerlqeS4x64SC7AJ0=Mt*`qHqXa=pb4|1*gg{6m%h(H<*_=wFAC(Fr zk<#c-HR(wT0IruO3jA&ZjPBQy3n4P{Rtl9St4LKECVnT=V56{G$)I(=G;1xP*^ZYH zcVp|#5|-uCsx6Q!RJxOfN+h+%Nzec3%6=OKbehQr+S-P<>z7HA7@ejp&7Vg3Z5qmA zsn$YBi*nJXSnzOMmvY&nT+TW(JAOd36;kioCfKIJzQm`Lwb+cP3*{>9#_}q6ydah& z+GgkUD28bgg~7_xg)}fs**!k1k8u*mG+RDPH6KGLTw9Y0h{CLrO=&@@GI;_Gj;(Pm z@N77JZka1~jdxqjEj)LG$%zVKm_6mFZU7*S6@T-hcY%p2TgAIse;$Uxgx6Xx++i3- z?7d}Jjzoy8_1k=tQvX{8$IYYCbj$PJwnEOmm`b2 zk%C#Km8=}kH%rbzEb${rKJT)9%){;abEl~yPEzL1H`q0kWziQFo8*TWV`;6?X~G5p z^Kgi)wrQimxtW>1i8Rg3X45c{U41xB6T-05zgYctgGzOZ#_~LlySnYTr!jAoRO`)y z6hiiYrYd{Qc0F{OQmTxj+Ak8%{lUuSTchX!4cguQQv~fMOA9O29YTO@MA&39V7qBi zubZUWW~7{zS-PG_u~?v3EM&FzzE86ive=9O)$gOowvCm4-Pfhi{ohliNK#4ONigJE zXSmfwoiB}Kwb%p1?MD)%!_4+kq+w96HCR|`AgS$X`ve0YRe^;@Z>P?A^;Z zo1b}8#H=;=U1A=scuY*?`?_Hm2Gr^uYV{ByvPy>@TJ4ar!ex3S)Whd&3|_=(nvkXm zFJ-ZhXYq0+Agi>A0>AIky?$K=`C^46jDG|yD-#wZ*>q$$NxwSO}Y!`1#8mW;7v4EXphlXlx9 zO0urMV!^@7x#aSBa``-ylig!9;8WBe_KyCe=br z({C|9uNfb&U<|aWCvl7^SHEAS$>kyFi;61#8^9om_w;!+q%z^{z*bA@wt~%!rZ$6T zYg+9N#bN=&nP4-;Fl|1Ev;7c<+m}YpsS@~+BvvM4qaM@6e7~i()9J9Z+#w7jTr0&g zB*kKm(a~(bdgSm{VKbf8c5?_J`uPsq@yHiPx`Sbp?)GI-a&>YBbmr;YZqzo^!2!Hn zk!EcHX&5+O9@i^m!;sHCh;BTwswrgMeG^uzixq!@M#ddH_PTevCB zb{hl~^Da>w)Akjewok!H*73w;(xCr>h|pWWM$uzW=2#nHYt^0n{X-z=9|k!OTc>L& zmg|1@h#L(_KnmF}1&V7=;LiNbZ1Va=G%3VsM$FQ%s8(|nikbbW)|zIc$-=UaP%)mZ z5SE}FS?ri9lFMgu!Q6a$0<3GqWIG;~@(( zmD52#ir#R&QW6GjynKmVu|lx$T{`E!1O5*#ZU@pPtrve4QMd`K@;%TY4&{#$a4%qo3?RLb{a+_4Co-E&wSbKH5h7_5{kC73#AqB#)n3^cz z*d{w?#%Q%e@|Hm%XJeQH)hs9$7E{VzN-H#QJ&(zW%v67Iu}-s@k+YDJT)vEuV#7|) zt-^6~>qvSSY1;zYjgWTB!H^nLYRaA-DivQI4f; zN;;dZ(~z1Zh_VQE7(ow~^Jzur)!)Fq@*i(V(1W+SD3~Jg4-$#7o85zyXe+4M6G9tX2-Crx04@v zABD;e(l{ngLR6Aqm=>1p5O!<8!?4qjA|czKB<^4lVhw5BShr3x(oRxI5<{yQF*T9x zv*+4)T@6?3OxtdELdxYlrBabNPN~&9l!_kXD5V~(S+t1tUqllyG@gILlIEw)c( z)3O2TwI=h6Es8mfJ>*Il7X4f-2FYnNxL$r}1x+vU=jIBODq|#ZM6w-!5wKuP!>)G-a{Ut7mtddA!ZQ)LNxv^CvsEu&3m+*;y7aNd;^unR7-EI^whfuhegqjm(RM}y5&`yAr1q=P75gwisiAa zKEGRQy>{6`N{W>+RQo95sow^@qQy#YcQzSifSirO0fbQ?T6lQXI_>JcARUa{9<&P3 zaSilpgCYE*#Qsr|`OhGo8LY88amzOl`fW<1lXRNPByofg635HasxPt`>b`;Jc@*;| zj$>h2)+*_uhqJSF+U*VkD0wOQfyAyKh0M*>7^@bu!Nh6G?D-mLjnyk~ol}hp3jm*6+ zmqn9IhQ*f2=xCAg>dJgVr4(Tp5Jd?=5Yy_U1YwM6 zXsU%FhDe4<-h)mUaO!l}n>&kZX$mpwq0A#NqmSb2o<+ z62INVadTM(&cHC`!TiNAO?oXZ6h*Hx?7vh5?etCi9%n7lS+-zM4vFSqipibJ#o<7o~8{w@avx+0*{mxIzb}3Y<_-8+dTKe+JN`$>C ziUu%?*CMP@;-yC~>prgDITum58F%as%)(yMBq8iH3H(-HpY2uMM5)Q{onu&*L7b#4 zF4pn=m?TLt4W0dy*-t65T4klO;S@>>G_v0)k~NKV$6r|z%aoXgq|pk=IhkqEVA^c$ zP0+Gkgp}P*(3R`f@$&s-E@Wh##9`kmbt7Deq&Fkz%cenJ%HY@}RwPmOMVXf98)x^R zlU2wYvLXT5t8{<6(9KMz$q(1f?qZ~lw~Cx0 zD;sMsK78RfcA=WjV_Fv4C@?wUkjt-}#8OJqR1t#@z6>+w&#+#rwQQHt=mdVNP8@}_8%tEiwq<2^mW6-%lc=Qu z4-H|iCTAhB$3Bb-PF|RtWgeUv%>0!Yxji8B_)E_sgQF0g-u$xwDnK{Bjo3>M5QYlJJ9v-kf?NXP5nZV^kz}? zWr?8UP+^!`t5ir6O%f?osxfVO+2{6UB|BNoj#8l0ZnJ>S2w!zczSpe;WRsi?Rw8vW zlF!icTaHmL?9|yhOrBHgik?t;} zw;LmW1*SLM_5XX)ipDY9B#{$1dUsfUqaf?tYxgL9F6IgyEr- zrr8RxEQ6e9(`k1|mBKV+cYK$`=(g5h2tD7FRHdY;B25$;O`(wQpFf>WhozcN)UAnk z%Z&!?oKLdZc5S{5%gtaj?GG; zd!(Eu87Vt!Mr-v5Ese8-l-1p5QpX_a3po%O(;XV!jgouOaj#_*vg!%8sQvbcU90Tk zPm|2#NTsVuU1u+6QMn-yQlL^z60gi<6k_G6!gz=JZw$7xZ>2l%QqW6QrOg-Cku$=e zaP7Y%ockit+-HY=K3@2GpP+lq0!fng|F1PPLyIKsb_*6Gtv$^EgUz8SF9j(oAxXJYIUW>AcRC1CDP7o(0OgupN#Th zoUwb5-flFR-Dw)f#8Hf)8h~JVxlSjtnAu*&G)>|tVzJ>dGX6pA?H@rUb<)NW!sVyI ze+k(9T+-2bh|Uu>9?PB)+`XjEUfjyHxZb|Z)i1yLOY4(v5@)2FDw0Hzq>3a-iDN~a zD3UZqkPVH4AgNK%A*9G z7HUX^$DnInue`8F%5JVe6oqu!jXpVU6iL738gvq68$b9cuTo7MW)np$*XVju4DK9# zD^9}@SdQE@0@rG#A*M&7{hNZ;s5E=6w+_{Pzp*8f?~?i@NFWQu1~6g2u47{WMnT+ALWabXHZ&I9?WQF4sCJ;jn#MC97QMbU1UaK{=-|M0T?< zZ3oBAp*{aJGI$ZydZBN$v}G6t5^EoJ`5;dDTBJQfyA$F2AwiJoy*<*ET@oH7 z|yPB^_CNKnsl{bBQphxLxt_FCuPV;ISR69({kn8Itg6smDX#mS8LpZ z5=bv0sZzRADMVND$lfXhh@J#O_jBE4rLjUtfoWy?X1t54H!c<%5p;5jxBDwv)L95Zi%NI%KKTEtg+=kTM^*^u_?xE9Z6D5M}QzH}$E=uYC#PlSNXf!+2 z8WDmN&(6Gd-wZC6pf!S28Azd!V(T}*t&p@~m|YUgf%XaJze7@g3K^f+@_I4|$lrif zIgDF9Owex9ZmzGrcHA7oFj!dZ;J6->lNE%JH0n*xFElB6=}?bn({gZgdEz+5usl4^ zCT$%hX*^HTII^`8%eAnlk-7bt#e+B_H)OiK$|kR@`q};eu;!57Q^(-*pfbWhs&Zv`8Xv*YF{RK{o>|Ig^=cZR;ln)+*q z;(NQs_8vJ`(|P5etbUWUutx5|nD_*9^9}Mji=5};beT6vv(B+v-6selOc7uiF}YlE z$QmymTP5g3nZ(LMNQXk+A_!CbAjS|WhD@`cB1MReFSB8ChY*=}gyneHwoPm9JH)jo zFvAxvdS6m|FJ}1`auc_cDoNybh{E2K>^1u>J;De&K}vPRrCQC(8rOPPYy{i!KnPkb zp9GKT?IXzUV`@-;jkx|S!haDRZXwCI7QzC12f`XbSR+WQinK?O&KQO>hBOO(k8Y*X zu4JjuT6N8$^oo~v*EmWkO_Z1<%3@-oi0focQ1kOkbUHpocVmJULXs<%2|BHHqqK6x z%Bo52!_YgwE;~VMmCf2qVvXfU3`>xNYL&J;NXnLLysPSf{}LC*P|uBgk$j;{^Vn}f zXE>1kY0eBQ-hdV!?zB($CZb#cDrhPM-=d@EMvR)ke0Nm6`2q|*tAVnq<82oy$F zDgcO6Nu`pb;90nyhY$j-HRsPS5%>XxA!M}~f>`3m23l)8TT?2!IBqr+BK6M^Et#)UdeC#oX1D2 z4j2wXSUmRSWq$3eZC+0-ZocCRe*16i<{HnTr*-ztvwCL!17=z}(_AraCzCSzPJCU* z!0x#gN5OzgpX%Qc4>K)P|pPcmD$tW9KRxP0PvQ7&U@p|9sVZg*8HM_uog^JF<(xG-$O0&YWFlw5aKs zjBPdA?Nv~01)C)aqeOs_XJWk6?{bTyh-RyU<5)PhjcKjcShP}vJ<|4LIzcusPza6d zc~r`I3VD~*KTT49lC=I5D%z<0ZaB12!6@F0Gx{FP{2r9n>uzqV_ED+K?lei!2)qGu zN|S_6$7i`7AaqF1zPw3f+wrj79G2svlP1yfGo-B}=+4nC&d{^?!%yDJpI-e4pS+d*B5rsHMWum5Xud;UH~ zZV#~G@F@!gwm3nYvMZD zfKkV>aosFBE_W?kvYC$p(gtzu+xW9jl6EexWDQ|K?t0A1t$5X2vhuNJo5tK5Xq|0` zWg6IaHj2rz3~bx#8qu3rrq%b!?vZl68R7>Kj;V00tU=^bF)Se_4U;5^Nm_O2P8hd} zhw-X+BBdr=dWxj+d`8x4^Bb=rRW?z4^+Dmpi#vFF`*Hrm)jpnp`|mlOXO~X# zE29=)dw!g$o4>F7$``PU`!-o-Q|N$m-e`cov0=hl7pg4?B|+Xo6m7{K|m$P(FMhUTiWzQS#P4juEr=Yhj8nV z-H4BGjaA7&)6OP` zT<*q`zr;HWYoq6UX@s^;w-X2~PYb&de|4ly+q&@g-p6X%`n4O=qL248p+25PIk!RLE>r z4XJU8IcztN?Rxl&&(J#Y1kyi(&=)r?UO2n3Mh;_*ya!~FB#8)pAEgzBX)-#t9U;55 z%xOXxtayE_uPzDt{OdS5l!pAkBrTO*{Iu?%!2lZ2pa3}rdHaklNpvRwhS zJ4(dj)-jT>hE9ES+Tq4~JN#b3W{(~5%8@F+{;Bs9{+-kOvzdr?Vv=(UNF&ThQKS@X z$;n6n=KtT`dB@pNm;3)c^_)4qY~M{KAqlAvdXtWdB1#i`0mSR&V!lN5DXU@!=neX|`Gtc+) zJRd5yM|6TQx1c&ik*L@L)AbgT+q?M43LQ;=bt?y%|4^JWjvAs>1{U}78hJmS$qT%p zc`u$eoDux|of!E$L0y2-a3ZPfdMc${t-ps{Ejjo;s9_N;R)0Z!&&RQY2|-y2w92YB zgA_;(s^(rL=>IziX)zSpLGS%}ZJ8KZiWq9eo8aCphFS?Vy_Rxe7}F6c=>qfG5`;A^ z=rlH1z_Cn3-#}|U6*rkP!%aJ*DgWh`Igp!eUySGwNGSB}ll(0Ch0>_Va|Gbn&>^Mvz=Wszs)j&+rII0@h1$ zma=wY_gsZj-a=yGd#F~5=%qaJ3wS;)t&{?*BgnSy724GnAhH zFK|c8Vnq#Y-g~KRy|iv!wdHh7qk?5Sl&b=Z7iN(p8PhP>)l(o6a*2jvFz?bNo5WjQ zi={*{yRWI=sb^w#{Q$M&0-}k1_vk=A8>vi=nD?e~FrvB)k5p)D4U^5p=Mw8I^V%m%c_~AUoS=p^I|Zz|H(I8-}eJzR#Y6@!Z3=su7j+ogtREG>mrF@ z+XngJep<3B{ad=(T@-0k6vR@QjfE)3wx=+CiRG3KxsLXWOn&@io-U?Nm&Waos=g+35kKqUcC@rNK)B=GScA8KKTdXXVl8rFEydg*#fnc`OA<+vDHcl%43$Zac9t6{3AD8& zh(@Ehu7e*t6sbkT?fXgnLHIV-?tr9Yi4~NKlk<{$kG(DHR%M@pZeUcagf)$2OIw2~ zR$R*c4^rCw2$HpB&l{SI$SRcNL4+HRz_tu5L&rBNl=IWK=@dl?cMgW2h8|S&g(Go9 zQKDQJMww)1GE@F|Vk4hdnw%$MN{?$nM3Us%P1!dp+`7?Y#fk(AeS=L8ZsALhiyZeM z7t!&Vzb?(XTf6z{h6tZu4)^J;JerN({jja z_Oo?{N9u3<DF#p?PVQubuzO2G+At@k2Qo(Ym7pcma&3Ho0giF6Zg>2du0 zowa3B=49m9a?D*nu3J}aegl?Kp=x?)T8KzQ!?rB?2g@`hd@Kj@6@djEX~N+!wq?=P zog*6d$Y$3g$r@Jom35?#?_%w`9JS*D;;Ge`Reg`{6*J+*_T0#(!?=Dh&Yj{$oWi5n z`A5LF_bP=!Xc1CkJ>iBU@P#m@p_3o%sX3;^XK7k3N)oO!_v0@Yh7m=PWTpk*_o>d1 z8mT+HIZXV`Rk}DE_LRTYqH!w4+^F&e1kd4_2X=GG&vgb(NH@oL%iEXmsb#@65gQu$ z{<|$M`pqU5=LFi8HgMT{8d!i&IX^_};mi1O|7Je+?X6twN~~Gm%=eEn5gmnOrkTP> z|J3g(J4lX8XOE8O`^cdX5yxUUXX1Juj$WWrn);lS$TZbD7KS4&Xba9oaB@@!?!qtr zZAPVvJAC`gQ|dhtdeI@0cvWimuZT-p3Zxp^5ZoauTR%VEKSNtVeCfw9c3)H16iG=R zN~q&~Fyau!o&x3Q(|6w8dX&>41=!j9LZ4&DoIv|##8v!?HFA@ zz;~ziHjq+BqhyXk(&l4U%NW(lE7s^p356+!3bbmAD3_k0I`ROa@>XPT@61Mhxd|!0 zKWg?cq;P8>wW{hk_SCkOiF6ai-1K_ra3nq_E$ws=C7EbEO({S3^6S0rxVJaknyh7? zO!|}0gRF#ti1bC?m;n$3v}l6-aBtmWSyoAAn<*DZFb$oMT7Q#tJ%M~xVadWqL`kB% zcLdR`OqqumgBDF-R_n{g)sRLg54>3}($)w}N6ERAqG9x1; zWXZ?z6*^kefu6Xc)6-WV6%7hdVu=ivWnh~I;b;ue>BriAMV+pCBE;wlq~u|Q8x9YO z0Q54pHNE-i-auB=V6rb9!LWNM4&8}ZdIrtjJ0k=^jw2@zLX59Ri7%t7>$p~BkCA^Y znVr#zBoa@7527sB8v47ggXcIkHfml4qE%)}9&{Q8m3Nf!ajVK09cm{_{q#_RT7!mkh zO}t+zj1Y}C5nlLVjIJNzoAnV7fLGa!SJ{j+_y@$qp+p;BgD<2otCb*K;QMUyHn4*A zz{C<>e+r3-l0+yR4eX6X4|C{#26q3IsM$|+%ARL~fD>LzIC}_M_MqBQ*KyFRCb@!5 zL=_1uGe^Ka#?Xmjy5bp5J=)*T7CJshP9f6`m5JiP`;#x#e zMv^`Au4_aOqh5T45fbS} zigSphCqj}HLg5Iq5~}M}AqWDV=kBpt&|DEb9gL3;QIavLWkgvHh;N1}Jed9b!FZ46 zN;yBHWN~bw)H14AM)1TViV|VbV^@#MJ_{R2r4kg&CYEDNe;r+iK*uvZH~OAOwNk{; z%fwQLAcb47x_|b{5VRT=aUFlJTZvxMQg}rSOJBuHLns`@7`zYPt^Xkia!|8u?EXdF za;^QHR4c{WgpMufn681QMoA?jG&KgF8yw70spur9>5w)y3+_+obF7yO_|XKheLsyc z^Z;)DZ+QC5Y6-8n0kgPa%JK;w*MTKe?Vo}#$T)5e#oN2ctg0mO;;Tqxk0YsO>8*CM zZR9Qr_Hb=igX;4P4J{%y(n?1|1JP)d=B5nkq{(ouOxc*)kjSyEDemUA?>CFYZp!hM zi!~L;#W~q(!j|ooc0o@7I%>qK^0Un2Z;r1QA7v=y`#fXXLW8 z0cwg4Nmh{LnG38HHC)&CWjcgH5zK0ZWTqKWEKl2FbTT|Iko9S@&G2xMrVD=xz}7FH zO-7#jv|$-l)Nr^)@H4^pJxaMjBJnmNOFlV?p#7lf5kjD87Nzk<_M#XxyPpf>kcd@v zk>t6hImYB$vpIWAtYG_kUvf^{eHAYcLRyqc&m&Wot1WNB8vZN3J)RqsGe?2if;rJ= zPxP=Y0ZoPG#w5P)(bu2HHg)3Rsn=VQmC*u(sXvrzrHE!LWY zh-PIWjhPr)M5DDO#K=gV3nNvv001BWNklOHQIa6lHf0|WM98y6$&q*pNs?=-n3)g? zMJVP5NoJa-Od8GxP4y_0^xE+?WMUMHC1Rn;H(HZeBr_{Pk7>LC^im#Ii;fetS#|L} z5ETIta6O-~8?^5ReN)HajlLEqG_v=pCv{VIYwbs8BG-w_UyYpqIq}71GQQP|U!B^- zM~<(fyyZW~7l>iB_IFY$1UgdN1n&Y_i^yQGSh=!)W-dZ#<WUwBUtWXh2RsOdw=W{zdR*u{=&C%wJD#NUI} z(->^A!cgcLie483eT!+==F`%gCX-1aNg_kTWfGc$C)`p`UPaI_ zeM)2^e9xnlA0jcDlNJOKRg0jgVa#fU${aQ4f+*tcA+<0UjHMPtQG)D305a!3Jn5ic zgj@Bj*tF+Wro*a*0Ho6iN@WwBt2KhXJA%xewE1oF}S3qfEu1h zW%FmJyeGx>!ydk~E@}<8o`GrF4CgH@S0Ek@kxZ#Hgk-{_UV+28GJ- zOgot}6HKFmX;gxWviPAyn@+$gY{JPuh&N4o<3%I9965O)TH_IDuE+EGlRVY`YfSgW z%e*YH$YA(M3~Ly>doAs)DU!(qvLw;dS0E8_M?1;+wHuZw$w-on8j2vxDzc&m1uLV( zT_f;Or;&-6ZNhO3zVBh^Wm1i8n0g>vG%B;F2qr@i#TO<0n{j)R1Pu#=7wMUG;jaw* z(VM^?YC9U5YkxL3#o4vnCOt{jVOA@|k{N8da~7G2_)Smk>!2kZbPN zFV58(_U!h&H{|^){&5f>C|#WdIk`V(&#xyeNT6hop-?E%+L}RC)taFuK-DzSLLn4M zz?)@EDWNds!roU0j&(%SOL;obtauTar zAwM#N>)7n@p56QH&47}!i%!SF?pn{h_7u@rlzHtUUEKxZ;rd5-Z~A{hL484q@mr>L(<;)t|+TVaNb%KFEuDO+j9zxJToXYyK(0c> zM-+ld6fZDxoOZuK>GDg@U5>%F44yLXWpm+SR52VVLl6-V5Xb%&CchRC5m{_Suu4;X z^EP;QPP3<%2d0##PuqakvzC3DJBY<&%8xe2;b%yG}*xq2J3y}Xf2a`0rKsG(WST*qMOC6ejpX;m%36O2hH9K|$( zC$oDF4~!~wOJsPYKtn^CmZmtnx~HZ(Y_mG!|MwP$Zb_+}6{WLYb#He;&3HssM zb5G&f-eJCY%R@Mpg(@q2;jT279v9rHUR7`WV^A3G53GrNA2p;Q+4TclR5HlXrEK4| z4Nue|Y#>bRJ#0l$qrs2XG@WT3p&=--bzfrP!DJjP9v}SS?H##xh>Kp<N8^a1h-Fr5a>yA)iH&iM^Nw82f8KZ>L)$iEmWzD;sKxBtnjKw3 zKoBJaF?dWe41?j}A#B@0RTR?c6roTsq6PyGj`Doy@cnErl7(ahF+eTpf~ppv!XT2i7OUx+om0yJ6~X*B}*xn zOSN)b2p%<_e|{VN1B3VzE}S4hb8{1^WRk7VPw(2hy|a_+JNHFhGW7>r9_VG{kv>9; zL=tWDNHn*PTDRvI+4(%KRUc_ds*2}0b$8ZqGEK65Ap={Ut~<6^V+-j8OJ@4&|Frnw z$#G8qo=(%Um(m%0X3UmO8jCt4S-~sUPjJYIb(E~BQAQ1}LPQCoAj5Ep#_Hb=X)!`t zP%JR9C&SCpC2c0W7_$C*lX_9C5|ek1RTT7JN}~a^PfzZ zSW{HASQ0}ov3$P}|MPu`1J?)R%J)5N(?AVtvucvZ)O*!(Vb)UkN-0M?)kwK8RI7TG zMIS}985t>(&8BE+O0cVYWJ;>Tu`Sea1lu&Rt?^@V9h*ozH9J9H_t`$F{Osv9(@s;Sgas8<42wd^qc5eK2BYnLpEiEn| zIA7xbecY+DU5dn#2!e=FEl-&+87skkF(m!l8=`#YdkJ>zl!?bZ)~&Vp&VP;2(&F;( z7iC$x#O9(4$FIjkvVN)P-xcHhqu;{sJAYPNcEx88;rCbV$A`alKPSEQ`P%Ydertbz z`R#SQ|1*zp`UTHS*_J8gFe*N->k*5FShl2PkNfvL58JZ1;deflToU5m`v-Asm$2<3 z;310wvgFU*JYW(^xj|A5trSNFW+iDuFB6W$_gKZZH|W|WbLf$+6!SWT;XXoIlyD@9 zF!l@~2xzesp6k>I^^%JVESNtj&ui$!l36U%m{O4AdIA+wM3hua+eH>!9MQmcg((p* z1Y}w+3=>N=1jQwzk#zL$oIZ95LeOl7|$8lNaW#U}-=yQ~Z`dQJE z;XhA42t}6Y&Xw?dpH=ORENjm2%|AcNEgL&IU|tgkEo|Y~W%Iaa>ux@H^cupd%n$E* zilK6q#(nph_B)U45V`;IFik65^brZ)55C`B-_$tlT$6?+vq!Fy3cDVcnKyd3-g>7( zw9%(L@Xz1bZ*uhf$6F%&_3kk7xX1QR6-5=<_JYK_-=pw@&lJ$czLKZ{0){i5!usSz z`|!+DQNH&5Z7g0sLgy1J_}r%(=-dvUxwQTfy;{!C+HtK`tT2sv>vVW}qsm7=p5ez= z3~}^P2Kl_mU+)Ry&Af{`I1b3KKm&yK#YOJAen}lc-*v-2v@M$b#%)L==z0tBxQ64n zSeA`|kIz`Mr(iPA$48cA)R00b93~P0NrFWSn(;gr*Y(i#Du&@us@gcNiz51U(e_-R zMH5uZ1)_-zmC^{V$hz{6a>ycat(q2KfL!Ts+P?=4_U!`4`0c$ zmMj}~^m6a>yNS276HcV2eqkT(zdX#kvn-ywL*Wfy(K+)66^{8xmDhc~%7Z@&%_Kgk zVdW_nn{FO26yEelg;j5;f2@4)iV#=4KF)WKNN~;BF}gO4v%%9hs$6$Ll$$>h;b(7) zam`y}?0T%8Ep|OBbJd&TTy{)?+rOaUPT2gTKM!%`8{&Nbm;`_Lc!X*`V9`Ri$YsYQ z=-U+hiYmhbmmim4=Z5K-sIO1r&wtTavX8^?u*7x08sHB%Rr%;eMZWxHfiHghklMO} zoWS$F+N8^-r=r~ay9U1ZldY^jq(n64a_~VO*InoH(`#h9x}xNDnN|C@^XW?^PJDd} zM;z12M=s7_S>rddr#Gsce%2yZtXayD$24=-T{5B+{9C<$JKw!5!AY-g;ou|M__qtQ z*mm&Qr=C{Xcd5-uCsqlEeOg*v&N;h6TdT|Uzl-vRnisx3ns@Ax#sKZdH2C*an71^`0m9=VCccQ{NnqM z$F?NibI6&z=a4h$+8T_t)ra-b+ZAW9I|xKJZD=N$HRxD8eq(eUkuRNl9OtY#hcj2a zozJ}eBsL9hr>k!W$8lM>P~wtL*c@@B#Qys$y#HM2?ahcp!FB~YJ7pFx z>);#TN^;WcTR8maR<8I_94(r_a~&}S~>90HlE$AQmF`heyE9 zz9&5GxO~@p8!#<_Wh56HfBwM3+IaM_U@q+W zZ3?HH+RQ%7JJ@GgE9ai4qJ+Yjw#Z0XCZ0&JctI1tx;DZor+A!uu1hAXvi^WDeSH~j zyS14k4sT=qL2X=neGJzN#@sD`ig5ICtu!>nSiQD^tFLJQK$d)d`x}*Gj&XR~+u#kS zWO?1|Te$naN&Tf=2iLJtCzvxhc98!TFKH=oNlSr?TZ+7`!C>DB&02il=b4RxC4A@h zZInx;3Axz!lUex&n{YDte$lLt z9P(Lsh*KlDnXv3cn-}g?a7=;nfXK*Bkp+j;M}3)v9`E>hng6)2$N_J&_`@X;Y-605 zc5aYadxpikepTkgPgS|;V-d^=E)AP+S9se`%bfT75<@RYJalz17@xaC;n82JoPJq_ z58PHlQsGaZ4WfW#yT>sfF}V3t5$vkKZJ&#<;&m1a4i1iOa`b%TA0m9V@Kghs<#CN_Ikl^r$$Qfrh@&5Ogc;<=c`RbSYIPZg5`ufJt z|09ouxaIf#JaBg}ojYWHcT@0P*B@ZAd9%V-zLw&VM?;wA__;gdEfr3EgU)|^sK^tK z^zh&RH9k@Fz=L6KySbl-?+^6O?>V=D<|db?9_{9qKlF3eweZmG^8xtPx7P9OBTang z=0Eb&hkuJ+R`}UB4glaYKfV)1b@}PTzvZV7|Cagt22qhH`W$oGcJ8_%czV0@`XwBH zX8qhu*)FjE3D0ray+7uP4Oi08R^jqb9!62wL3MPJ{h6o3+;qbr_ubV?ZbalqSHy^@ z9ud_e9(GAb9nujK!8P$cpT7Qpv>n&u+G}lYxw*vSj~V>p7Xoj4TbRo(lNlHgaGel; zy0wv_pcbI24Ramvs;&We2)3rlQ4euu`DS0%8jIZk`C!wol%r>g$&#|VcUY|`B9)?MqZn|AZfua9v42OH|H z^%#EklOaMOcw$30Pdw7YvVDVe!e8$Wvu<^nzFvb5T~Oqrk7lNP7T}9tPI1zSRkm&3 z&8DZjdB@xH@uUA4qI2smuKv*gU;e7brY*rSsFKfp_bHrnPMOCZgDbBTIQRT4 zLnHOy&#YEZ!;xB#5g4`ofi-vt% ze(|m-g&vWkFA5&Rrkfb->6Tf%Xlzm?ST^Pf=bD2wW=iCXK_n>1F&uAvhC4T+(9mR& zHiLg=bu%Gx2tywtn>88ew-LoaZ~Pw@iKNpJ=Cvhw=esN1aAUB|n|>cW5m^?jSU@8*R7-1>`Uyyp{-k#4FI(j4CL zu_w9jk9(Ho9e>6)?z&+KmMQVj9rHN))J`1V!Ez1Cb^%HDc+Kh05{}xaVTZSW^hq{7 z+)P>SA(s!X*M%4QIDU{)_`tcP+BusHN%9c{zed_3KL7r~JR!9}C_K#i0}a;gU!kRC z7{@7c+M8@PZj@O#FO6;mW9owQg8XsEyclmi+u+x~86V82zokM`Qx)IyP(xvExG}<~ z{xeT1>Cx8e^3jV5Tz7p0*ReVCbdwu@AFGX}>wg#J^f&9%Uh6{-HaYqzgFoLn_mb{a zD{am?qk?VZIq!Ulu3a*P;?&=&qWJ9CDbw8}V|yaYRthv_W3;qnkrjny1I7Ntz#IY`IdNse4#+GSi*5;cXB9|%8calBvZk`Jh{u^+L0)yPFP1D8N?_R zn7=3}q0CjP3|E4EEoeyMdoHEE?$O394)e1?^p(?t$nER{mk|$#@PXr(&*z@!ceAT| z2U;>+R~Qxf|eZFAe_G*-URLQDBnh6SQopM1Bt#~d`k%2RBfyk4cyBl59~{BInUmz@Yt_HREB~w`pS@qo*TbVkxc!0i)MYwgX4oO(LA1KNwoS@27}L*2SpOC zcHQSB6-omlp?GlIYu{pV{l7;!@sm~L>D7$@w6!^O?vQ!i$vQvypE%$D?l1@f!y^h> zV=sdvaZ-sOCFM&IJa0ULPG@X}2BzxO!%`o8y~_~9JkP&S#&H&4c_Y|%f>=Dpy!kGD z{Q&{&+AZ<;lPZTE*;*S%dR1igN`o;cmrQ1YS|{w&+c$m=4?f7`;Ddsj^TuaX-u=D? zF8e`(i$5~6N~O7Z{Mzo`E#ug5(YMi|;qk(V+&i zFVCZ?Y5bhc1+6V^Eq9uXxy);`z||=g1Psd~pO2xcAv#(`LLnbjqn6glW_+G}YCLr? zcD@X~gs3!7EQ-wQ7(a*e=DGCt2J~{^{y97^#v_l0>FBU|;z^ZXUK32>O}y4)&~=eD ztLLsbX=w@e>pC`C$VXLtDiwiby)ign`a+H`d^ydrC$`Ys1fTk}$UEKvj_uGlSirFi zQV|zbQfO)#|1R;UM?CJ)nsu;Um#*D5;czRuF0${wX|`j~c$ViS@EQ+pARX_Ci_OM{#VpgnN&4$0-&&Fqh+5Av=`aBZAu3ftcYg%oxal_`R z)jGr5pQAYu;miZ}#RoR*=x2AXL|>uI;fq^&WJfQL?C1nwZAT+VFKK76ROR`BJo~j~ zdHw3e^cKqe=F#W4==k+~=$LhU@}~P4-tjz5OIJ?mfYrR*<>9MCtUA@^hzm?^{zMS@ zcO2kw(7P;lJ}k5PO?w_Ri;l3l?F$;QMvum&E`86A|9}eJB7gph#yMA4XxcXz09U=K zzJ|5XU4Q4#cZ)1New=uV{UWWagU^=w1fq?>^@=rm6nn=%TNxH`t>DH3fuiKjuWPJ6 z&Eml;!Yn({=5x!ZZ>WCSn{>YRjU?ax<_MQvp5V-Lnh1qe&Og_qvOq`EEM#evAjJr_ zGhSVK*wF>P^VRum*&?!Z$@m1#vzz0*usy_aM?FSNE+Y!>( z&lhNKb2;*GgKMrHn#N3Y(ywk0SiQ>PwI^43_SqmRoJsyZaX7TKImBW<58m5bTYsX& zE}k;^)Kzz}Xhn|65N9aD8N+d>zrc?^e=wi<@l?s)y*IAl>H8M&x!+t*GOLs8kMe;- z&cpYiEcf8~E9vZ%XkTXVLT(3t-eJ+w+&Il%<_=|af-s_bn5ILiSVfZKm?rcNMv!F- z34@(G)3h|#%V=wGb0p##yLL-7HU{hL+9lE2I;vY1;j~lB{Na`~Elm|pIIc<}5saUS z*LqJFyB4!)tgDqG2vg^n99JNc5V-7egG^fCo_iEt|9V(|KoKQerXd}{755x~DUwe% z9vBn!_2n^5jd#8)%;!Gm^V-+u(RH2AUYZI72ChT3QexNc6!CN;QmH_1U!HB-!o1}z zG99fcdiwIDqE1a!V~tiBh9mJn9toojSUjgrD?A2SmT78gBr;8^0-&$AhrZr!vJH(K zfAT3De$+7>dc@Hjc<^CU){VyE9D2mj9C7rq9DBlRi6@eD?dW8SJFc^vpNaE{*B;Cl zPd$Qfyya+`6A}LK`4_dkQ{`F!+*1Nr9ZNAr!-kLHrs9*pPvTzUV~sItTd zU$Yk1ZiW9L000gcNklvzVvUKTTf+0gk%R;I_|d zG%RsB^M@7A{9%O^ue15nXEhEx&zw`^C{czpe^}v-Uz<7`ZB_)7Fk}`4gRAoanOs-> zMsr;v8*ftaJ=lDkLVlOXqQl1{)JK07LeB{pMS;Iv6=wNK0eP=@oy`-!Q5o4GVjBYY z{I|y9qZ~ruiH9FabN+|can|WQ zEZ;Yf)A@K@d1Z`|K7p;BLwx0{B4?lJQndt5J5}eQ4PkzFV+6+$uq=UxH$>Rotx(lx zS3UgYE{&i4BF64+8OsuQ>~WP_ZjG@1fZ*oZ(BRU!V|JOwisd#-m)Lyv^J&Uu5zm8N z&!>3qiGU1W|E}k_^0S99*b}4|hWjHtdRGSkiHwQkhz#{kpL#g?oUMH6+S@ts_^D;& zdMQMzsX{UvjGe#y>`(wIc9DL63!Vr6^(`MyZ^Rj%$FIM;mN&m?ZiPJ-CeL^ev%$M_ zMm@J8`wR?~D3!{HBK+|3G(}zHiH#wy{Y{iNziE1fh3C1PafZn^zLlj=6zT1g_|9cX z&OCj5{nOuE;fCKy+;CHpcf3;~o@yYTYTzC3471@8jhk<4!nT8J{m{c9cI}>ejj|aR z+lIdWJ(X1YsNr$Gs#+q38{*-I8W6~!C<@W2jv)9rcA0d5eLrB=YFPe`DX}`!RpPA{rW-W?WZQRhpUuEoZq@V(XS?*}iQn2+>-yGZs== z)6s|z?9P?AW#e}4*}9u(Lo-@B%jRvH`RpGbp6D82bMG$VE$vf|FFoJmgils^>=z+Q1Az`Y+Te5C z$E&mIpeJK2I-YL%$~RhE^VS%Vj7Q^=Aj+PIMMpU7enR4||4I;V@;U8WI^o3lzL%Y3 z^Q-s7s1^j49&2;xxk2>0{3M%VpU7|jEsCWJ%s<7pXGd4$(IU2&IA_gJl}1 zp)gx*5Q{}wy;|VN!y5pP3ok5k)R8kAB3$~(AwK)XW)3}~4N3Mn z^YjYmpF6IBUc1I3nQ+;;L*|&HMkwWjFR!U^-L)#8|8gTA{%|{z6y$Ng@ztr7ewya< z(GQn7>ewu{4L9G^KV=;Vs6>_(3|qqUAQq3XV1ATuJp>>5sE@8gLxalq{(FSB<{*Nis6mnFzV9lrFX9A}-Cq_I(;rA6b!69cj@=z&!CxMQo_{a3j7;(4^RI9z?z zFr|t|gPkTGkK?*Nxm>BvsA0@rOBm|i8B~n=K94`~B!)5m<6E?70d1}0xgokUtsrG4oO0@0C>9IcclY?+TM(eNrG+0C8p!YNoc>&hQhg<1F&|VC zn)Md-qAUlctP^tI@s@THt@G&L{1ncF;*?N4Nz<~`vmWn10#Dzl^1{6`Z~pJuwV*E* zFQx%iNQ)xNDuS^ItNW_jazV)uTk#E^==uxpXf9d}1?jB@!<=?o0P7EX4Zr`rPk8>r zNJcY@n-`)*G`f3+k(Vc9MaQ<8PBXTk>$J)f(u$#d#S zZ4BxC?C9IgVEF0U`*SI{nSAWieWtTh=D3qv*tw%bIukhH^!DX&?Wr2x$(V})Z6ecD z*D6#H1j3Q{v^_7TLO_efsg`G6*LDRerbH?gCza5UWEt0W85t>3ELDky+-Y^+AuWpM zx_fkkmn0ck4Pj1bOJKVKWkVvHiIPqS*R!hYeCN9kci*k>t7`@cN8>?TT+76A1WY%? z{EjT5Br!CUr&6g*abl^Ba6u4QvwAhfVlY5tMIo7}&-aDHVb-l(Q|qe{iA2yejd*+s z^XGMt%jdByyN)EwJL_9=pq>3E! zrzPj$^RH|f_-uH&%e^O(^Pb@2p<7i-R*r^9Ged&Ku&?3?*0jg=QYs_`0Sd)3p6`>* zrf6%;($_aa#nfkX!hyj1aHa-BW6+Cvv{;hrs6neZ2TQ7P_((JO8u~s|ObJ0&X>W_y z6lTRjiN3)yk&sI&GV`&U)e5mx!yXAbh@k5UUXgs#QHN5oOsQ)B>jpL^hhqp=FQ{1o&^C8*neH^?ly+M7fDYh=h<9_Cq6F!D@NIS z8%4)c4MACP?hfpsTWZV2_-e%V_pzzxfx7j_QXLTFrzc`f>uV_G2I=;%AN3*1vQXFHEwt&P!<2aTt?x129*|xKXp2*+k zwC%BodZzC&Q^Z|1CBm9Ub5k(qGdP$-ujo@8$R}bhsgALnuNF;U=%rbuxf3zb(PS*0 zk%((#Gl|ij;ts|58b_7uuj?2oPbOzzO8Z7Z(HR*nTuQ{l zn9j^Y({r5}(;u%C{$8EzCZ;@MO0xEE3_dPJp@)G=FHt2yG!iD{rl;G~6wIdJ7<+%Z zzhfa6v#QhE7fjqWHl~Tiqm+!9HQ1HnNL|sz^y>unPogC66?wX@gXcrZkZ^pBjK94d)O9f!5|YRY#**DH4f~ zXAoi`mvTubmn$Ml5*=-6Dwc}v3a@+wy(j!LN6r&TU@T($SBRuvEIDhjBxbcty0M+| zri<|1@d#I5a1nhr441oS*+PJLIE$)=D4F#$^>Sq~D;9U)`#vvp_7hcRpES}U^>ZXI zHG)>uFiI$b<4ny{7Nh}oR-Yv#YP5tG;X4Alkf*o0orIF1DYO935pbm{JIb4w7hQ(x zO|@+k1gJ2=&dReaiLFENVs-B!d6b-ChRkj%P7zU%SQ1}{;*QJqL|-K$B#3GeEOfT^ zZX=ylk=@7)+v=g>6c7+esf{#*+6eh^JR8K2N68&uXEG*6)w(4jDH^RUX#_zeH&P&9 zDA%bECL$D$;^WWS07(r;h{TfQhk9pRXEJO*OiA}>X^Ih#2j{PQg8wb#Jofq@H8J(i0^6+Oxh{@vAx4+s79X#@=T)8~kvMEl1f9?_4CzyK zz`k4}ujfd|vP7dHL@$ari`lE^IY) zi3jd`j<;X1KM^@jQ)mIV{&owd>G0-vtU?eZLPC^lu6&4mzW(@|8dIEo-f9FyLPC@u z|KLGNjo{&X^uZ>H7$!4(yed9aO;nE zgLh|*q$8?F)vD6n*mA4=~gGJ)~ac1TK(f8^H&o0qaJ1S|y!yBa3y5)tMrsBj& cF6>ea3V@;|>0q(VGh978nDCnq>C9%DPk#q*=F zu<2v{vKY_M*#Ra+je56GQC1n%&V{JH7+WXYh3Ob6Mw<&;$TifHC#} diff --git a/source/gui/qml/places/resources/marker.png b/source/gui/qml/places/resources/marker.png deleted file mode 100644 index 2116dfdf51bfb8ac9556af035d598cf2c68c44e3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 752 zcmVP001Be1^@s6=bY090008FNklP9F+g_dGL z7b4wOL~YbX6}NhC`Y^Yem;_BVH^=jjGv%gj-gDq^?<8~n@6OCQGh-NK7!h@__p?7@ zAHg%1%k{H&7`2$=I6)SB$ey9%mf^nW7pw@t0liA$uW3=@<{h$6c2acLUNScZ#1n1& zj{lW0thX!xPr(xr5KoZZd4{Yl+b9~?SDiKsYw4jl=ahsz49ascH$lOp{)gvA{a+7Rbz6(!?wYhMaEN_*&FvlTY+Qe#GeLd5Y`1f1;(W)TxhmI&f zGMmlT7dqEPnL5c-$rEwKC^iKt`y;L(O{LEFOX&6M`3tgeo|g$ok3Ur@d#&7y#A^h6 z?>^6`UFq7fPoGtQPnFzO*2?UlncYoA0W+aJ?(31K(tFo2L@iE#B&)%{`ZRITEx!AZ zU)hx!$Bv5w?bcmR&+YjDzHG#=UYFZb?pf8h$W$s-$07?*nr~~*-vC?M)D-<;udDUC zx(`a(n9X1Re>5i2b#_ic_8U43M<~(&X=?Gdk$OC$)?v`lX*}=K5dL}Zz8b-2L$~o) id-3sdrSb5U8~YFSpzHYmbwF4E0000V@;|>0q@p}s978nDCnp?WIL391jps+> z#>S7;kN+Rz{2}_5UF)a6!^}da5W(CjlH3yJ360MKr$|~K*tuf?R diff --git a/source/gui/qml/places/resources/scale.png b/source/gui/qml/places/resources/scale.png deleted file mode 100644 index c4f08122ada97f0848409a7b4de914274d04d55e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 98 zcmeAS@N?(olHy`uVBq!ia0vp^ra;Wb!3HFgIj$80DNRoo#}JF&PQ<|Z&(Z(QQpe}ECj@=zX;NfjIC%2Ts>e~;XMma*JYD@<);T3K0RYVMA4vcJ diff --git a/source/gui/qml/places/resources/scale_end.png b/source/gui/qml/places/resources/scale_end.png deleted file mode 100644 index 94510b1258e33726e65d4d5f539b8dc1dea5c905..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 93 zcmeAS@N?(olHy`uVBq!ia0vp^OhC-W0V2~}Z=?b#6;Bt(5RU7~DID*U6A}^<1tu^B pAL2^zV(}^D?rhdzjZ-+uz+kqK@vYpot*Suv44$rjF6*2UngECF7V7{2 diff --git a/source/gui/qml/places/resources/search.png b/source/gui/qml/places/resources/search.png deleted file mode 100644 index ce8c27aa6e387f5ac9cec3fe14c33dd99caca5d1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 259 zcmeAS@N?(olHy`uVBq!ia0vp^Vn8gy!2%?eOIddVsZ*XVjv*T7=T3^|J#4_^%Bv{A zwD6K*07t6;M{59EBaj56#s{@Jt8X2dy6t9sVc)txJCxD|EG|s5-fY8qne|V~v6~sL zfm{@G=xuWP8-|V zmG|wJW;?gYF71;}bqfqzJ;VA+V4&8%>nGmE{Zk4En3CIa_hnDBN7jN#9LGLb1f?%N z<(47GIc=`eOee+7k8ZPmt=u{-``1%&#EP)zqJjq^g28AcLO?%AlpqE~#2|^N zs~}!@=UUeLVnr84MWeBiUpdLIP)o*%drn_f*9Qd*BsMD|N)%B|0v}*PK zmCUQ5zE20x4-5f4t5Nvb;0AaCYC*4RQotneFYp)_>;i47LHHULRtfL(&n7Ua8WhkS zJk*5uH7i(A4GNeJvc~Q!&VsgSSHNCFXk8Jn!H6^q-wQkzc3-&yxxx2o4t}$MWB9%q z3$9a|Orru?gQJ4Lj$sjRz}Pe@;3M$V5SC2-f8o7NX;i=hVYj7BK->bI(=++UBE8;8hPVAsuriFK>>ro ze-`ssID%X3CJSom3iy_HR~O6|a2Z`uk6Lt}0E=%AE($v@D4D*#zz({#-D@E9TZ1~>dlHD*eoQ!bpzgW zOHfX!E>ozi&RS%lKsrw9*vtff7dWl?F~keMO#bf+X1^2kwxz@2oJ#TmA5y6T`vs2L zbR1s-+JzlnY%%hP?=4E`w;gaYoa(X zkxPu>GrpTZT(F%nXuSR%=oH7vu{ZeHQfzoJ20G#%m=NGR> zAgN1FzYFOvU&JBC6fjp{i0T=^aaIxv=nI|+>CbDX@In2%e1I|~rPapn26*6Hq5AW* zuB;Q{N=y@<-5rZH+iL$Hlc!zWtY3WKc=8DkIrAa=3}#jMQ=AHzB;@2msf`wS2h8AxYmM-^J$OKq z3E6ehX^8ELEw{{F%VIoXG)4!eej&TjQ~0u^8**Hys>0DpRe!c_4c!i(*WBH~zyFZC zPGK6cDr>BXLjfZ>dfTcuRn*W0g<&OLv6}-P6zD-J>LUN%5gxEwsK(4iQAA%^uKT`p zk%4b`IF>?+e!d9fW~DCXoW(E63@>m*uPO6$JA$QJ@g-#*dj6uQ70?*4>vRI#M3Fq= z?h{?-`BS)9scM9cQ7hmVq5P%vHZ`vA{c#s+trm;)P53hEhY#ReSWP@~-o{^sh_x1H zYoLj5J$S`m#iPMU_c$ItfLmchL(SWxT}uznOe13v{{1UuuXoV~ok6Cp4AL$_N&pJ zjJ<@r;krLku3w1#H#mMD`v-yH62NQha6EU%>GS)0y^!hgfB3dYXE4u&fu+Wn|4%@Z z7GT>SE|xNKKAv|B+e&Q2U~}}T|LFRS$Ff8Mf8H z$$uHaN@iS(e(l883;k@0Z{gxm_$Dr7x^S+%d!O9`zIZSXXht(^Lx2tPv#|MK7GCo= zaF+nwwE)d4G<^NO9Nc9ydPiA&_{QX$F;D$~lVe$kl}O_HKfF&IaMx_o_Cq?6J*8Wak6UBSXsMp zw5(nZWpLoCg7l-K_oBr(-u0Jv1 z4mmXKW!X8WyMfPn%NEO+HQRx|3}KM8Zs^F3$(6b+`85Y~nS{A9uzP_|UJW`%KKW0$ z7#j?^EpE+L(5RWRV{T75I;Eu$6B)r&xYwQre*c*CunXqa@y0M3EZ8BuK zn`pZ^SLEsJ-p}znjwSi!NwYmvFr$Z9S;>_gV!g^)Rn7c^ZWsFVq(Ly zO1DD6mfJahkG};x_iLHGd}+A!?j*+PJMh**({~-q!CV-a8;frgIJ+C)>$XraHe%f_ zgD)MP`mCHD8i#9IUk;2V z6~Q(pRE)*1-V7SnU;c@&mWnUPMSqV_lF(7fn~l$|OlD#wQv3hnipsCEzl2V_G91h; zg)CR`>i#owXq<+|Z8-8LX<1XyvcsX^Y$D`p>UgK(E(yRG=XiThCC#cUL4t*B?tX4# z&5GH5Gv1XMzbp?GbARHSeG58~C#z{lc6$EU&HFEcemOW4jE!5p#lYC_Ml~V<(0e>%S!a?m&uP^&rhroccm>Z*jO$4X)biiMp}$<+>Z=`Tz0<_Puoi+-^}uoe?diw>0Df9 zy>tFz&7^bx##fS+i{b@-lwg=U4W9Z{zcu?VD4yDP^$M0_>e3ZLped>xa;%4hNN-nP!EqTY4NrSVz@nxiG zH6^FUoc}yj_YEDI+E&IRcED|%p)(x9-z%Te*aWfzR?^#tWxtEUcT@)Nx5e%K$pikF z^k`6=(RS9bibwJcPfO2C{u%$;g^4p0d;i4WBny9fX-H9PV&F!9DPII3t?O9 zgfr>@$q8?ThcnV5V68(#&@~5Hjku$YP2HMXcEBDI$~;^s=ln6LIb!Bqb%x)8w<_n7 z>^5QRfxMt+j`}9!VGmAwA>BBb*g;9mhnMT=T8hmh_WP^knLGSG_zML~p}gmx6YmrH zlAUM(=IsFF>yqaJ-r~0&@SwkraT=r6CL%UE5NH354v+rq{SLk;(5?LQD!Ae;`pu&9 z;Uig(H_DE?`zYD@ZPxdNc>HsMJKli9b@WkZXS{*_GA8Ifr*CG&y4|2>?E~o9??aT- zx?0Kp@595}+lUp49e9;1*78Gki|$xVp1EB~Vz2P-9}0~KcFw=R*m&4p?!4Y(_-WPs z`K4l6uc1eu&SKl&pNJ!6JeJd3fnLNzugjKkaFcc(WlT_Gr@k{cN$YQd{ME6El9s^3 ziD9ARVfAOAZI55#-=Z_g{=8?A_Q1Tb-w4ux;`EK)?&_~By8xr2A zFGRmlRGz#QG_-$c&uCpQ2K~BBuFhRUZmXc=|84_*(8pozqGZAQKH1gVBcxrr{*Hc0 zNz^N_0a|>troNnSI&_!ol)UB}D)0E>m52n}3_v33TIC z2b*pRO*7}$+~@97TJE~h13D7?8HWdXr1>p*mpKaZ%`;^3cj!6Q#!EL%aE&V;4<<6)U zGOD(eWehq;OfYUP+R3lMZvebhfj*A)98Po33F^4i_qCFh-Oet3TeEPa6Kxa3 zeobATbUe#rky2tEwfUOkA$!s<7s@wD9qmr_H0Z}^>8K`1%Q_0QA~@dqJfkFck5VD= zQ4?$2=k9x@+zX#7b=qM4J2=2257ms3FTKcZ$LYGQuV;hYcVlsbzV&O3KJ_l`+$UlU zGU_N#vi4qsJv*h@O;K_(O#M9Ad$|3ban5s>{pg4{(32KDmTtq_XALif+!zD;x)GRYuSZoU+4%L@rEPyr zsEd4Uecl%4`S|b+NmpbA)<&$`OWw)cP3^a^5&4-`OoZ~AKK1r$pn)~wt*2Tex0Jj= zHhqnQ6j{i=XWUTvD?CDZ+e)`W{mpoB^+Z8=qmh!|`Zzy_&)xsMN19a6CtrJia>U5n zzOm3Jypnf9S?B%`YY!?J;`!C_KAn7%Wa^tf$M?36L!^$A;LCB8-8Lk}tv`GmgLHOj z8+d0a;OuW5)@CBt$0_&3ZA>UrUlVhq#H+u~;BA0Plo}V`>6$z6d_Cx+nmD#l@kU*d zJg;z#7>RpDiJNUXxxYsmS1l~vy+3PlGF_dLXMNozx!*}_u9lv`8tL0` zwO{J0mO?wiDVq#Kn?seWK-Z?hhULO9L-`wZ4Ar`jbcL_spOMZqE(v&RRJpkH@GjS4 zWeRlGX5J2x>ywiDJ`rn=#K-{8HtqGqT2Jo^>DM}Iuy%4>MfgoOYVn47-;Nr0xy}~e zpqJdN!x`H)AYRJ+KGL&a_a$;W)mt(Z<4v5I+c@r|H2S zXdHc8uiUF-PhV%e?d#`}dn;W5eyW$>#;apeC+2a9?W^%^5NnU+HtZ+Fm2Ue6IHoNn zJ!2S&Yxd1}M~gMiG3Ni3vw=0laWemDi4JR%R;@=psS+6)AM&q8mAx`lC7r>UiMPq% zPj9NR@>FdlN&Wmdcmw%UvHh=%9M)3snY&kMDOEX2e(mjyH}ccRZjP0YV1Lu$WhC^> za>Z*)o{=_tGqKh@FYIYswAb-opLu_Pe=F;-27`<+e@!>fXxk4PZ@$dN8~Ak--Sb&< zDhWBVk@%(Wg)wR#>Yy6id?-9K*g3SrJq2HZn{D~`!5(ST zKnZ1e9o`1O_FLqJGJ(1RvG#a=>F3#`y@vPsz&rh{+jQ-7cVc2=N1p<)_Ws0;zoDm@ zqbGFyaVKfo3LVyHo3Zyby~oM$A>F7N%0zY25pRRkZn;f8Ceic*rH5CBcumx6mtoGG zX&c{>{?g}xx31n9TI`U|Mm4x3)sH}|J$VtZwo!XNu}0t3w71W`9%`Sn)$sY~<{NU` z5%9Q7qiwi%ecf}ZBOjjnT*R=(_oY9+ms;V(u%4@%xRhZx-u@#Kb8`pWB; z4IWcYAAL*2%YEXVtHn=e?-cPoa{L$v?M(cv@Z}eLd^boJX9o zy3iBe56`+S*G|*SW9oalc}LrR!n@;xg*f1K*i59QgJb?k%F_o0ieir&W{;XcHx)UW$^*Z$!!5PV{s6WFg|we(dUn-ylk^ zj;Cu>mqTsQyVb&IiK79zt( zQ4={2o}-OT+c)FAkiK`b&*AKMz#m^vJ!AOei7BV;3-yykwYfBGKAP*(E2Qpq9vShX z6591xgT~sw@1Ki8j2ZGPJ;-;1KZ!PqUfxxPkBV_c-MsS+`K+rqK|1>4j5xG*zP|FD z?;H3IzIOC2Ojdu(!%=TL+HxntmKa;Gh^XArz_U+gzvq+r!19t0eMbDp=I&nE@vRrJ z#vb^KJwn^^5yU@HUuI6I^&KMh`^1F19cwp0zN#8AtZhhsN{4CIvCgb_;~4RqX1p%_ zR8BZ!JAGQkiQetl?>9#I8BX@ab)*Oy+bgc`bdepTU>k z#XC*tV`W@rdtZNf0a$M1`&ORteJJ<)UY0vNPf0b^M9QfKa=EGv`-?Zze}-wt*jWjl=0WtZknEz2iJN&0o0ftZVfWV%prW#=o^w{UvvI2cM7)d-l`k9Wkql1-HEKpg-gYUTE?K`yvaXQ}Md=z$HZ>vIx^T))5z;FH- z%GeHPoiQu1=Jf1|umv?zFUg`0B5N}t4|B?gft*z@qgVrdY^|edbFmIdD03Bwb3TKt zPG5l=*66>wMLp~s?*W@uzNzJmc-bxwxyN$Y`<&RzD|N1^;3&&G&3RU~GdAwt$`?gk zw{X-Eu*S*IwR`XZr;oM`!`er{nl_#zarW0|4Qp$^P|!8scEuWT_^z5PG4ES!ZKxxY zXT&v<>(dhAMb1@?avm9rm?5_q4m-}w<6n`-(yYcMhK+Rs=tfrJD3oWDx85B6AmWZA zYd1MMeVU7OyyRXk{#1^^HHpU*QYRHL4 z{Zb$D;tCe`%Igi4On6-x@s>_GPbQv%?SJd5q~^6zQY^ZHv_^~?^-sp>G7fE+=QpJD z9hPb8ziflUO40R=_|9PO74F~tYa6AFk%c~5DZN;OUZC|!alNo``2X*JPiz2h%)GA-mzsQwjb=h-AYRIYsCy-fak6PqHaLW z@s&z0yQHk#6xBo;t5*;Q^`W%%bb}4|TZ1OP@0)7)O+WR{Gjz@Gyc=bpXS)pcB+5w7 zKH&8T{J?)Ars|}DTVmJ0okFhFDd6~YNLc1QpQ;_3Df7hoymtD-W7uF(pe22D4Kz)g zAGK-zz)X1uxA{+kKfa2(UnXJf-DunAY6)zvU?3sL{lU&5uN{V15?|FA$@LX<+}SQQ z9Uu=H`Nq&a7>}NBQaK~GBhTn-VQ0QtV!yjea`(DYa&<3-S|nFU%sZDGvAa>P6ct~K zOGVwEPZaDssus2y*eYSW7O{Dk7nI8{zD_Fo?vR_+LvpuzPMZ1NkOyJEenh<|kE;*l zaZgw5yUPFJ_y4Ib^00bWs(2c~?+{ttz#OmSgbsSF!CtXx%XSQYcz7GS`d7+oKcvNP za>V`Y<~s!2Gghs)+Te;c##G*LNhSFsgq%OO=h5y)`&%^PJj~kS;rhEmKHtPC_X|@o zOKdY%*uXC0j;Y%)XQpaN4{8B>;5+lmdgLyz`_jMXZ{{*@`^GB=E%~Z$@0p&zog8-! z?7C_5mw}fP*uut|`gk$zYNza28@V#r$ zFUlBg`|=4Txq{R}3K>f_`(8$`Q}y!5z7TQ^!x`Uj&z97@)J*k zSoq`Tx?*h-Waz4@sZgd*@3SASiQKI5E_rtmrd8o!js6kpO7?f7o^8~)iGZwXy*KN5 zy#{?=)z4$BhZ9vZm&6bHSc^622i?d;0fcZ_h0&`!$ro>-VR@8|1aQ)3zT(CqmZ` zfU^WU)_CtfCN)m;J*D?uoUYsOl``^Iy#Kqzh`D7fWV;6bdU^E6Gq+`++T}{yh9Nhm z;f?vy<=c$5zSpqm?zE9~Jqhx+(#Ey zYKSY=s6RAO9b`RXh3wA><(RbrRl|G{%bQ_-eQaz&X{kP!s5<#2)}fBMiA{4)9XQwL zS4hF?G4d^RBYWHv--U8%=VquO0xZP#yHZ}hC$uDr)mMr=o#wbhxQnr?YJhz!B?e(C^IjEBt+-x9}~bqb1CkA@x} zh!>9cjRk52^~Zmvew3aq1Fv-(U+dpUKUv#8<{i*BeADLKXJpUXMU4GqoB(sHeeDW4 z=TM_QE7#b%?8a!rHf_kBar$@Jh#C~?K71FbqshLiCkx8ruKIJW@96fs6S3PHd=v5N ztf@E>G|tQer~Edwt&(rYj?>XKwqfDm(0C|n!d#2<)2vH2Clho~%4N*G^FoggsN2Ui zF+f+Ae5fC@Pn#?GN-cAxZM3zOEm%6NdX?7kCoS#x0KV^+kgJs*zGvfy%)z-;J!;6B z6V$)Rm6$9ADijO zd{Zt%H}WC|wMUCoI!U|Z?T9apdc2@Cc;Z?33X;>{4SrDs0ELD%;?mAPdAxMVjCAoM zr*|XH7{lRxK6NcdbG+y;CqH$%b`AXTkEqVBSfkyojp~yjTO0K{%G>JUiws+;*}wGe zy-o5Obj`F04phI&?Y<`@26cT&LwMiZ@GW$HFtk{dmE9myp>Ov7&@K`z*U&z;{I(7c z^v5VG59^jFL%*`>w$y(qKeOilJx{mQVh!@wOQB*7vRw@w)>bc?;5hg8eur{QpSX{) z+ob(g8o)dw_=ViQY3lcND=J}bi#cz)eQ&i_PbbX4Qu*Y=|@1H zt^IfTo%@?o^1SL5&}YWxwNzigS5?rUB_;5jQ0z6#|9P+m>Te;I#oia{i`QT44eCFk zAC7kKc6TW$idcnwSNf1ofm-3f9p5`(d@zQMD#I28*(Tp~+`m>m!8)*M=o+vSat#K= zz5P#zwT%&s!zF#csRG^&V`3jC@|sq4g5!fVh2BvU1Ln<+H^#NqjCvqIrVSXsAabPj zT-IB7;#Tlf)ZGoYmZkZQysmhW3V{CcfPS;a;ah5)sEbhp@Fm+EJM=LQG=_aK?`_{x zkJj1Y_)e6&mw%$cIjs{cQ~$x8fT#{nh(|`{ReHWNB0-H2EjgcOZ|Wo%1z3|AtbCC2CT@pbvGi zmI3WgjCETAU9cZyy+^9yePL@?&lQqfAC)k4+XvKZTCDLKc?I?y#zndHW$eq8n}XQ? zsFT)-4XC&DJM2odRYp_4PLU5u51Ehexh*&R_U_MR9Z$2i?2##tX|V=6H9n(Q`*k+l z57xO($8XLN?SVSpY2^WoX;6<{WXvUNjPg3GjB56Sb&y-DZye{%Pv1_<1F*HZ)u%M? z7xo@_C#@rYrOvEdqk(eIVc2OHUp)B@CH-3~sa6{LH)1>e{R_-ToS^_gT= zwLElp1h7V%RmioJ@m=N_0@(n(NZpfHZo5)RxBpYZZ_9jd@`DP6OQey1>~q*nElRho z&3slQ_rt-5yQrC3tg-Lp`^2UFnbeosLyphg)4d)wW9FLH@Cet%;XR1=j~@dqw8qG% z;EmsX4am;qk@n}g9se<@i44;CsUm^3#0+AMeiZNRsE1(JJ8j>X`K<-)fjh1jKp$lk za7SAsYkttz@cna2K2q}>=Z$kmS-fiTvRb<1HlCUFH^xf1`E}`odm8$YsS8q;r!G|V zhA7GXHR3ig9s%QH8AHR)4}aB;o~hVb^%?j$>xXI9@M6q-de)Kteey$@M%Q-C{U$8j z+vjNvWDMHPoW>~Rc3_qD{a6nxx_p#eS3=1>s*Nkwh_}|NC-T@*$KT$+vw2J#d^6Z9 zhN^wqep4^4g_>WcPbi@yumYJP6#bX}2CEOAw7)6zP3kde#+Wi4zJIfJVmM=Pc*^5i zc@6e8ES{1v9=c^-?+jt>v053dp=|kf&x{$yin^b-ZXWpKf7Q+#amJ0dwm0F^3uip- z=aRm#KHSoe{PLGhhO}R!J0`t)5&9-`zs&yG_sp-D2pi-^_~<-XPb-*wW{wGctrbv9 ze{dUR=vQ3ZQpY=aKC#=dd@B9a_0_5E;I!6StRW`~KnV?N@G&&h**w<$Ff85kMA<&3 z4%T7R;UxlXl!ISY!yV_1^T=FY=o?yIrUI z8-2W7m;QFolaBFGLHs$UjQ3wun>{!y2Ve#_bJs2hiH+NigdRksLrI6Hl?9>1;P zjT}C+U!m?rY`9_O1;3s6i0dT3s+M=Ikhut5uf20SDcX4{(NVI#N zEg)a3<&N{lIUJ()O4DlLub;@Zh@5H)(nnMnah$Zbo3gz5-nu>Q^{QzBLq}pv8tYA4 z@n!w}4)|zHSNAobGdgzE^;_H)K5e5PNk`XU%MCdWeDd~#`Eiev_WLBPSeY)YQJ1dD zH3-tVwo0gDNjlLSIcwIr(*3?4d7I(b+77_Zpb$Ui7VBZy1DjuL#H{G>Wwuc#Xjs)F zd13cAJ| zsx<4Fja{<^IaDae3;8&ljj3o3i~N<8l|;>Dpk_VE#A6b@R;r&|jMiu>)rOqxJnV z<2U)-dupoVyb*7-wUsY)RY0t-*8I3U&qC+ML%vZJ=cg0yA?J@=7Of+g>koT zdJTP~hMX8-e3{QT_l)1TqH=V|HCrd@*LL}L;JSSn<p`retD6s} zHriX&(-B-(CCGSlzL_7+Tq=`}>GrKu563u6-Mjn+8x><0eTtpIV=JXF%dqmxV?={G~N8<0a!BvIcOIx$G-}c`p<8PFq z>wZf^*AS1k3w6}O#o9Y|y2j&eb9=e=A)rt26}GGIU_;EraZ?X@q_5iSiZ#}=5615T z-UT?JE$!W=dVeD4*`RAFJd|-^jMumpYXF*Yc%+YaB3?Ei{y1eEe291Kqc%DAnQN=+ zu8Rb|?Dt?CF4`*Cy7;Yia+W-W>%RsP4^oCa-De3y@pk z53=`{$E*+iiW=&OHRd43e4xKpcfX9b(I$5b@W$K%-TZE!+cOPKBVK^Dcf;YIJQsBE zavj#Du3U|0hgQ>z>*9G4%atzzvHIbR9c|%-N|p-hkEgAHaY4GVbZhI`625P{%?t7u zeb_1%@kI^t8M#l)X{Dc>d6taLC=6N1$;ZUp(Hm4fN8V3gma3y1`FA+u6Y9D2KipZ# zBaHvGkH=3-60}$Yjk-5ntl=8UZ2QvUZC^;W*ZeipP^SR#dZE5sB+sL-)F~d(q;ZC= z4Sqsm!9JF5$Nt<=*yADFP_B=D39*rP#29sjlov8X;ew*Bf}DDp-w(z3amKe8wT@h5 z2T#+yj`}EVBK1)d{cQ13V=kcAtDAG5iB~hnwU;fH7$tK&o%ZA@U5OiC0ptFR z{rOt`V%UheX3>-sI~n~KjM4l?t(FdIH0rB9BEDt?{CRK=aW0H2!9Yj&?(yJu=dO1NkOqjnT2axTlK9- zkB961fN_QO;|HnV9OsU68LF*~@#bBCv0GGg`2cZeqfwL3js>@4#;Ny#@1M42?|sO% zhOOS-f5wVeSB)KG+PTi9strEsfK~hb(tFJB)OUAY83f#)XJ&~~ibkD2osk@z7Oo)c^=`TW<_NLNgZRewm85|^d1O_=XPJO9)-;rEDXAdI&R zR%_4=Z|2`vL#__|oY8NhwwqO!<@W(UsndE6yo>aVMYz{cRxcNQ zEBx{Qy5g;s>aMl5@tdYT`50(XusU2OjzZm!$NC@b)c2wqBUZ?gOGf`F^QoNf(^*Y( z)MdjRAM5$Kzb!3gDn-c@d{?yB*zsi^|2M9fj6kgo9Ss_@X@4OTJK^q!uGvl7$2YqB zu3b3Fu|M=dMebx%ndGh5FZ}q<@s_qB{9UGlP%j{-UH2!$Muz#FW$ix0xSmaR!>UP<=HAHwa%= zGp_;G?$BXv{OV2GevuY1XNhB$Rrs<#m+`xlk)~o4oaUccx>4PI#^%a#W(-tQ^(JuU zP7|H(8BRODg_s%_``1n;ABBx>u#23@nz`Y|vsuT){+l^%jK_4sm$jYick1u}+5U}_ z8NeCw1|2pU_uj9&|AA@k)AVn}r?6pSZA|<7MEn?YLVJo~Q?bfCcKMEVXs$0RBh?{C ztPvM)s4)ir;JDI%6{tnzlY^{$SL$N-xH&*8ywV*va9j1^xH<+Nphm|Fgk$u-_tHAmVh)La*rO zVeMpNT<}cFR;-gnyTr0j{P{-jKZIPqtG%d6S=#VZ`s)L^`{VCXFB-YHtfMd>NbZ7( zH_BD?V?GOC{&j_~GHM33gneIKo0-qC z@0rV!XH*2^jPU(N!=A>xK3(n}$9U4pby}6>|W3JmB=h%83 zZMDs?&OlqpSIk4E{ThxjgBN`P`tC(ttJv?al)NLaHR@%sRz{`#cS%pR*75#apYk^E zW60IX3p$tJcwVIWs4*{~lexgZ>%uR!pmSiYh2(@cwKxMNPK@2W|DufG%X;lm$Ze4Q zp4VY*-0H2UH3?P?+;g0pRLgw5fPQM`B=cLd(s=uC`u>~W41YKBZ#jnc`ao9P@Hg!m zm#QnV*2*W2b8KGI2XQ2|N>nmx`s#dK)RAbHW6d9<4g+jJj0s>ot{3%gJE&2PJd$)$ zDd<>OE6?;pn9nu$tkD`%3$?Hyw`TbJweSqyi!lVAwwGdECWUpL{bS7auXXbeTztnm zq*lCS^f&7NPXsgq@ND;KA1OWKG$haen7i&*~>jrLRED2 z$5U5*8Z}1SsJ^aPBX6r&;`*R5UT6A*Z}8v%CI16oWDRfTE_qtymlq)uI>~V_sD1|C zMq!OB6JORn`+BcxtIzqgVMjZLA)G^7g1R$SmJVtIoM~%c$*>K{l{1Ph`}KpdULSDw zxejZrZF(xMq%rT5lQJD^{PqxUeHZeVbTJ5L=Ga2_h&lS0K2-~~b7#(Df3-d6IZvpM zgmK~a=a7do2beXObag!#k5vCg)Rck`h;ho^mKQntKk3i7N>y`>A29eR^q%x$DU|Dc zZ41dK6MO_*Tgs_FtUVJ`J#+Y|F~+nPT~}1T`+1v|e?lj?%LywPZJ(WZi1v@(I@&gN z%{KXO{0(w_QTT>u`fG8Tn9%N7R|4-s`xx~p*8ZYALwg1NnA}r`jD?TdSknS?W0y@R zSKNkpK3#2W`yBI_dh0{L0BsOX^B1iB12sz+muJ5}Wy4A(QrCLn`&^E70T@qY&Euo4 ztWbN(d>8r)uDZOs=y)aLMp!$`$%nwc-ly96>0}5zQ9BPV*ToLJN*c9(SzD(R7+40G z3Oz`_pCH(^klRY)Ie+W$wsz5IBQDjbA8mUF#?%u_{O&1hsfy83qd00>RQAVsajmJr zZIv;P^vSWl7~>4+k8BQFS+O``5K%KmwJv1XI`hW)^?l;<`{&Zmy&VhYG3E8wA(sck zl+)k2)|GA@3)aLkYO`40+lZY+9v^LvhK>rna}7Z1Hr9FPcg1z`bkC$*rfWCbXvd@d z(0ac}{r0xHNZubaLrc?uvwMPJC8K}ecl0ph+CI}^ZP>a!vT5l5Nuf%q@uyrDj(OGh zLZ=z{yx%s!d7=Dd*r~yH$$L#KX!rO#b3_=o&zj8B-$MPo8kk$G^T2T?9<|q52&OVZMUG|MURyi6I+D!{jmmX@RE4{GKsd-GBt$n=(K6~zau&sRL zoS#lV2G?$I%E#v4=_^Q2%o1%QhQ49NZw7z+kPrLTpz&IohWW2yV&QD;p(nho!y4Px z&*)*`jW#gWP^63!G8QznDALywqfe-h(}lJ6YM}hkCGGpLra9}^1kkH6=iB>4fuJ!d zCg!dCu4*=F)<>>Z3hM;k()bb3w6wlY=$?beZ{Cjq$b6b+J_B-_54=?COBlKKS2;1U zakj#j6|dyowXTM27-noO=l5eZUt5b{G~`RlT^Yd|V|6L(TX7W1Z^jiEe3bfAnE1Az z&w7f!+Ii%&=}UAp?HJ~~u!(`QxkudYZBDdpHr9kc9hW)ljazY(-rua{&A7u*=F)l& zV`iC`XMZm1GV1Ek+UL^s*oY_cImYE$`(gk6fO<9Kd=zq{?|%j5#U2B7IHTS6#UZN_ z&nitb@jQaLRt~Y0#NgT=Mx>b&`y6G}G3%+;_B403C)nqc$CRfkM%|XC=2`-3mPaDy zowV^KH7M+FfNQE|wB{J=I5chdrVL)YHx1T6&lV0^pM+%1v&TE_&w}4IANrw<6Cb*M zuOubBm2L6XroIQd-`I|N1x#kUHH9l8Mg)tU7T4ryfAB%NCt$knjCF~i`WH3e)JTwNiYZ=qjL#+y_ zFV?;_MP2ykTu1t-`!YxFWIca8F**Xi(@w>WeM-J;}LX?{)G34E!{R5 zaZmroR|}XM>pW%UZ`w|{#wgcYE*D$X@P`vi);Uc3`?TDRwVAn=qS<%a3yWQwv3g9* zW4f!HGU`XuW}No9?si?~F3?tP$CBG|F60_iY0yx5E#9b|JIF{A`>p#eTj0#Z-Gr?N zXycu$!y4P>VLixGaYfF|jX6izX-~Y6H$Ho(k~>hVrHh&&W7JXYoOg$P?#=sCvBvjc zojJyFxXrEG-{=#fkAZdcD=6BVPimj-gh4+a^@PSpNkg$-)g6yMEq#`5(c^4=(r&Cx zR=}L&?6gOYUm@Tv$q8>iE}e~-vs~F4ZzlHXH>WSXdZ~-0h3ba<^)&%=&sd;(s#Smw zfpy!2gan_>3K?MI}0aYuo?1kXcyMq|4bYF7E!3P@<7|y z<@*(hTAX1H|An2QN_N7Ry)Tg6t_R-!a>Cp4#S<}>QRf8SIOl)E7DxXRYhhK*-N49! z@vlj6+K{QZPOK4&o??Tho%kZGV`1jtotfVdu&185IH1lRYoO65T;+-aM(!YM<_D`Q z$Jk=0HRaeB=3saqzerlX*Hs3tNo%W3nYYuBi5{K3_pfZlJMCE82AvrFZH7&&EAU-@ zSv&#sE&80nn?dW~+oC^~>-IFMuH=5iUoa2;9@Grs`kTf%Cf>S%zE$!Gd1A;|gB`Z? zJ|5?kp~qizW48|yYOHq+2gVL$UcSwPx;{J9KS zm)5S4f-}T*Bz-z{$H8okGZS}-f1XsJzi*j+*X>E)PRHd9m?P_aW#`|dWAwjsUBs)4 z_s;tYIgXzx{f&Iz2EcpHNL0%O{E5EFZp-%iC{9xzAN z`8pSVvsNV69pc{JU+Nm25gVXTvy?h!8oaS)+syLDI%W#%&MZ!e?YG}YcT7JUYu9tF z?(5Y(##(92K_J%XM`KKl5kCWZ%ySvjGZ+`JS}DWmkKz)BJ|p&iFg7b;mf}neX^(I1pc4dowLqRi8sWgP(OVW z?{~_4U)_H8@}-D>Ym|ex6dOu7xcnFE4*a}invQ-2v_Y=vJ7L>F7@p2u`7Bu9<2FNI zSfA9y&E8A=jar*1JLi0zgSRm7mOQ_7ImYCk; z#v{Fr@o|;mIDX_0yJmd~|JJ$VPYp-b3jJJ<9GL!!B>aL}_ZXL88+3qSz*-*N_+Myk zlXv~Wc*|Qc9*M!mjenoMVukFR@eVKtlaTE@Ki`iJPkmMv{JbD2zEZ~VFvhh7a_lY$ z*({vz23X4r8pj$AL1`SU~DFM!F4%uS;plB*p285 zlFlA{_9W~#NeLZg)uM4SdF9%$@s;xaOMtO@6Sp18(!9;A;(wX>-1trVXdmGkS);Hy z#{IhEaGy*C?O6Wf6iJ-(mHa;WG5Ig9bf(h2Q*p%+$8xXi2G&jb#> z-7mA@n_G;n0nW|gm0|MAaPbLUj5d-o81Jt!-hYNNKThXRx8SG8tobOvZ0N!gXZ|fY!Z; zd06Q%M`6j=)_V{igV*nuK?WXo%Wz<3_;FDY8ci5qmDRe!~RI%DNSGT zUWwScqE=6_ksEX9m>mOIam*UQkX4wnIVg@r>G( zTog3#L16BE%yj~`o%kKpFP2V>p2GbP;@Uabe~RZm3E95P$W6(f?^o?QZ^kxHrh302>`ZZ~9|+tk#*ClAH7^mXvs zyYRc_)a{4zV!cB(u{R6Ngw~&&^DgXhdU3=IH7oJ3n!N3xibK8FiP+D?dJi+U=hz=| zzKsj}+sK*!ocYheKn@0SFpz_R91NUS7{GJ}{7Vct@*kYlw*M5%ml*%d=bpyetz3JT z|ID^Tv?+g+*~Zh(oS1UnQKOB45crqUHs5Gdoh)tsOU;Y@=l$(JP5CV6C8o6bpX@)c zv)NXMCmL<$?NV-NwEbtE=D(rQ=IcHR2e#GGw3T98;Awb~MB8idMf7cfuf~^4 zw7o80E>QwsSKsErd4WT~K}g$%r5poijs4fPbxM@^ws%twZJq7s)k(AupHjNEQi=BA zQ!3Q9ixLCT!ahX0Emxv_iZDqLZu4pG=S#FtIVL@)&0!4E&XI0RBRy}qH2BlCWek() z|32^?b>=r={ipi|9optwujB7ddU}v(KTq`ZB^263dSwT`6aBMKx{h|T%}yjpi|vD| zYcptj=fIb%!)xaUwsm4#V(>Pcq~}qAFAQdj^8#Pa&+`Ib#NQV9A`o_PZD5<9uLgEH zh5rV0x|9FffLX%5ct2|gOr59VY2=cT@JsnoVJ52=&dX1<+Yuruy=W~hzZrQFZFp>aF2Ev1K@cssMr-$SE! mXWIN1moiQ>&oel4ia2?ujg!*Je_Co=$}xBT{#hC_+V=l1WBMKd From 2b74c00a4ac6bc7288fa82c4b1f5fa76f5b594f2 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 16 Jan 2022 22:36:58 +0100 Subject: [PATCH 34/47] Fixed some lines which slipped through at the last merge. Compiles now --- daemon/include/pigpiodhandler.h | 126 ++++++++++++++++---------------- daemon/src/daemon.cpp | 4 + 2 files changed, 68 insertions(+), 62 deletions(-) diff --git a/daemon/include/pigpiodhandler.h b/daemon/include/pigpiodhandler.h index f6902d22..847c59b0 100644 --- a/daemon/include/pigpiodhandler.h +++ b/daemon/include/pigpiodhandler.h @@ -1,85 +1,87 @@ #ifndef PIGPIODHANDLER_H #define PIGPIODHANDLER_H +#include +#include #include #include -#include #include -#include +#include +#include +#include #include "utility/gpio_mapping.h" #include +#include -#define XOR_RATE 0 -#define AND_RATE 1 -#define COMBINED_RATE 2 - -static QVector DEFAULT_VECTOR; +#include -class PigpiodHandler : public QObject { - Q_OBJECT +class PigpiodHandler : public QObject +{ + Q_OBJECT public: - explicit PigpiodHandler(QVector gpioPins = DEFAULT_VECTOR, unsigned int spi_freq = 61035, - uint32_t spi_flags = 0, QObject* parent = nullptr); - // can't make it private because of access of PigpiodHandler with global pointer - QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) - QElapsedTimer elapsedEventTimer; - GPIO_SIGNAL samplingTriggerSignal = EVT_XOR; - - double clockMeasurementSlope = 0.; - double clockMeasurementOffset = 0.; - uint64_t gpioTickOverflowCounter = 0; - quint64 lastTimeMeasurementTick = 0; - - bool isInhibited() const { return inhibit; } - void setInhibited(bool inh = true) { inhibit = inh; } + enum PinBias : std::uint8_t { + BiasDisabled = 0x00, + PullDown = 0x01, + PullUp = 0x02, + ActiveLow = 0x04, + OpenDrain = 0x08, + OpenSource = 0x10 + }; + enum class EventEdge { + RisingEdge, FallingEdge, BothEdges + }; + + static constexpr unsigned int UNDEFINED_GPIO { 256 }; + + explicit PigpiodHandler(std::vector gpioPins, QObject *parent = nullptr); + ~PigpiodHandler(); + + QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) + QElapsedTimer elapsedEventTimer; + double clockMeasurementSlope=0.; + double clockMeasurementOffset=0.; + uint64_t gpioTickOverflowCounter=0; + quint64 lastTimeMeasurementTick=0; + + bool isInhibited() const { return inhibit; } + signals: - void signal(uint8_t gpio_pin); - void samplingTrigger(); - void eventInterval(quint64 nsecs); - void timePulseDiff(qint32 usecs); - - // spi related signals - void spiData(uint8_t reg, std::string data); + void event(unsigned int gpio_pin, EventTime timestamp); public slots: - void stop(); + void start(); + void stop(); bool initialised(); - void setInput(unsigned int gpio); - void setOutput(unsigned int gpio); - void setPullUp(unsigned int gpio); - void setPullDown(unsigned int gpio); - void setGpioState(unsigned int gpio, bool state); - void setSamplingTriggerSignal(GPIO_SIGNAL signalName) { samplingTriggerSignal = signalName; } - void registerForCallback(unsigned int gpio, bool edge); // false=falling, true=rising - - // spi related slots - void writeSpi(uint8_t command, std::string data); - void readSpi(uint8_t command, unsigned int bytesToRead); + bool setPinInput(unsigned int gpio); + bool setPinOutput(unsigned int gpio, bool initState); + + bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); + bool setPinState(unsigned int gpio, bool state); + bool registerInterrupt(unsigned int gpio, EventEdge edge); + bool unRegisterInterrupt(unsigned int gpio); + void setInhibited(bool inh=true) { inhibit=inh; } private: - bool isInitialised = false; - bool spiInitialised = false; - bool spiInitialise(); // will be executed at first spi read/write command - bool isSpiInitialised(); - unsigned int spiClkFreq; //3906250; // TDC7200: up to 20MHz SCLK - // Raspi: Core clock speed of 250MHz can be devided by any even number from 2 to 65536 - // => 3.814kHz to 125MHz - /* - * spi_flags consists of the least significant 22 bits. + bool isInitialised { false }; - 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 - b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m - 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 - word size bits msb msb only-3wire 3wire aux CEx? activ-low? spi-mode - */ - unsigned int spiFlags; // fixed value for now - QTimer gpioClockTimeMeasurementTimer; + QTimer gpioClockTimeMeasurementTimer; - void measureGpioClockTime(); - bool inhibit = false; - int verbose = 0; + void measureGpioClockTime(); + void reloadInterruptSettings(); + [[gnu::hot]] void eventHandler( struct gpiod_line *line ); + [[gnu::hot]] void processEvent( unsigned int gpio, std::shared_ptr line_event ); + + bool inhibit { false }; + int verbose { 0 }; + gpiod_chip* fChip { nullptr }; + std::map fInterruptLineMap { }; + std::map fLineMap { }; + bool fThreadRunning { false }; + std::map> fThreads { }; + std::mutex fMutex; }; -#endif // PIGPIODHANDLER_H + +#endif // PIGPIODHANDLER_H \ No newline at end of file diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp index bace5b7d..0b529639 100644 --- a/daemon/src/daemon.cpp +++ b/daemon/src/daemon.cpp @@ -29,6 +29,10 @@ #define DEGREE_CHARCODE 248 +#define XOR_RATE 0 +#define AND_RATE 1 +#define COMBINED_RATE 2 + // REMEMBER: "emit" keyword is just syntactic sugar and not needed AT ALL ... learned it after 1 year *clap* *clap* using namespace std; From 80f040b190680e0554cab4e2c0f6cfd90fd32ed0 Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 8 Feb 2022 22:30:21 +0100 Subject: [PATCH 35/47] Restored muondetector-daemon service file which was corrupted from a prior merge conflict. Added ratebuffer.cpp file which was not commited properly during the last big PR. --- daemon/config/muondetector-daemon.service | 6 -- daemon/src/utility/ratebuffer.cpp | 110 ++++++++++++++++++++++ 2 files changed, 110 insertions(+), 6 deletions(-) create mode 100644 daemon/src/utility/ratebuffer.cpp diff --git a/daemon/config/muondetector-daemon.service b/daemon/config/muondetector-daemon.service index d3cb586b..be7291c1 100644 --- a/daemon/config/muondetector-daemon.service +++ b/daemon/config/muondetector-daemon.service @@ -1,12 +1,6 @@ [Unit] Description=muondetector-daemon - Daemon for custom muondetector board -<<<<<<< HEAD:daemon/config/muondetector-daemon.service After=sockets.target network-online.target -======= -Requires=pigpiod.service -BindsTo=pigpiod.service -After=pigpiod.service sockets.target network-online.target ->>>>>>> dev:daemon/config/muondetector-daemon.service [Service] Type=simple diff --git a/daemon/src/utility/ratebuffer.cpp b/daemon/src/utility/ratebuffer.cpp new file mode 100644 index 00000000..9a231256 --- /dev/null +++ b/daemon/src/utility/ratebuffer.cpp @@ -0,0 +1,110 @@ +#include "utility/ratebuffer.h" +#include + +constexpr auto invalid_time = std::chrono::system_clock::time_point::min(); + +RateBuffer::RateBuffer(QObject *parent) : QObject(parent) +{ + +} + +void RateBuffer::updateAllIntervals( unsigned int new_gpio, EventTime new_event_time ) +{ + for ( const auto [ other_gpio, buffer_item ] : buffermap ) { + if ( new_gpio == other_gpio ) continue; + if ( buffer_item.eventbuffer.empty() ) continue; + auto last_other_time = buffer_item.eventbuffer.back(); + std::chrono::nanoseconds nsecs = std::chrono::duration_cast( new_event_time - last_other_time ); + fIntervalMap.insert_or_assign( std::make_pair( new_gpio, other_gpio ), nsecs ); + } +} + +void RateBuffer::onEvent( unsigned int gpio, EventTime event_time ) { + if ( buffermap[gpio].eventbuffer.empty() ) { + buffermap[gpio].eventbuffer.push(event_time); + emit filteredEvent(gpio, event_time); + return; + } + auto last_event_time = buffermap[gpio].eventbuffer.back(); + if ( event_time - last_event_time < buffermap[gpio].current_deadtime ) + { +// buffermap[gpio].eventbuffer.push(event_time); + return; + } + updateAllIntervals( gpio, event_time ); + + while ( !buffermap.at(gpio).eventbuffer.empty() + && ( event_time - buffermap[gpio].eventbuffer.front() > fBufferTime) ) + { + buffermap[gpio].eventbuffer.pop(); + } + + if ( !buffermap[gpio].eventbuffer.empty() ) { + auto last_event_time = buffermap[gpio].eventbuffer.back(); + buffermap[gpio].last_interval = std::chrono::duration_cast( event_time - last_event_time ); + if ( event_time - last_event_time < MAX_DEADTIME ) { +// std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< 10 ) { + buffermap[gpio].current_deadtime -= std::chrono::microseconds( 10 ); + } else if ( deadtime > 0 ) { + buffermap[gpio].current_deadtime -= std::chrono::microseconds( 1 ); + } + } + } + buffermap[gpio].eventbuffer.push(event_time); + emit filteredEvent(gpio, event_time); + if ( buffermap[gpio].last_interval != std::chrono::nanoseconds(0) ) { + emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); + } +} + +auto RateBuffer::avgRate(unsigned int gpio) const -> double +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() ) return 0.; + if ( it->second.eventbuffer.empty() ) return 0.; + auto end = std::chrono::system_clock::now(); + auto start = end - fBufferTime; + if ( start > it->second.eventbuffer.front() ) start = it->second.eventbuffer.front(); + double span = 1e-6 * std::chrono::duration_cast(end - start).count(); + return ( it->second.eventbuffer.size() / span ); +} + +auto RateBuffer::currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() ) return std::chrono::microseconds(0); + return it->second.current_deadtime; +} + +auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() || it->second.eventbuffer.size() < 2 ) return std::chrono::nanoseconds(0); + return it->second.last_interval; +} + +auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds +{ + auto it = fIntervalMap.find( std::make_pair( gpio1, gpio2 ) ); + if ( it == fIntervalMap.end() ) return std::chrono::nanoseconds(0); + return fIntervalMap.at( std::make_pair( gpio1, gpio2 ) ); +} + +auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime +{ + auto it = buffermap.find(gpio); + if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; + return it->second.eventbuffer.back(); +} + From b86d232c7fd8c40670524b48cc9fda7139d42cc5 Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 8 Feb 2022 22:33:54 +0100 Subject: [PATCH 36/47] renamed pin_bias to bias_flags --- daemon/include/pigpiodhandler.h | 2 +- daemon/src/pigpiodhandler.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/daemon/include/pigpiodhandler.h b/daemon/include/pigpiodhandler.h index 847c59b0..8d0e81e2 100644 --- a/daemon/include/pigpiodhandler.h +++ b/daemon/include/pigpiodhandler.h @@ -57,7 +57,7 @@ public slots: bool setPinInput(unsigned int gpio); bool setPinOutput(unsigned int gpio, bool initState); - bool setPinBias(unsigned int gpio, std::uint8_t pin_bias); + bool setPinBias(unsigned int gpio, std::uint8_t bias_flags); bool setPinState(unsigned int gpio, bool state); bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); diff --git a/daemon/src/pigpiodhandler.cpp b/daemon/src/pigpiodhandler.cpp index 5cb45a3f..3d07f9a1 100644 --- a/daemon/src/pigpiodhandler.cpp +++ b/daemon/src/pigpiodhandler.cpp @@ -343,20 +343,20 @@ bool PigpiodHandler::setPinOutput(unsigned int gpio, bool initState) { return true; } -bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t pin_bias) { +bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t bias_flags) { if (!isInitialised) return false; int flags = 0; - if ( pin_bias & PinBias::OpenDrain ) { + if ( bias_flags & PinBias::OpenDrain ) { flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_DRAIN; - } else if ( pin_bias & PinBias::OpenSource ) { + } else if ( bias_flags & PinBias::OpenSource ) { flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_SOURCE; - } else if ( pin_bias & PinBias::ActiveLow ) { + } else if ( bias_flags & PinBias::ActiveLow ) { flags |= GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; - } else if ( pin_bias & PinBias::PullDown ) { + } else if ( bias_flags & PinBias::PullDown ) { //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN; - } else if ( pin_bias & PinBias::PullUp ) { + } else if ( bias_flags & PinBias::PullUp ) { //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP; - } else if ( !(pin_bias & PinBias::PullDown) && !(pin_bias & PinBias::PullUp) ) { + } else if ( !(bias_flags & PinBias::PullDown) && !(bias_flags & PinBias::PullUp) ) { //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; } From 95a3f177f6e8107ec2dcc12866b66dff865aa99c Mon Sep 17 00:00:00 2001 From: hangeza Date: Tue, 8 Feb 2022 22:34:22 +0100 Subject: [PATCH 37/47] removed commented-out lines --- daemon/src/pigpiodhandler.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/daemon/src/pigpiodhandler.cpp b/daemon/src/pigpiodhandler.cpp index 3d07f9a1..d5047fab 100644 --- a/daemon/src/pigpiodhandler.cpp +++ b/daemon/src/pigpiodhandler.cpp @@ -211,9 +211,7 @@ PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *pare int ret = gpiod_line_request_rising_edge_events_flags( line, CONSUMER, flags); if ( ret < 0 ) { qCritical()<<"Request for registering gpio line"< line_event ) { - //std::uint64_t ns = line_event.ts.tv_sec*1e9 + line_event.ts.tv_nsec; - //const std::chrono::nanoseconds since_epoch_ns(ns); std::chrono::nanoseconds since_epoch_ns(line_event->ts.tv_nsec); since_epoch_ns += std::chrono::seconds(line_event->ts.tv_sec); - //auto since_epoch = std::chrono::duration_cast(since_epoch_ns); EventTime timestamp(since_epoch_ns); emit event(gpio, timestamp); if ( verbose > 3 ) { @@ -270,7 +265,6 @@ void PigpiodHandler::eventHandler( struct gpiod_line *line ) { if ( read_result == 0 ) { std::thread process_event_bg( &PigpiodHandler::processEvent, this, gpio, std::move(line_event) ); process_event_bg.detach(); - //processEvent( gpio, std::move( line_event ) ); } else { // an error occured // what should we do here? From e9030c6ab558bbc6e331b3d600c0a190a20c8c40 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sat, 19 Feb 2022 21:48:48 +0100 Subject: [PATCH 38/47] added suffix string "libgpiod" to version strings (e.g. used in package descriptor) to make this libgpiod-development branch discernible from the mainstream packages --- CMakeLists.txt | 2 +- cmake/version.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 621f98ea..e217b5dd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -82,7 +82,7 @@ endif () set(CPACK_RESOURCE_FILE_LICENSE "${MUONDETECTOR_CONFIG_DIR}/license") set(CPACK_PACKAGE_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/output/packages") set(CPACK_PACKAGE_VENDOR "MuonPi.org") -set(CPACK_PACKAGE_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}-hotfix2") +set(CPACK_PACKAGE_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}-${PROJECT_VERSION_ADDITIONAL}") set(CPACK_PACKAGE_VERSION_MAJOR "${PROJECT_VERSION_MAJOR}") set(CPACK_PACKAGE_VERSION_MINOR "${PROJECT_VERSION_MINOR}") set(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_VERSION_PATCH}") diff --git a/cmake/version.cmake b/cmake/version.cmake index 3b600f1e..7dcec3ba 100644 --- a/cmake/version.cmake +++ b/cmake/version.cmake @@ -1,4 +1,4 @@ set(PROJECT_VERSION_MAJOR 2) set(PROJECT_VERSION_MINOR 0) set(PROJECT_VERSION_PATCH 2) -set(PROJECT_VERSION_ADDITIONAL "") +set(PROJECT_VERSION_ADDITIONAL "libgpiod") From f4eb121c3e0a4127744ce453657b911580b9b017 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sat, 19 Feb 2022 21:51:42 +0100 Subject: [PATCH 39/47] removed several debug outputs and decreased the status2 LED flash time to 10ms --- daemon/src/daemon.cpp | 6 +----- daemon/src/pigpiodhandler.cpp | 2 +- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp index 0b529639..fcdaa010 100644 --- a/daemon/src/daemon.cpp +++ b/daemon/src/daemon.cpp @@ -1449,13 +1449,11 @@ void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { //emit eventInterval( nsecs ); if ( nsecs < 100000L ) { emit eventInterval( nsecs ); - std::cout<<"trigger interval="< Date: Mon, 21 Feb 2022 00:53:03 +0100 Subject: [PATCH 40/47] improved preinst script to check whether muonuser exists and already is in gpio group --- daemon/config/preinst | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/daemon/config/preinst b/daemon/config/preinst index d97ca101..f4e38b93 100755 --- a/daemon/config/preinst +++ b/daemon/config/preinst @@ -1,6 +1,12 @@ #!/bin/bash -e mkdir -p /var/muondetector -useradd muonuser -g users -G dialout,pi,i2c,gpio,users -s /usr/sbin/nologin -r -N -M -b /var/muondetector || echo "User already exists" +if id muonuser &> /dev/null; then + # transitional code until all older versions of muondetector-daemon are updated. + echo "muonuser exists, adding to group gpio." + adduser muonuser gpio +else + useradd muonuser -g users -G dialout,pi,i2c,users,gpio -s /usr/sbin/nologin -r -N -M -b /var/muondetector +fi chown muonuser:users /var/muondetector chmod g+w /var/muondetector From f1a04447ca2237d8e61185a6519bb9d9c6efcc44 Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 19 Feb 2023 20:22:30 +0100 Subject: [PATCH 41/47] applied clang-format --- daemon/include/daemon.h | 10 +- daemon/include/pigpiodhandler.h | 113 ++--- daemon/include/utility/gpio_mapping.h | 17 +- daemon/include/utility/ratebuffer.h | 68 ++- daemon/src/daemon.cpp | 216 ++++----- daemon/src/pigpiodhandler.cpp | 645 +++++++++++++------------ daemon/src/utility/ratebuffer.cpp | 161 +++--- library/include/gpio_pin_definitions.h | 3 +- library/include/muondetector_structs.h | 2 +- 9 files changed, 628 insertions(+), 607 deletions(-) diff --git a/daemon/include/daemon.h b/daemon/include/daemon.h index 6dc5e68d..c07d15c6 100644 --- a/daemon/include/daemon.h +++ b/daemon/include/daemon.h @@ -231,7 +231,7 @@ private slots: std::shared_ptr> io_extender_p; std::shared_ptr oled_p {}; std::shared_ptr ublox_i2c_p {}; -/* + /* float biasVoltage = 0.; bool biasON = false; GPIO_SIGNAL eventTrigger { UNDEFINED_SIGNAL }; @@ -262,10 +262,10 @@ private slots: // mqtt QPointer mqttHandler; - // rate buffer - RateBuffer rateBuffer; - - // signal handling + // rate buffer + RateBuffer rateBuffer; + + // signal handling static int sighupFd[2]; static int sigtermFd[2]; static int sigintFd[2]; diff --git a/daemon/include/pigpiodhandler.h b/daemon/include/pigpiodhandler.h index 62ca97d1..ced13b9e 100644 --- a/daemon/include/pigpiodhandler.h +++ b/daemon/include/pigpiodhandler.h @@ -1,19 +1,19 @@ #ifndef PIGPIODHANDLER_H #define PIGPIODHANDLER_H -#include -#include #include #include +#include #include +#include #include -#include -#include -#include #include "utility/gpio_mapping.h" #include +#include #include +#include +#include #include @@ -21,68 +21,69 @@ class PigpiodHandler : public QObject { Q_OBJECT public: - enum PinBias : std::uint8_t { - BiasDisabled = 0x00, - PullDown = 0x01, - PullUp = 0x02, - ActiveLow = 0x04, - OpenDrain = 0x08, - OpenSource = 0x10 - }; - enum class EventEdge { - RisingEdge, FallingEdge, BothEdges - }; - - static constexpr unsigned int UNDEFINED_GPIO { 256 }; - - explicit PigpiodHandler(std::vector gpioPins, QObject *parent = nullptr); - ~PigpiodHandler(); - - QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) - QElapsedTimer elapsedEventTimer; - - double clockMeasurementSlope=0.; - double clockMeasurementOffset=0.; - uint64_t gpioTickOverflowCounter=0; - quint64 lastTimeMeasurementTick=0; - - bool isInhibited() const { return inhibit; } - + enum PinBias : std::uint8_t { + BiasDisabled = 0x00, + PullDown = 0x01, + PullUp = 0x02, + ActiveLow = 0x04, + OpenDrain = 0x08, + OpenSource = 0x10 + }; + enum class EventEdge { + RisingEdge, + FallingEdge, + BothEdges + }; + + static constexpr unsigned int UNDEFINED_GPIO { 256 }; + + explicit PigpiodHandler(std::vector gpioPins, QObject* parent = nullptr); + ~PigpiodHandler(); + + QDateTime startOfProgram, lastSamplingTime; // the exact time when the program starts (Utc) + QElapsedTimer elapsedEventTimer; + + double clockMeasurementSlope = 0.; + double clockMeasurementOffset = 0.; + uint64_t gpioTickOverflowCounter = 0; + quint64 lastTimeMeasurementTick = 0; + + bool isInhibited() const { return inhibit; } + signals: - void event(unsigned int gpio_pin, EventTime timestamp); + void event(unsigned int gpio_pin, EventTime timestamp); public slots: - void start(); - void stop(); + void start(); + void stop(); bool initialised(); bool setPinInput(unsigned int gpio); bool setPinOutput(unsigned int gpio, bool initState); - - bool setPinBias(unsigned int gpio, std::uint8_t bias_flags); + + bool setPinBias(unsigned int gpio, std::uint8_t bias_flags); bool setPinState(unsigned int gpio, bool state); bool registerInterrupt(unsigned int gpio, EventEdge edge); bool unRegisterInterrupt(unsigned int gpio); - void setInhibited(bool inh=true) { inhibit=inh; } + void setInhibited(bool inh = true) { inhibit = inh; } private: - bool isInitialised { false }; - - QTimer gpioClockTimeMeasurementTimer; - - void measureGpioClockTime(); - void reloadInterruptSettings(); - [[gnu::hot]] void eventHandler( struct gpiod_line *line ); - [[gnu::hot]] void processEvent( unsigned int gpio, std::shared_ptr line_event ); - - bool inhibit { false }; - int verbose { 0 }; - gpiod_chip* fChip { nullptr }; - std::map fInterruptLineMap { }; - std::map fLineMap { }; - bool fThreadRunning { false }; - std::map> fThreads { }; - std::mutex fMutex; -}; + bool isInitialised { false }; + + QTimer gpioClockTimeMeasurementTimer; + void measureGpioClockTime(); + void reloadInterruptSettings(); + [[gnu::hot]] void eventHandler(struct gpiod_line* line); + [[gnu::hot]] void processEvent(unsigned int gpio, std::shared_ptr line_event); + + bool inhibit { false }; + int verbose { 0 }; + gpiod_chip* fChip { nullptr }; + std::map fInterruptLineMap {}; + std::map fLineMap {}; + bool fThreadRunning { false }; + std::map> fThreads {}; + std::mutex fMutex; +}; #endif // PIGPIODHANDLER_H diff --git a/daemon/include/utility/gpio_mapping.h b/daemon/include/utility/gpio_mapping.h index e0742fbe..2f3e25bc 100644 --- a/daemon/include/utility/gpio_mapping.h +++ b/daemon/include/utility/gpio_mapping.h @@ -5,7 +5,6 @@ #define MAX_HW_VER 3 - // Mapping between signals of the MuonPi hardware interface and the actual GPIO pins of the RaspberryPi // ATTENTION: // All pins are numbered according to the BCM designation @@ -26,12 +25,10 @@ static const std::map GPIO_PINMAP_VERSIONS[MAX_HW_VER { STATUS1, 13 }, { STATUS2, 19 }, { STATUS3, 26 }, - { TDC_INTB, 24 }, - { TDC_STATUS, 25 }, - { EXT_TRIGGER, 16 } - } , - { - /* Pin mapping, HW Version 2 */ + { TDC_INTB, 24 }, + { TDC_STATUS, 25 }, + { EXT_TRIGGER, 16 } }, + { /* Pin mapping, HW Version 2 */ { UBIAS_EN, 26 }, { PREAMP_1, 4 }, { PREAMP_2, 17 }, @@ -72,8 +69,10 @@ extern std::map GPIO_PINMAP; inline GPIO_SIGNAL bcmToGpioSignal(unsigned int bcmGpioNumber) { std::map::const_iterator i = GPIO_PINMAP.cbegin(); - while (i != GPIO_PINMAP.cend() && i->second!=bcmGpioNumber) ++i; - if (i==GPIO_PINMAP.cend()) return UNDEFINED_SIGNAL; + while (i != GPIO_PINMAP.cend() && i->second != bcmGpioNumber) + ++i; + if (i == GPIO_PINMAP.cend()) + return UNDEFINED_SIGNAL; return i->first; } diff --git a/daemon/include/utility/ratebuffer.h b/daemon/include/utility/ratebuffer.h index 63d5a42e..a62f4081 100644 --- a/daemon/include/utility/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -1,15 +1,15 @@ #ifndef RATEBUFFER_H #define RATEBUFFER_H +#include #include #include #include -#include -#include #include -#include -#include #include +#include #include +#include +#include class PigpiodHandler; @@ -18,46 +18,44 @@ using namespace std::literals; constexpr double MAX_AVG_RATE { 100. }; constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; -constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6/MAX_AVG_RATE) }; +constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6 / MAX_AVG_RATE) }; -class RateBuffer : public QObject -{ - Q_OBJECT +class RateBuffer : public QObject { + Q_OBJECT public: - struct BufferItem { - std::queue< EventTime, std::list > eventbuffer { }; - std::chrono::microseconds current_deadtime { 0 }; - std::chrono::nanoseconds last_interval { 0 }; - }; + struct BufferItem { + std::queue> eventbuffer {}; + std::chrono::microseconds current_deadtime { 0 }; + std::chrono::nanoseconds last_interval { 0 }; + }; - RateBuffer(QObject *parent = nullptr); + RateBuffer(QObject* parent = nullptr); ~RateBuffer() = default; - void setRateLimit( double max_cps ); - [[nodiscard]] auto currentRateLimit() const -> double { return fRateLimit; } - void clear() { buffermap.clear(); } - - [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; - [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; - [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; - [[nodiscard]] auto lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds; - [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> EventTime; - + void setRateLimit(double max_cps); + [[nodiscard]] auto currentRateLimit() const -> double { return fRateLimit; } + void clear() { buffermap.clear(); } + + [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; + [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; + [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; + [[nodiscard]] auto lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds; + [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> EventTime; + signals: - void filteredEvent( unsigned int gpio, EventTime event_time ); - void eventIntervalSignal( unsigned int gpio, std::chrono::nanoseconds ns ); - + void filteredEvent(unsigned int gpio, EventTime event_time); + void eventIntervalSignal(unsigned int gpio, std::chrono::nanoseconds ns); + public slots: - void onEvent(unsigned int gpio, EventTime event_time ); + void onEvent(unsigned int gpio, EventTime event_time); private: - double fRateLimit { MAX_AVG_RATE }; - std::chrono::microseconds fBufferTime { MAX_BUFFER_TIME }; - std::map buffermap { }; - std::map, std::chrono::nanoseconds> fIntervalMap { }; - - void updateAllIntervals( unsigned int new_gpio, EventTime new_event_time ); - + double fRateLimit { MAX_AVG_RATE }; + std::chrono::microseconds fBufferTime { MAX_BUFFER_TIME }; + std::map buffermap {}; + std::map, std::chrono::nanoseconds> fIntervalMap {}; + + void updateAllIntervals(unsigned int new_gpio, EventTime new_event_time); }; #endif // RATEBUFFER_H diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp index 7badd88e..a62c8c78 100644 --- a/daemon/src/daemon.cpp +++ b/daemon/src/daemon.cpp @@ -193,9 +193,9 @@ Daemon::Daemon(configuration cfg, QObject* parent) qRegisterMetaType("GnssMonHw2Struct"); qRegisterMetaType("UbxTimeMarkStruct"); qRegisterMetaType("I2cDeviceEntry"); - qRegisterMetaType("ADC_SAMPLING_MODE"); - qRegisterMetaType("PigpiodHandler::EventEdge"); - qRegisterMetaType("EventTime"); + qRegisterMetaType("ADC_SAMPLING_MODE"); + qRegisterMetaType("PigpiodHandler::EventEdge"); + qRegisterMetaType("EventTime"); qRegisterMetaType("MuonPi::Version::Version"); qRegisterMetaType("UbxDynamicModel"); @@ -640,38 +640,35 @@ Daemon::Daemon(configuration cfg, QObject* parent) // create network discovery service networkDiscovery = new NetworkDiscovery(NetworkDiscovery::DeviceType::DAEMON, peerPort, this); - // set up histograms + // set up histograms setupHistos(); // connect to the pigpio daemon interface for gpio control connectToPigpiod(); - // set up the rate buffer for all GPIO signals - rateBuffer.clear(); - connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); - -// connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if ( m_histo_map.find("gpioEventInterval") != m_histo_map.end() - && ( GPIO_PINMAP[config.eventTrigger] == gpio ) ) - { - m_histo_map["gpioEventInterval"]->fill( 1e-6 * ns.count() ); + // set up the rate buffer for all GPIO signals + rateBuffer.clear(); + connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); + connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); + + // connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) + connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) { + if (m_histo_map.find("gpioEventInterval") != m_histo_map.end() + && (GPIO_PINMAP[config.eventTrigger] == gpio)) { + m_histo_map["gpioEventInterval"]->fill(1e-6 * ns.count()); } - } ); + }); connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) -// connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if ( m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end() ) - { - if ( nsecs/1000 <= m_histo_map["gpioEventIntervalShort"]->getMax() ) { - m_histo_map["gpioEventIntervalShort"]->fill( 1e-3 * nsecs ); - } - } - } ); + // connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if (m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end()) { + if (nsecs / 1000 <= m_histo_map["gpioEventIntervalShort"]->getMax()) { + m_histo_map["gpioEventIntervalShort"]->fill(1e-3 * nsecs); + } + } + }); // establish ublox gnss module connection connectToGps(); @@ -768,13 +765,14 @@ Daemon::~Daemon() } } -void Daemon::connectToPigpiod(){ -/* +void Daemon::connectToPigpiod() +{ + /* const QVector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], GPIO_PINMAP[TIMEPULSE], GPIO_PINMAP[EXT_TRIGGER] }); */ - const std::vector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], - GPIO_PINMAP[TIMEPULSE] }); + const std::vector gpio_pins({ GPIO_PINMAP[EVT_AND], GPIO_PINMAP[EVT_XOR], + GPIO_PINMAP[TIMEPULSE] }); pigHandler = new PigpiodHandler(gpio_pins); pigThread = new QThread(); pigThread->setObjectName("muondetector-daemon-pigpio"); @@ -787,9 +785,9 @@ void Daemon::connectToPigpiod(){ connect(pigThread, &QThread::finished, pigHandler, &PigpiodHandler::deleteLater); connect(this, &Daemon::GpioSetOutput, pigHandler, &PigpiodHandler::setPinOutput); connect(this, &Daemon::GpioSetInput, pigHandler, &PigpiodHandler::setPinInput); -// connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); -// connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); - connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState ); + // connect(this, &Daemon::GpioSetPullUp, pigHandler, &PigpiodHandler::setPullUp); + // connect(this, &Daemon::GpioSetPullDown, pigHandler, &PigpiodHandler::setPullDown); + connect(this, &Daemon::GpioSetState, pigHandler, &PigpiodHandler::setPinState); connect(this, &Daemon::GpioRegisterForCallback, pigHandler, &PigpiodHandler::registerInterrupt); //connect(pigHandler, &PigpiodHandler::signal, this, &Daemon::sendGpioPinEvent); struct timespec ts_res; @@ -801,7 +799,7 @@ void Daemon::connectToPigpiod(){ timespec_get(&lastRateInterval, TIME_UTC); startOfProgram = lastRateInterval; - pigThread->start(); + pigThread->start(); rateBufferReminder.setInterval(rateBufferInterval); rateBufferReminder.setSingleShot(false); connect(&rateBufferReminder, &QTimer::timeout, this, &Daemon::onRateBufferReminder); @@ -820,12 +818,12 @@ void Daemon::connectToPigpiod(){ emit GpioSetState(GPIO_PINMAP[STATUS2], 0); emit GpioSetPullUp(GPIO_PINMAP[ADC_READY]); //emit GpioRegisterForCallback(GPIO_PINMAP[ADC_READY], PigpiodHandler::EventEdge::RisingEdge); - auto it=GPIO_PINMAP.find(config.eventTrigger); - if (it != GPIO_PINMAP.end()) { -// pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); - emit GpioRegisterForCallback(GPIO_PINMAP[config.eventTrigger], PigpiodHandler::EventEdge::RisingEdge); - } -// connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); + auto it = GPIO_PINMAP.find(config.eventTrigger); + if (it != GPIO_PINMAP.end()) { + // pigHandler->setSamplingTriggerSignal( GPIO_PINMAP[eventTrigger] ); + emit GpioRegisterForCallback(GPIO_PINMAP[config.eventTrigger], PigpiodHandler::EventEdge::RisingEdge); + } + // connect(this, &Daemon::setSamplingTriggerSignal, pigHandler, &PigpiodHandler::setSamplingTriggerSignal); if (MuonPi::Version::hardware.major > 1) { //emit GpioSetInput(GPIO_PINMAP[PREAMP_FAULT]); @@ -1398,73 +1396,73 @@ void Daemon::sendDacReadbackValue(uint8_t channel, float voltage) emit sendTcpMessage(tcpMessage); } -void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) { +void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) +{ // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) - { return item.second == gpio; } - ); + auto result = std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second == gpio; }); if (result != GPIO_PINMAP.end()) { - if ( result->first == TIMEPULSE) { - auto usecs = std::chrono::duration_cast(event_time.time_since_epoch()).count(); - usecs = usecs % 1000000LL; - if ( usecs > 500000L ) { - usecs -= 1000000LL; - } - if (m_histo_map.find("TPTimeDiff") != m_histo_map.end()) { - m_histo_map["TPTimeDiff"]->fill((double)usecs); - } - if (verbose>2) qDebug()<<"TP time diff:"<first == EVT_XOR || result->first == EVT_AND ) { - rateCounterIntervalActualisation(); - if ( result->first == EVT_XOR ) { - xorCounts.back()++; - } else if ( result->first == EVT_AND ) { - andCounts.back()++; - } + if (result->first == TIMEPULSE) { + auto usecs = std::chrono::duration_cast(event_time.time_since_epoch()).count(); + usecs = usecs % 1000000LL; + if (usecs > 500000L) { + usecs -= 1000000LL; + } + if (m_histo_map.find("TPTimeDiff") != m_histo_map.end()) { + m_histo_map["TPTimeDiff"]->fill((double)usecs); + } + if (verbose > 2) + qDebug() << "TP time diff:" << usecs << "us"; + } else if (result->first == EVT_XOR || result->first == EVT_AND) { + rateCounterIntervalActualisation(); + if (result->first == EVT_XOR) { + xorCounts.back()++; + } else if (result->first == EVT_AND) { + andCounts.back()++; + } } - if ( result->first == config.eventTrigger ) { - /* + if (result->first == config.eventTrigger) { + /* auto nsecs = rateBuffer.lastInterval(gpio).count(); if ( nsecs > 0 ) { emit eventInterval( rateBuffer.lastInterval(gpio).count() ); } */ - emit sampleAdc0Event(); - } - - if ( result->first == TIME_MEAS_OUT ) { - auto start_gpio = GPIO_PINMAP.find(config.eventTrigger); - if ( start_gpio != GPIO_PINMAP.end() ) { - long long nsecs { 0 }; - if ( result->first != config.eventTrigger ) { - nsecs = rateBuffer.lastInterval( gpio, start_gpio->second ).count(); - if ( nsecs < 0 ) nsecs = rateBuffer.lastInterval( start_gpio->second, gpio ).count(); - } else { - nsecs = rateBuffer.lastInterval( gpio ).count(); - } - if ( nsecs > 0 ) { - //emit eventInterval( nsecs ); - if ( nsecs < 100000L ) { - emit eventInterval( nsecs ); - } - } else { - } - } - onStatusLed2Event( 10 ); - } + emit sampleAdc0Event(); + } + + if (result->first == TIME_MEAS_OUT) { + auto start_gpio = GPIO_PINMAP.find(config.eventTrigger); + if (start_gpio != GPIO_PINMAP.end()) { + long long nsecs { 0 }; + if (result->first != config.eventTrigger) { + nsecs = rateBuffer.lastInterval(gpio, start_gpio->second).count(); + if (nsecs < 0) + nsecs = rateBuffer.lastInterval(start_gpio->second, gpio).count(); + } else { + nsecs = rateBuffer.lastInterval(gpio).count(); + } + if (nsecs > 0) { + //emit eventInterval( nsecs ); + if (nsecs < 100000L) { + emit eventInterval(nsecs); + } + } else { + } + } + onStatusLed2Event(10); + } } } -void Daemon::sendGpioPinEvent(unsigned int gpio, EventTime event_time) { +void Daemon::sendGpioPinEvent(unsigned int gpio, EventTime event_time) +{ // reverse lookup of gpio function from given pin (first occurence) - auto result=std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) - { return item.second==gpio; } - ); + auto result = std::find_if(GPIO_PINMAP.begin(), GPIO_PINMAP.end(), [&gpio](const std::pair& item) { return item.second == gpio; }); if (result != GPIO_PINMAP.end()) { - TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); - *(tcpMessage.dStream) << (GPIO_SIGNAL)result->first; - emit sendTcpMessage(tcpMessage); - } + TcpMessage tcpMessage(TCP_MSG_KEY::MSG_GPIO_EVENT); + *(tcpMessage.dStream) << (GPIO_SIGNAL)result->first; + emit sendTcpMessage(tcpMessage); + } } void Daemon::sendBiasVoltage() @@ -1747,9 +1745,9 @@ void Daemon::setEventTriggerSelection(GPIO_SIGNAL signal) if (verbose > 0) { qInfo() << "changed event selection to signal" << QString::fromStdString(GPIO_SIGNAL_MAP.at(signal).name); } - emit GpioRegisterForCallback( it->second, PigpiodHandler::EventEdge::RisingEdge ); - config.eventTrigger = signal; - emit logParameter(LogParameter("gpioTriggerSelection", "0x"+QString::number((int)signal,16), LogParameter::LOG_EVERY)); + emit GpioRegisterForCallback(it->second, PigpiodHandler::EventEdge::RisingEdge); + config.eventTrigger = signal; + emit logParameter(LogParameter("gpioTriggerSelection", "0x" + QString::number((int)signal, 16), LogParameter::LOG_EVERY)); } // ALL FUNCTIONS ABOUT SETTINGS FOR THE I2C-DEVICES (DAC, ADC, PCA...) @@ -2498,20 +2496,20 @@ void Daemon::onLogParameterPolled() emit logParameter(LogParameter("systemFreeSwap", QString::number(1e-6 * info.freeswap / info.mem_unit) + " Mb", LogParameter::LOG_AVERAGE)); emit logParameter(LogParameter("systemLoadAvg", QString::number(info.loads[0] * f_load) + " ", LogParameter::LOG_AVERAGE)); } - + // rate buffer debug output - if ( verbose > 2 ) { + if (verbose > 2) { qDebug() << "GPIO Rate Summary:"; - for (auto signalIt=GPIO_PINMAP.begin(); signalIt!=GPIO_PINMAP.end(); signalIt++) { - const GPIO_SIGNAL signalId=signalIt->first; - if (GPIO_SIGNAL_MAP.at(signalId).direction == DIR_IN ) { - qDebug()<second - <<"rate:"<second )<<"Hz" - <<"deadtime"<second ).count()<<"us"; - } + for (auto signalIt = GPIO_PINMAP.begin(); signalIt != GPIO_PINMAP.end(); signalIt++) { + const GPIO_SIGNAL signalId = signalIt->first; + if (GPIO_SIGNAL_MAP.at(signalId).direction == DIR_IN) { + qDebug() << QString::fromStdString(GPIO_SIGNAL_MAP.at(signalId).name) + << "pin:" << signalIt->second + << "rate:" << rateBuffer.avgRate(signalIt->second) << "Hz" + << "deadtime" << rateBuffer.currentDeadtime(signalIt->second).count() << "us"; + } } - } + } } void Daemon::onUBXReceivedTimeTM2(const UbxTimeMarkStruct& tm) diff --git a/daemon/src/pigpiodhandler.cpp b/daemon/src/pigpiodhandler.cpp index 2d0d552e..fd363ac6 100644 --- a/daemon/src/pigpiodhandler.cpp +++ b/daemon/src/pigpiodhandler.cpp @@ -1,25 +1,20 @@ +#include "pigpiodhandler.h" #include "utility/gpio_mapping.h" #include #include #include #include #include -#include "utility/gpio_mapping.h" -#include "pigpiodhandler.h" #include +#include #include #include -#include -#include -#include -#include - constexpr char CONSUMER[] = "muonpi"; const std::string chipname { "/dev/gpiochip0" }; template -inline static T sqr(T x) { return x*x; } +inline static T sqr(T x) { return x * x; } /* linear regression algorithm @@ -76,335 +71,359 @@ void calcLinearCoefficients(int n, quint64* xarray, qint64* yarray, *offs = (double)(b + offsy); } - - -PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject *parent) +PigpiodHandler::PigpiodHandler(std::vector gpioPins, QObject* parent) : QObject(parent) { - startOfProgram = QDateTime::currentDateTimeUtc(); - lastSamplingTime = startOfProgram; - elapsedEventTimer.start(); - - fChip = gpiod_chip_open(chipname.c_str()); - if ( fChip == nullptr ) { - qCritical()<<"error opening gpio chip "<stop(); - for ( auto [gpio,line] : fInterruptLineMap ) { - gpiod_line_release(line); - } - for ( auto [gpio,line] : fLineMap ) { - gpiod_line_release(line); - } - if ( fChip != nullptr ) gpiod_chip_close( fChip ); +PigpiodHandler::~PigpiodHandler() +{ + this->stop(); + for (auto [gpio, line] : fInterruptLineMap) { + gpiod_line_release(line); + } + for (auto [gpio, line] : fLineMap) { + gpiod_line_release(line); + } + if (fChip != nullptr) + gpiod_chip_close(fChip); } -void PigpiodHandler::processEvent( unsigned int gpio, std::shared_ptr line_event ) +void PigpiodHandler::processEvent(unsigned int gpio, std::shared_ptr line_event) { - - std::chrono::nanoseconds since_epoch_ns(line_event->ts.tv_nsec); - since_epoch_ns += std::chrono::seconds(line_event->ts.tv_sec); - EventTime timestamp(since_epoch_ns); - emit event(gpio, timestamp); - if ( verbose > 3 ) { - qDebug()<<"line event: gpio"<event_type==GPIOD_LINE_EVENT_RISING_EDGE)?"rising":"falling") - <<" ts="<ts.tv_nsec); + since_epoch_ns += std::chrono::seconds(line_event->ts.tv_sec); + EventTime timestamp(since_epoch_ns); + emit event(gpio, timestamp); + if (verbose > 3) { + qDebug() << "line event: gpio" << gpio << " edge: " + << QString((line_event->event_type == GPIOD_LINE_EVENT_RISING_EDGE) ? "rising" : "falling") + << " ts=" << since_epoch_ns.count(); + } } -void PigpiodHandler::eventHandler( struct gpiod_line *line ) { - static const struct timespec timeout { 4ULL, 0ULL }; - while ( fThreadRunning ) { - if ( inhibit ) { - std::this_thread::sleep_for( std::chrono::milliseconds( 100 ) ); - continue; - } - - const unsigned int gpio = gpiod_line_offset( line ); - std::shared_ptr line_event { std::make_shared() }; - int ret = gpiod_line_event_wait( line, &timeout ); - if ( ret > 0 ) { - int read_result = gpiod_line_event_read( line, line_event.get() ); - if ( read_result == 0 ) { - std::thread process_event_bg( &PigpiodHandler::processEvent, this, gpio, std::move(line_event) ); - process_event_bg.detach(); - } else { - // an error occured - // what should we do here? - qCritical()<<"read gpio line event failed"; - } - } else if ( ret == 0 ) { - // a timeout occurred, no event was detected - // simply go over into the wait loop again - } else { - // an error occured - // what should we do here? - qCritical()<<"wait for gpio line event failed"; - } - } +void PigpiodHandler::eventHandler(struct gpiod_line* line) +{ + static const struct timespec timeout { + 4ULL, 0ULL + }; + while (fThreadRunning) { + if (inhibit) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + continue; + } + + const unsigned int gpio = gpiod_line_offset(line); + std::shared_ptr line_event { std::make_shared() }; + int ret = gpiod_line_event_wait(line, &timeout); + if (ret > 0) { + int read_result = gpiod_line_event_read(line, line_event.get()); + if (read_result == 0) { + std::thread process_event_bg(&PigpiodHandler::processEvent, this, gpio, std::move(line_event)); + process_event_bg.detach(); + } else { + // an error occured + // what should we do here? + qCritical() << "read gpio line event failed"; + } + } else if (ret == 0) { + // a timeout occurred, no event was detected + // simply go over into the wait loop again + } else { + // an error occured + // what should we do here? + qCritical() << "wait for gpio line event failed"; + } + } } -bool PigpiodHandler::setPinInput(unsigned int gpio) { - if (!isInitialised) return false; - auto it = fLineMap.find(gpio); - - if (it != fLineMap.end()) { - // line object exists, request for input - int ret = gpiod_line_request_input( it->second, CONSUMER ); - if ( ret < 0 ) { - qCritical()<<"Request gpio line" << gpio << "as input failed"; - return false; - } - return true; - } - // line was not allocated yet, so do it now - gpiod_line* line = gpiod_chip_get_line(fChip, gpio); - if ( line == nullptr ) { - qCritical()<<"error allocating gpio line"<second, CONSUMER); + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "as input failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); + if (line == nullptr) { + qCritical() << "error allocating gpio line" << gpio; + return false; + } + int ret = gpiod_line_request_input(line, CONSUMER); + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "as input failed"; + return false; + } + fLineMap.emplace(std::make_pair(gpio, line)); + return true; } -bool PigpiodHandler::setPinOutput(unsigned int gpio, bool initState) { - if (!isInitialised) return false; - auto it = fLineMap.find(gpio); - - if (it != fLineMap.end()) { - // line object exists, request for output - int ret = gpiod_line_request_output( it->second, CONSUMER, static_cast(initState) ); - if ( ret < 0 ) { - qCritical()<<"Request gpio line" << gpio << "as output failed"; - return false; - } - return true; - } - // line was not allocated yet, so do it now - gpiod_line* line = gpiod_chip_get_line(fChip, gpio); - if ( line == nullptr ) { - qCritical()<<"error allocating gpio line"<(initState) ); - if ( ret < 0 ) { - qCritical()<<"Request gpio line" << gpio << "as output failed"; - return false; - } - fLineMap.emplace( std::make_pair( gpio, line ) ); - return true; +bool PigpiodHandler::setPinOutput(unsigned int gpio, bool initState) +{ + if (!isInitialised) + return false; + auto it = fLineMap.find(gpio); + + if (it != fLineMap.end()) { + // line object exists, request for output + int ret = gpiod_line_request_output(it->second, CONSUMER, static_cast(initState)); + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "as output failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); + if (line == nullptr) { + qCritical() << "error allocating gpio line" << gpio; + return false; + } + int ret = gpiod_line_request_output(line, CONSUMER, static_cast(initState)); + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "as output failed"; + return false; + } + fLineMap.emplace(std::make_pair(gpio, line)); + return true; } -bool PigpiodHandler::setPinBias(unsigned int gpio, std::uint8_t bias_flags) { - if (!isInitialised) return false; - int flags = 0; - if ( bias_flags & PinBias::OpenDrain ) { - flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_DRAIN; - } else if ( bias_flags & PinBias::OpenSource ) { - flags |= GPIOD_LINE_REQUEST_FLAG_OPEN_SOURCE; - } else if ( bias_flags & PinBias::ActiveLow ) { - flags |= GPIOD_LINE_REQUEST_FLAG_ACTIVE_LOW; - } else if ( bias_flags & PinBias::PullDown ) { - //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_DOWN; - } else if ( bias_flags & PinBias::PullUp ) { - //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_PULL_UP; - } else if ( !(bias_flags & PinBias::PullDown) && !(bias_flags & PinBias::PullUp) ) { - //flags |= GPIOD_LINE_REQUEST_FLAG_BIAS_DISABLED; - } - - auto it = fLineMap.find(gpio); - int dir = -1; - if (it != fLineMap.end()) { - // line object exists, set config - dir = gpiod_line_direction(it->second); - gpiod_line_release(it->second); - fLineMap.erase( it ); - } - // line was not allocated yet, so do it now - gpiod_line* line = gpiod_chip_get_line(fChip, gpio); - if ( line == nullptr ) { - qCritical()<<"error allocating gpio line"<second); + gpiod_line_release(it->second); + fLineMap.erase(it); + } + // line was not allocated yet, so do it now + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); + if (line == nullptr) { + qCritical() << "error allocating gpio line" << gpio; + return false; + } + int req_mode = GPIOD_LINE_REQUEST_DIRECTION_AS_IS; + if (dir == GPIOD_LINE_DIRECTION_INPUT) + req_mode = GPIOD_LINE_REQUEST_DIRECTION_INPUT; + else if (dir == GPIOD_LINE_DIRECTION_OUTPUT) + req_mode = GPIOD_LINE_REQUEST_DIRECTION_OUTPUT; + gpiod_line_request_config config { CONSUMER, req_mode, flags }; + int ret = gpiod_line_request(line, &config, 0); + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "for bias config failed"; + return false; + } + fLineMap.emplace(std::make_pair(gpio, line)); + return true; } -bool PigpiodHandler::setPinState(unsigned int gpio, bool state) { - if (!isInitialised) return false; - auto it = fLineMap.find(gpio); - if (it != fLineMap.end()) { - // line object exists, request for output - int ret = gpiod_line_set_value( it->second, static_cast(state) ); - if ( ret < 0 ) { - qCritical()<<"Setting state of gpio line" << gpio << "failed"; - return false; - } - return true; - } - // line was not allocated yet, so do it now - return setPinOutput( gpio, state ); +bool PigpiodHandler::setPinState(unsigned int gpio, bool state) +{ + if (!isInitialised) + return false; + auto it = fLineMap.find(gpio); + if (it != fLineMap.end()) { + // line object exists, request for output + int ret = gpiod_line_set_value(it->second, static_cast(state)); + if (ret < 0) { + qCritical() << "Setting state of gpio line" << gpio << "failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + return setPinOutput(gpio, state); } void PigpiodHandler::reloadInterruptSettings() { - this->stop(); - this->start(); + this->stop(); + this->start(); } -bool PigpiodHandler::registerInterrupt(unsigned int gpio, EventEdge edge) { - if (!isInitialised) return false; - auto it = fInterruptLineMap.find(gpio); - if (it != fInterruptLineMap.end()) { - // line object exists - // The following code block shall release the previous line request - // and re-request this line for events. - // It is bypassed, since it does not work as intended. - // The function simply does nothing in this case. - return false; - //stop(); - //gpiod_line_release(it->second); - if ( gpiod_line_update(it->second) < 0 ) { - qCritical()<<"update of gpio line" << gpio << "after release failed"; - //return false; - } - // request for events - int ret=-1; - int errcnt = 10; - while ( errcnt && ret < 0 ) { - switch (edge) { - case EventEdge::RisingEdge: - ret = gpiod_line_request_rising_edge_events( it->second, CONSUMER ); - break; - case EventEdge::FallingEdge: - ret = gpiod_line_request_falling_edge_events( it->second, CONSUMER ); - break; - case EventEdge::BothEdges: - ret = gpiod_line_request_both_edges_events( it->second, CONSUMER ); - default: - break; - } - errcnt--; - if ( ret < 0 ) std::this_thread::sleep_for( std::chrono::milliseconds( 1 ) ); - - } - if ( ret < 0 ) { - qCritical()<<"Re-request gpio line" << gpio << "for events failed"; - return false; - } - return true; - } - // line was not allocated yet, so do it now - gpiod_line* line = gpiod_chip_get_line(fChip, gpio); - if ( line == nullptr ) { - qCritical()<<"error allocating gpio line"<second); + if (gpiod_line_update(it->second) < 0) { + qCritical() << "update of gpio line" << gpio << "after release failed"; + //return false; + } + // request for events + int ret = -1; + int errcnt = 10; + while (errcnt && ret < 0) { + switch (edge) { + case EventEdge::RisingEdge: + ret = gpiod_line_request_rising_edge_events(it->second, CONSUMER); + break; + case EventEdge::FallingEdge: + ret = gpiod_line_request_falling_edge_events(it->second, CONSUMER); + break; + case EventEdge::BothEdges: + ret = gpiod_line_request_both_edges_events(it->second, CONSUMER); + default: + break; + } + errcnt--; + if (ret < 0) + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } + if (ret < 0) { + qCritical() << "Re-request gpio line" << gpio << "for events failed"; + return false; + } + return true; + } + // line was not allocated yet, so do it now + gpiod_line* line = gpiod_chip_get_line(fChip, gpio); + if (line == nullptr) { + qCritical() << "error allocating gpio line" << gpio; + return false; + } + int ret = -1; + switch (edge) { + case EventEdge::RisingEdge: + ret = gpiod_line_request_rising_edge_events(line, CONSUMER); + break; + case EventEdge::FallingEdge: + ret = gpiod_line_request_falling_edge_events(line, CONSUMER); + break; + case EventEdge::BothEdges: + ret = gpiod_line_request_both_edges_events(line, CONSUMER); + default: + break; + } + if (ret < 0) { + qCritical() << "Request gpio line" << gpio << "for events failed"; + return false; + } + fInterruptLineMap.emplace(std::make_pair(gpio, line)); + reloadInterruptSettings(); + return true; } -bool PigpiodHandler::unRegisterInterrupt(unsigned int gpio) { - if (!isInitialised) return false; - auto it = fInterruptLineMap.find(gpio); - if (it != fInterruptLineMap.end()) { - gpiod_line_release(it->second); - fInterruptLineMap.erase( it ); - reloadInterruptSettings(); - return true; - } - return false; +bool PigpiodHandler::unRegisterInterrupt(unsigned int gpio) +{ + if (!isInitialised) + return false; + auto it = fInterruptLineMap.find(gpio); + if (it != fInterruptLineMap.end()) { + gpiod_line_release(it->second); + fInterruptLineMap.erase(it); + reloadInterruptSettings(); + return true; + } + return false; } -bool PigpiodHandler::initialised(){ +bool PigpiodHandler::initialised() +{ return isInitialised; } -void PigpiodHandler::stop() { - fThreadRunning = false; - for ( auto &[ gpio, line_thread ] : fThreads ) { - if ( line_thread ) line_thread->join(); - } +void PigpiodHandler::stop() +{ + fThreadRunning = false; + for (auto& [gpio, line_thread] : fThreads) { + if (line_thread) + line_thread->join(); + } } -void PigpiodHandler::start() { - if (fThreadRunning) return; - fThreadRunning = true; +void PigpiodHandler::start() +{ + if (fThreadRunning) + return; + fThreadRunning = true; - for ( auto &[ gpio, line ] : fInterruptLineMap ) { - fThreads[ gpio ] = std::make_unique( [this, gpio, line](){ this->eventHandler( line ); } ); - } + for (auto& [gpio, line] : fInterruptLineMap) { + fThreads[gpio] = std::make_unique([this, gpio, line]() { this->eventHandler(line); }); + } } -void PigpiodHandler::measureGpioClockTime() { - if (!isInitialised) return; +void PigpiodHandler::measureGpioClockTime() +{ + if (!isInitialised) + return; static uint32_t oldTick = 0; -// static uint64_t llTick = 0; - const int N = MuonPi::Config::Hardware::GPIO::Clock::Measurement::buffer_size/*GPIO_CLOCK_MEASUREMENT_BUFFER_SIZE*/; - static int nrSamples=0; - static int arrayIndex=0; + // static uint64_t llTick = 0; + const int N = MuonPi::Config::Hardware::GPIO::Clock::Measurement::buffer_size /*GPIO_CLOCK_MEASUREMENT_BUFFER_SIZE*/; + static int nrSamples = 0; + static int arrayIndex = 0; static qint64 diff_array[N]; static quint64 tick_array[N]; struct timespec tp, tp1, tp2; @@ -412,32 +431,32 @@ void PigpiodHandler::measureGpioClockTime() { quint64 t0 = startOfProgram.toMSecsSinceEpoch(); clock_gettime(CLOCK_REALTIME, &tp1); -/// uint32_t tick = get_current_tick(pi); + /// uint32_t tick = get_current_tick(pi); uint32_t tick = 0; clock_gettime(CLOCK_REALTIME, &tp2); -// clock_gettime(CLOCK_MONOTONIC, &tp); + // clock_gettime(CLOCK_MONOTONIC, &tp); - qint64 dt = tp2.tv_sec-tp1.tv_sec; + qint64 dt = tp2.tv_sec - tp1.tv_sec; dt *= 1000000000LL; - dt += (tp2.tv_nsec-tp1.tv_nsec); + dt += (tp2.tv_nsec - tp1.tv_nsec); dt /= 2000; tp = tp1; - if (tick=N) { - arrayIndex=0; + oldTick = tick; + quint64 nr_usecs = ((quint64)tp.tv_sec * 1000 - t0) * 1000; + nr_usecs += tp.tv_nsec / 1000 + dt; + diff_array[arrayIndex] = (qint64)(nr_usecs - gpioTickOverflowCounter) - tick; + tick_array[arrayIndex] = (quint64)gpioTickOverflowCounter + tick; + lastTimeMeasurementTick = (quint64)gpioTickOverflowCounter + tick; + if (++arrayIndex >= N) { + arrayIndex = 0; } - if (nrSamples 10 ) { - buffermap[gpio].current_deadtime -= std::chrono::microseconds( 10 ); - } else if ( deadtime > 0 ) { - buffermap[gpio].current_deadtime -= std::chrono::microseconds( 1 ); - } - } - } - buffermap[gpio].eventbuffer.push(event_time); - emit filteredEvent(gpio, event_time); - if ( buffermap[gpio].last_interval != std::chrono::nanoseconds(0) ) { - emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); - } + if (!buffermap[gpio].eventbuffer.empty()) { + auto last_event_time = buffermap[gpio].eventbuffer.back(); + buffermap[gpio].last_interval = std::chrono::duration_cast(event_time - last_event_time); + if (event_time - last_event_time < MAX_DEADTIME) { + // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< 10) { + buffermap[gpio].current_deadtime -= std::chrono::microseconds(10); + } else if (deadtime > 0) { + buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); + } + } + } + buffermap[gpio].eventbuffer.push(event_time); + emit filteredEvent(gpio, event_time); + if (buffermap[gpio].last_interval != std::chrono::nanoseconds(0)) { + emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); + } } auto RateBuffer::avgRate(unsigned int gpio) const -> double { - auto it = buffermap.find(gpio); - if ( it == buffermap.end() ) return 0.; - if ( it->second.eventbuffer.empty() ) return 0.; - auto end = std::chrono::system_clock::now(); - auto start = end - fBufferTime; - if ( start > it->second.eventbuffer.front() ) start = it->second.eventbuffer.front(); - double span = 1e-6 * std::chrono::duration_cast(end - start).count(); - return ( it->second.eventbuffer.size() / span ); + auto it = buffermap.find(gpio); + if (it == buffermap.end()) + return 0.; + if (it->second.eventbuffer.empty()) + return 0.; + auto end = std::chrono::system_clock::now(); + auto start = end - fBufferTime; + if (start > it->second.eventbuffer.front()) + start = it->second.eventbuffer.front(); + double span = 1e-6 * std::chrono::duration_cast(end - start).count(); + return (it->second.eventbuffer.size() / span); } auto RateBuffer::currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds { - auto it = buffermap.find(gpio); - if ( it == buffermap.end() ) return std::chrono::microseconds(0); - return it->second.current_deadtime; + auto it = buffermap.find(gpio); + if (it == buffermap.end()) + return std::chrono::microseconds(0); + return it->second.current_deadtime; } auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds { - auto it = buffermap.find(gpio); - if ( it == buffermap.end() || it->second.eventbuffer.size() < 2 ) return std::chrono::nanoseconds(0); - return it->second.last_interval; + auto it = buffermap.find(gpio); + if (it == buffermap.end() || it->second.eventbuffer.size() < 2) + return std::chrono::nanoseconds(0); + return it->second.last_interval; } auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds { - auto it = fIntervalMap.find( std::make_pair( gpio1, gpio2 ) ); - if ( it == fIntervalMap.end() ) return std::chrono::nanoseconds(0); - return fIntervalMap.at( std::make_pair( gpio1, gpio2 ) ); + auto it = fIntervalMap.find(std::make_pair(gpio1, gpio2)); + if (it == fIntervalMap.end()) + return std::chrono::nanoseconds(0); + return fIntervalMap.at(std::make_pair(gpio1, gpio2)); } auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime { - auto it = buffermap.find(gpio); - if ( it == buffermap.end() || it->second.eventbuffer.empty() ) return invalid_time; - return it->second.eventbuffer.back(); + auto it = buffermap.find(gpio); + if (it == buffermap.end() || it->second.eventbuffer.empty()) + return invalid_time; + return it->second.eventbuffer.back(); } - diff --git a/library/include/gpio_pin_definitions.h b/library/include/gpio_pin_definitions.h index c855c2c1..507c73a6 100644 --- a/library/include/gpio_pin_definitions.h +++ b/library/include/gpio_pin_definitions.h @@ -62,8 +62,7 @@ static const std::map GPIO_SIGNAL_MAP = { { U { TDC_STATUS, { "TDC_STATUS", DIR_OUT } }, { IN_POL1, { "IN_POL1", DIR_OUT } }, { IN_POL2, { "IN_POL2", DIR_OUT } }, - { UNDEFINED_SIGNAL, { "UNDEFINED_SIGNAL", DIR_UNDEFINED} } - }; + { UNDEFINED_SIGNAL, { "UNDEFINED_SIGNAL", DIR_UNDEFINED } } }; enum class TIMING_MUX_SELECTION : uint8_t { AND = 0, diff --git a/library/include/muondetector_structs.h b/library/include/muondetector_structs.h index 734869e8..67947288 100644 --- a/library/include/muondetector_structs.h +++ b/library/include/muondetector_structs.h @@ -13,13 +13,13 @@ #include #include #include +#include #include #include #include #include #include #include -#include using EventTime = std::chrono::time_point; From e2521c434e074e26cd7d23357d8d6200dca56eee Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 19 Feb 2023 21:01:11 +0100 Subject: [PATCH 42/47] added constant with deadtime increment and increased this value to 50us --- daemon/include/utility/ratebuffer.h | 2 ++ daemon/src/utility/ratebuffer.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/daemon/include/utility/ratebuffer.h b/daemon/include/utility/ratebuffer.h index a62f4081..5c6a470e 100644 --- a/daemon/include/utility/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -19,6 +19,8 @@ constexpr double MAX_AVG_RATE { 100. }; constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6 / MAX_AVG_RATE) }; +constexpr std::chrono::microseconds DEADTIME_INCREMENT { 50 }; + class RateBuffer : public QObject { Q_OBJECT diff --git a/daemon/src/utility/ratebuffer.cpp b/daemon/src/utility/ratebuffer.cpp index d865c349..f0335bbc 100644 --- a/daemon/src/utility/ratebuffer.cpp +++ b/daemon/src/utility/ratebuffer.cpp @@ -46,7 +46,7 @@ void RateBuffer::onEvent(unsigned int gpio, EventTime event_time) if (event_time - last_event_time < MAX_DEADTIME) { // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< 10) { - buffermap[gpio].current_deadtime -= std::chrono::microseconds(10); - } else if (deadtime > 0) { + auto deadtime = buffermap[gpio].current_deadtime; + if (deadtime > DEADTIME_INCREMENT) { + buffermap[gpio].current_deadtime -= DEADTIME_INCREMENT; + } else if (deadtime > 0s) { buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); } } From c7b8ad83f852485c3bf062b6efea73f0c9bba19b Mon Sep 17 00:00:00 2001 From: hangeza Date: Sun, 19 Feb 2023 21:02:29 +0100 Subject: [PATCH 43/47] removed shadowed redeclaration --- daemon/src/utility/ratebuffer.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/daemon/src/utility/ratebuffer.cpp b/daemon/src/utility/ratebuffer.cpp index f0335bbc..93b9da3d 100644 --- a/daemon/src/utility/ratebuffer.cpp +++ b/daemon/src/utility/ratebuffer.cpp @@ -41,7 +41,6 @@ void RateBuffer::onEvent(unsigned int gpio, EventTime event_time) } if (!buffermap[gpio].eventbuffer.empty()) { - auto last_event_time = buffermap[gpio].eventbuffer.back(); buffermap[gpio].last_interval = std::chrono::duration_cast(event_time - last_event_time); if (event_time - last_event_time < MAX_DEADTIME) { // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< Date: Sun, 19 Feb 2023 21:04:48 +0100 Subject: [PATCH 44/47] removed blank line --- daemon/include/utility/ratebuffer.h | 1 - 1 file changed, 1 deletion(-) diff --git a/daemon/include/utility/ratebuffer.h b/daemon/include/utility/ratebuffer.h index 5c6a470e..f76b287f 100644 --- a/daemon/include/utility/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -21,7 +21,6 @@ constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6 / MAX_AVG_RATE) }; constexpr std::chrono::microseconds DEADTIME_INCREMENT { 50 }; - class RateBuffer : public QObject { Q_OBJECT From a2d240fde1dc389065f5c8dbbaa6629e5994db19 Mon Sep 17 00:00:00 2001 From: SimonGLM Date: Wed, 24 May 2023 21:14:04 +0200 Subject: [PATCH 45/47] Updated changelog --- daemon/config/changelog | 7 ++++++- gui/config/changelog | 4 ++-- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/daemon/config/changelog b/daemon/config/changelog index 80d11e51..847a4db6 100644 --- a/daemon/config/changelog +++ b/daemon/config/changelog @@ -3,7 +3,12 @@ muondetector-daemon (2.1.0) ; urgency=low * Bugfixes: - removed wrong QT connect call which resulted in a warning in log messages after daemon startup - fixed reconnect to MQTT broker after connection was lost temporarily - - fixed bug in I2C subsystem which lead to a stuck bus after certain read operations and preventing detection of a device in the next logical read access + - +6cecacd +May 24, 2023 +Git stats + +1,254 c * Updates: - restructured data logging system: diff --git a/gui/config/changelog b/gui/config/changelog index bef524f3..78a09cd9 100644 --- a/gui/config/changelog +++ b/gui/config/changelog @@ -1,7 +1,7 @@ muondetector-gui (2.1.0) ; urgency=low * Updates: - - Intensively improved the geographic map feature with position marker (zoom level independent), semitransparent accuracy indicator and info box with current coordinates and position accuracy. + - Extended the geographic map feature with position marker (zoom level independent), semitransparent accuracy indicator and info box with current coordinates and position accuracy. - Added daemon hardware and software info under "Parameters" tab. - Added time as scan parameter in "Scans" tab. - Added display of log rotation interval and event log enable flag in "Log" tab. @@ -11,7 +11,7 @@ muondetector-gui (2.1.0) ; urgency=low - Parameters: Added daemon hardware and software information - Scans: Added time as scan parameter - Log: Added display of log rotation interval and event log enable flag - - Map: Intensively improved the geographic map + - Map: Extensively improved the geographic map - position marker (zoom level independent) - semitransparent accuracy indicator - info box with current coordinates and position accuracy From d38a9ec2e3b5d501f507bf31bb760dee5234ca89 Mon Sep 17 00:00:00 2001 From: hangeza Date: Wed, 24 May 2023 22:31:06 +0200 Subject: [PATCH 46/47] applied clang-format --- daemon/include/utility/ratebuffer.h | 51 ------------ daemon/src/daemon.cpp | 61 +++------------ daemon/src/utility/filehandler.cpp | 21 +++-- daemon/src/utility/ratebuffer.cpp | 115 ---------------------------- gui/src/mainwindow.cpp | 6 +- library/include/networkdiscovery.h | 2 +- library/src/networkdiscovery.cpp | 9 +-- 7 files changed, 28 insertions(+), 237 deletions(-) diff --git a/daemon/include/utility/ratebuffer.h b/daemon/include/utility/ratebuffer.h index 5d3d0c77..d4b49495 100644 --- a/daemon/include/utility/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -1,17 +1,7 @@ #ifndef RATEBUFFER_H #define RATEBUFFER_H -/* -//<<<<<<< HEAD -#include -#include -#include -#include -#include -//======= -*/ #include #include -//>>>>>>> dev #include #include #include @@ -26,47 +16,6 @@ constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6 / MAX_AVG_RATE) }; constexpr std::chrono::microseconds DEADTIME_INCREMENT { 50 }; -/* -//<<<<<<< HEAD -class RateBuffer : public QObject { - Q_OBJECT - -public: - struct BufferItem { - std::queue> eventbuffer {}; - std::chrono::microseconds current_deadtime { 0 }; - std::chrono::nanoseconds last_interval { 0 }; - }; - - RateBuffer(QObject* parent = nullptr); - ~RateBuffer() = default; - void setRateLimit(double max_cps); - [[nodiscard]] auto currentRateLimit() const -> double { return fRateLimit; } - void clear() { buffermap.clear(); } - - [[nodiscard]] auto avgRate(unsigned int gpio) const -> double; - [[nodiscard]] auto currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds; - [[nodiscard]] auto lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds; - [[nodiscard]] auto lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds; - [[nodiscard]] auto lastEventTime(unsigned int gpio) const -> EventTime; - -signals: - void filteredEvent(unsigned int gpio, EventTime event_time); - void eventIntervalSignal(unsigned int gpio, std::chrono::nanoseconds ns); - -public slots: - void onEvent(unsigned int gpio, EventTime event_time); - -private: - double fRateLimit { MAX_AVG_RATE }; - std::chrono::microseconds fBufferTime { MAX_BUFFER_TIME }; - std::map buffermap {}; - std::map, std::chrono::nanoseconds> fIntervalMap {}; - - void updateAllIntervals(unsigned int new_gpio, EventTime new_event_time); -//======= -*/ - class CounterRateBuffer : public QObject { Q_OBJECT diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp index 551c304e..d61d5906 100644 --- a/daemon/src/daemon.cpp +++ b/daemon/src/daemon.cpp @@ -598,33 +598,6 @@ Daemon::Daemon(configuration cfg, QObject* parent) // connect to the pigpio daemon interface for gpio control connectToPigpiod(); -/* -//<<<<<<< HEAD - // set up the rate buffer for all GPIO signals - rateBuffer.clear(); - connect(pigHandler, &PigpiodHandler::event, &rateBuffer, &RateBuffer::onEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); - connect(&rateBuffer, &RateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); - - // connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) { - if (m_histo_map.find("gpioEventInterval") != m_histo_map.end() - && (GPIO_PINMAP[config.eventTrigger] == gpio)) { - m_histo_map["gpioEventInterval"]->fill(1e-6 * ns.count()); - } - }); - - connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - // connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if (m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end()) { - if (nsecs / 1000 <= m_histo_map["gpioEventIntervalShort"]->getMax()) { - m_histo_map["gpioEventIntervalShort"]->fill(1e-3 * nsecs); - } - } - }); -//======= -*/ // set up rate buffers for all GPIO input signals for (auto [signal, pin] : GPIO_PINMAP) { if (GPIO_SIGNAL_MAP.at(signal).direction == DIR_IN) { @@ -632,11 +605,10 @@ Daemon::Daemon(configuration cfg, QObject* parent) connect(pigHandler, &PigpiodHandler::event, ratebuf.get(), &EventRateBuffer::onEvent); connect(ratebuf.get(), &EventRateBuffer::filteredEvent, this, &Daemon::sendGpioPinEvent); connect(ratebuf.get(), &EventRateBuffer::filteredEvent, this, &Daemon::onGpioPinEvent); - + connect(ratebuf.get(), &EventRateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) { if (m_histo_map.find("gpioEventInterval") != m_histo_map.end() - && (GPIO_PINMAP[config.eventTrigger] == gpio)) - { + && (GPIO_PINMAP[config.eventTrigger] == gpio)) { m_histo_map["gpioEventInterval"]->fill(1e-6 * ns.count()); } }); @@ -646,18 +618,17 @@ Daemon::Daemon(configuration cfg, QObject* parent) } connect(this, &Daemon::eventInterval, this, [this](quint64 nsecs) - // connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) - { - if (m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end()) { - if (nsecs / 1000 <= m_histo_map["gpioEventIntervalShort"]->getMax()) { - m_histo_map["gpioEventIntervalShort"]->fill(1e-3 * nsecs); + // connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) + { + if (m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end()) { + if (nsecs / 1000 <= m_histo_map["gpioEventIntervalShort"]->getMax()) { + m_histo_map["gpioEventIntervalShort"]->fill(1e-3 * nsecs); + } } - } - }); + }); // set up histograms setupHistos(); -//>>>>>>> dev // establish ublox gnss module connection connectToGps(); @@ -793,19 +764,7 @@ void Daemon::connectToPigpiod() timespec_get(&lastRateInterval, TIME_UTC); startOfProgram = lastRateInterval; -//<<<<<<< HEAD -/* -//======= - connect(pigHandler, &PigpiodHandler::signal, this, [this](uint8_t gpio_pin) { - rateCounterIntervalActualisation(); - if (gpio_pin == GPIO_PINMAP[EVT_XOR]) { - xorCounts.back()++; - } else if (gpio_pin == GPIO_PINMAP[EVT_AND]) { - andCounts.back()++; - } - }); -//>>>>>>> dev -*/ + pigThread->start(); rateBufferReminder.setInterval(rateBufferInterval); rateBufferReminder.setSingleShot(false); diff --git a/daemon/src/utility/filehandler.cpp b/daemon/src/utility/filehandler.cpp index b53a32f4..5d166ac5 100644 --- a/daemon/src/utility/filehandler.cpp +++ b/daemon/src/utility/filehandler.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include #include #include @@ -11,7 +12,6 @@ #include #include #include -#include #include #include #include @@ -327,18 +327,17 @@ bool FileHandler::rotateFiles() currentWorkingLogPath = dataFolderPath + "log_" + fileNamePart; auto currentWorkingFilePathCandidate = currentWorkingFilePath; auto currentWorkingLogPathCandidate = currentWorkingLogPath; - for (size_t i=0; i<1000ul; i++){ - if ( QFile::exists(currentWorkingFilePathCandidate) || QFile::exists(currentWorkingLogPathCandidate)){ - qDebug()<(new_event_time - last_other_time); - fIntervalMap.insert_or_assign(std::make_pair(new_gpio, other_gpio), nsecs); - } -} - -void RateBuffer::onEvent(unsigned int gpio, EventTime event_time) -{ - if (buffermap[gpio].eventbuffer.empty()) { - buffermap[gpio].eventbuffer.push(event_time); - emit filteredEvent(gpio, event_time); - return; - } - auto last_event_time = buffermap[gpio].eventbuffer.back(); - if (event_time - last_event_time < buffermap[gpio].current_deadtime) { - // buffermap[gpio].eventbuffer.push(event_time); - return; - } - updateAllIntervals(gpio, event_time); - - while (!buffermap.at(gpio).eventbuffer.empty() - && (event_time - buffermap[gpio].eventbuffer.front() > fBufferTime)) { - buffermap[gpio].eventbuffer.pop(); - } - - if (!buffermap[gpio].eventbuffer.empty()) { - buffermap[gpio].last_interval = std::chrono::duration_cast(event_time - last_event_time); - if (event_time - last_event_time < MAX_DEADTIME) { - // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< DEADTIME_INCREMENT) { - buffermap[gpio].current_deadtime -= DEADTIME_INCREMENT; - } else if (deadtime > 0s) { - buffermap[gpio].current_deadtime -= std::chrono::microseconds(1); - } - } - } - buffermap[gpio].eventbuffer.push(event_time); - emit filteredEvent(gpio, event_time); - if (buffermap[gpio].last_interval != std::chrono::nanoseconds(0)) { - emit eventIntervalSignal(gpio, buffermap[gpio].last_interval); - } -} - -auto RateBuffer::avgRate(unsigned int gpio) const -> double -{ - auto it = buffermap.find(gpio); - if (it == buffermap.end()) - return 0.; - if (it->second.eventbuffer.empty()) - return 0.; - auto end = std::chrono::system_clock::now(); - auto start = end - fBufferTime; - if (start > it->second.eventbuffer.front()) - start = it->second.eventbuffer.front(); - double span = 1e-6 * std::chrono::duration_cast(end - start).count(); - return (it->second.eventbuffer.size() / span); -} - -auto RateBuffer::currentDeadtime(unsigned int gpio) const -> std::chrono::microseconds -{ - auto it = buffermap.find(gpio); - if (it == buffermap.end()) - return std::chrono::microseconds(0); - return it->second.current_deadtime; -} - -auto RateBuffer::lastInterval(unsigned int gpio) const -> std::chrono::nanoseconds -{ - auto it = buffermap.find(gpio); - if (it == buffermap.end() || it->second.eventbuffer.size() < 2) - return std::chrono::nanoseconds(0); - return it->second.last_interval; -} - -auto RateBuffer::lastInterval(unsigned int gpio1, unsigned int gpio2) const -> std::chrono::nanoseconds -{ - auto it = fIntervalMap.find(std::make_pair(gpio1, gpio2)); - if (it == fIntervalMap.end()) - return std::chrono::nanoseconds(0); - return fIntervalMap.at(std::make_pair(gpio1, gpio2)); -} - -auto RateBuffer::lastEventTime(unsigned int gpio) const -> EventTime -{ - auto it = buffermap.find(gpio); - if (it == buffermap.end() || it->second.eventbuffer.empty()) - return invalid_time; - return it->second.eventbuffer.back(); -======= -*/ CounterRateBuffer::CounterRateBuffer(unsigned int counter_mask, QObject* parent) : QObject(parent) , m_counter_mask(counter_mask) @@ -263,5 +149,4 @@ auto EventRateBuffer::lastEventTime() const -> EventTime if (m_eventbuffer.empty()) return invalid_time; return m_eventbuffer.back(); -//>>>>>>> dev } diff --git a/gui/src/mainwindow.cpp b/gui/src/mainwindow.cpp index 233dd06d..d056a689 100644 --- a/gui/src/mainwindow.cpp +++ b/gui/src/mainwindow.cpp @@ -83,7 +83,7 @@ MainWindow::MainWindow(QWidget* parent) if (addresses == nullptr) { return; } - unsigned device_counter{}; + unsigned device_counter {}; for (auto device : devices) { // check if device is not a GUI (might show other GUIs later on) if (device.first == static_cast(NetworkDiscovery::DeviceType::GUI)) { @@ -992,8 +992,8 @@ void MainWindow::connected() void MainWindow::connection_info(const QString message) { - ui->ipStatusLabel->setStyleSheet(""); - ui->ipStatusLabel->setText(message); + ui->ipStatusLabel->setStyleSheet(""); + ui->ipStatusLabel->setText(message); } void MainWindow::connection_error(int error_code, const QString message) diff --git a/library/include/networkdiscovery.h b/library/include/networkdiscovery.h index b4f537b4..03b6089e 100644 --- a/library/include/networkdiscovery.h +++ b/library/include/networkdiscovery.h @@ -3,8 +3,8 @@ #include #include -#include #include +#include class NetworkDiscovery : public QObject { Q_OBJECT diff --git a/library/src/networkdiscovery.cpp b/library/src/networkdiscovery.cpp index 0d04ec58..8f2af40f 100644 --- a/library/src/networkdiscovery.cpp +++ b/library/src/networkdiscovery.cpp @@ -43,8 +43,7 @@ void NetworkDiscovery::searchDevices() // auto datagram = QNetworkDatagram{data,m_broadcast_address, m_port}; // datagram.setHopLimit(255); // probably overkill qDebug() << "NetworkDiscovery is an experimental feature and may or may not work!"; - for (auto address : m_broadcast_address) - { + for (auto address : m_broadcast_address) { qDebug() << "NetworkDiscovery: sending " << data << " on address " << QHostAddress(address.toIPv4Address()); socket->writeDatagram(data, address, m_port); } @@ -74,15 +73,15 @@ void NetworkDiscovery::readPendingDatagrams() if (device_type == static_cast(m_device_type)) { bool skip = false; for (auto address : m_own_ipv4) { - if (address == sender_address){ + if (address == sender_address) { skip = true; } } - if (skip){ + if (skip) { continue; // do not answer or discover self } } - discovered_devices.append(QPair { static_cast(device_type), sender_address}); + discovered_devices.append(QPair { static_cast(device_type), sender_address }); if (static_cast(device_type) == DeviceType::GUI) { data = QByteArray(); From eec0256bede8b49d95b5bab7826bac6cf18ebe2c Mon Sep 17 00:00:00 2001 From: hangeza Date: Fri, 26 May 2023 07:29:35 +0200 Subject: [PATCH 47/47] improved event timestamp handling --- daemon/include/utility/ratebuffer.h | 10 +++++----- daemon/src/daemon.cpp | 21 +++++++++------------ daemon/src/main.cpp | 3 ++- daemon/src/pigpiodhandler.cpp | 19 ++++++++++++------- daemon/src/utility/ratebuffer.cpp | 24 +++++++++++++----------- library/include/muondetector_structs.h | 3 ++- 6 files changed, 43 insertions(+), 37 deletions(-) diff --git a/daemon/include/utility/ratebuffer.h b/daemon/include/utility/ratebuffer.h index d4b49495..426c4451 100644 --- a/daemon/include/utility/ratebuffer.h +++ b/daemon/include/utility/ratebuffer.h @@ -10,9 +10,9 @@ using namespace std::literals; -constexpr double MAX_AVG_RATE { 100. }; -constexpr unsigned long MAX_BURST_MULTIPLICITY { 10 }; -constexpr std::chrono::microseconds MAX_BUFFER_TIME { 60s }; +constexpr double MAX_AVG_RATE { 500. }; +constexpr unsigned long MAX_BURST_MULTIPLICITY { 20 }; +constexpr std::chrono::microseconds MAX_BUFFER_TIME { 30s }; constexpr std::chrono::microseconds MAX_DEADTIME { static_cast(1e+6 / MAX_AVG_RATE) }; constexpr std::chrono::microseconds DEADTIME_INCREMENT { 50 }; @@ -69,8 +69,8 @@ class EventRateBuffer : public QObject { void eventIntervalSignal(unsigned int gpio, std::chrono::nanoseconds ns); public slots: - //void onEvent(unsigned int gpio, EventTime event_time); - void onEvent(uint8_t gpio); + void onEvent(unsigned int gpio, EventTime event_time); + //void onEvent(uint8_t gpio); private: double fRateLimit { MAX_AVG_RATE }; diff --git a/daemon/src/daemon.cpp b/daemon/src/daemon.cpp index d61d5906..27648110 100644 --- a/daemon/src/daemon.cpp +++ b/daemon/src/daemon.cpp @@ -621,8 +621,9 @@ Daemon::Daemon(configuration cfg, QObject* parent) // connect(&rateBuffer, &RateBuffer::eventIntervalSignal, this, [this](unsigned int gpio, std::chrono::nanoseconds ns) { if (m_histo_map.find("gpioEventIntervalShort") != m_histo_map.end()) { - if (nsecs / 1000 <= m_histo_map["gpioEventIntervalShort"]->getMax()) { - m_histo_map["gpioEventIntervalShort"]->fill(1e-3 * nsecs); + const long usecs = nsecs / 1000L; + if (usecs <= m_histo_map["gpioEventIntervalShort"]->getMax()) { + m_histo_map["gpioEventIntervalShort"]->fill(usecs); } } }); @@ -1387,12 +1388,12 @@ void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) } } if (result->first == config.eventTrigger) { - /* - auto nsecs = rateBuffer.lastInterval(gpio).count(); + + auto nsecs = m_gpio_ratebuffers.at(gpio)->lastInterval().count(); if ( nsecs > 0 ) { - emit eventInterval( rateBuffer.lastInterval(gpio).count() ); + emit eventInterval( nsecs ); } - */ + emit sampleAdc0Event(); } @@ -1409,12 +1410,8 @@ void Daemon::onGpioPinEvent(unsigned int gpio, EventTime event_time) nsecs = m_gpio_ratebuffers.at(gpio)->lastInterval().count(); //nsecs = rateBuffer.lastInterval(gpio).count(); } - if (nsecs > 0) { - //emit eventInterval( nsecs ); - if (nsecs < 100000L) { - emit eventInterval(nsecs); - } - } else { + if (std::abs(nsecs) < 100'000L) { + emit eventInterval(nsecs); } } onStatusLed2Event(10); diff --git a/daemon/src/main.cpp b/daemon/src/main.cpp index aa533211..6d6ed458 100644 --- a/daemon/src/main.cpp +++ b/daemon/src/main.cpp @@ -104,7 +104,8 @@ int main(int argc, char* argv[]) qRegisterMetaType("MuonPi::Version::Version"); qRegisterMetaType("UbxDynamicModel"); qRegisterMetaType("EventTime"); - + qRegisterMetaType("PigpiodHandler::EventEdge"); + qInstallMessageHandler(messageOutput); QCoreApplication a(argc, argv); diff --git a/daemon/src/pigpiodhandler.cpp b/daemon/src/pigpiodhandler.cpp index fd363ac6..3b1c56fa 100644 --- a/daemon/src/pigpiodhandler.cpp +++ b/daemon/src/pigpiodhandler.cpp @@ -16,6 +16,14 @@ const std::string chipname { "/dev/gpiochip0" }; template inline static T sqr(T x) { return x * x; } +constexpr std::chrono::nanoseconds timespecToDuration(timespec ts) +{ + auto duration = std::chrono::seconds{ts.tv_sec} + + std::chrono::nanoseconds{ts.tv_nsec}; + + return std::chrono::duration_cast(duration); +} + /* linear regression algorithm taken from: @@ -125,22 +133,19 @@ PigpiodHandler::~PigpiodHandler() void PigpiodHandler::processEvent(unsigned int gpio, std::shared_ptr line_event) { - - std::chrono::nanoseconds since_epoch_ns(line_event->ts.tv_nsec); - since_epoch_ns += std::chrono::seconds(line_event->ts.tv_sec); - EventTime timestamp(since_epoch_ns); + EventTime timestamp{timespecToDuration(line_event->ts)}; emit event(gpio, timestamp); if (verbose > 3) { qDebug() << "line event: gpio" << gpio << " edge: " << QString((line_event->event_type == GPIOD_LINE_EVENT_RISING_EDGE) ? "rising" : "falling") - << " ts=" << since_epoch_ns.count(); + << " ts=" << timestamp.time_since_epoch().count(); } } void PigpiodHandler::eventHandler(struct gpiod_line* line) { - static const struct timespec timeout { - 4ULL, 0ULL + static constexpr struct timespec timeout { + 4, 0 }; while (fThreadRunning) { if (inhibit) { diff --git a/daemon/src/utility/ratebuffer.cpp b/daemon/src/utility/ratebuffer.cpp index da1c86d5..392cf548 100644 --- a/daemon/src/utility/ratebuffer.cpp +++ b/daemon/src/utility/ratebuffer.cpp @@ -1,18 +1,18 @@ #include "utility/ratebuffer.h" #include -constexpr auto invalid_time = std::chrono::system_clock::time_point::min(); +constexpr auto invalid_time = TimestampClockType::time_point::min(); CounterRateBuffer::CounterRateBuffer(unsigned int counter_mask, QObject* parent) : QObject(parent) , m_counter_mask(counter_mask) - , m_instance_start(std::chrono::system_clock::now()) + , m_instance_start(TimestampClockType::now()) { } void CounterRateBuffer::onCounterValue(uint16_t value) { - EventTime event_time { std::chrono::system_clock::now() }; + EventTime event_time { TimestampClockType::now() }; m_countbuffer.emplace_back(event_time, value); if (m_countbuffer.size() == 1) { return; @@ -29,7 +29,7 @@ auto CounterRateBuffer::avgRate() const -> double if (m_countbuffer.size() < 2) { return 0.; } - auto tend = std::chrono::system_clock::now(); + auto tend = TimestampClockType::now(); auto tstart = tend - m_buffer_time; if (tstart < m_instance_start) { tstart = m_instance_start; @@ -58,21 +58,21 @@ auto CounterRateBuffer::avgRate() const -> double EventRateBuffer::EventRateBuffer(unsigned int gpio, QObject* parent) : QObject(parent) , m_gpio(gpio) - , m_instance_start(std::chrono::system_clock::now()) + , m_instance_start(TimestampClockType::now()) { } void EventRateBuffer::clear() { m_eventbuffer = std::queue> {}; - m_instance_start = std::chrono::system_clock::now(); + m_instance_start = TimestampClockType::now(); } -void EventRateBuffer::onEvent(uint8_t gpio) +void EventRateBuffer::onEvent(unsigned int gpio, EventTime event_time) { if (gpio != m_gpio) return; - EventTime event_time { std::chrono::system_clock::now() }; + //EventTime event_time { TimestampClockType::now() }; if (m_eventbuffer.empty()) { m_eventbuffer.push(event_time); emit filteredEvent(gpio, event_time); @@ -81,6 +81,7 @@ void EventRateBuffer::onEvent(uint8_t gpio) auto last_event_time = m_eventbuffer.back(); if (event_time - last_event_time < m_current_deadtime) { + emit eventIntervalSignal(gpio, event_time - last_event_time); // m_buffer[gpio].eventbuffer.push(event_time); return; } @@ -92,14 +93,15 @@ void EventRateBuffer::onEvent(uint8_t gpio) if (!m_eventbuffer.empty()) { m_last_interval = std::chrono::duration_cast(event_time - last_event_time); - if (event_time - last_event_time < MAX_DEADTIME) { + if (m_last_interval < MAX_DEADTIME) { // std::cout << "now-last:"<<(now-last_event_time)/1us<<" dt="< double { if (m_eventbuffer.empty()) return 0.; - auto tend = std::chrono::system_clock::now(); + auto tend = TimestampClockType::now(); auto tstart = tend - m_buffer_time; if (tstart < m_instance_start) tstart = m_instance_start; diff --git a/library/include/muondetector_structs.h b/library/include/muondetector_structs.h index 5ee01a19..bdea11e1 100644 --- a/library/include/muondetector_structs.h +++ b/library/include/muondetector_structs.h @@ -21,7 +21,8 @@ #include #include -using EventTime = std::chrono::time_point; +using TimestampClockType = std::chrono::steady_clock; +using EventTime = std::chrono::time_point; enum class ADC_SAMPLING_MODE { DISABLED = 0,

{6XTt|rus=F80I_+zR zQrIo7!2agNDqR|_95Ro+d)4B&Q`I8%&hw0bw+t-{3jHPBj7A2aPyuugiS{H;Yc#s{ zsruc;g#-14)BZFS^I4(?Z~kIAeB=P-Y;RG*|Gk8hcMH`TN3D*`hU}wsHK#k2zjKGP zsi7}If;J24yBCb4Z#V94^J^T^;R~Uh*0hvhNB|~Zb)j;ue)U@CBSR%z59qV;(1hmvjU+A;q)_7QSwr$D`bm#!!t(p>=Nr`ryJt~)5sH)c3`f|_oao$)SD2G#jz2fT z8A=8Gzwhpk7iPPXUZNY;qMGWDxtSZ~=|m=EZQO=UpYSh?g2`AfbDx=`=5qd=He6*l zh*92bL4d#<l`SF(+#9*~<`rY`H9;*EnhJ{sTp z+)Cc`vr9(P-!Jwf#wPshyACwWD0R)Jf~(8)Y=L7L5s6&GLm%a4vP7Dk#XQ=0f+-ar^2X4=6*Y`Rg@Ju^Zi$<( zXo@5KT-=W`A_?n(=IXbQRO;<#@)bMc;k3)2E8P;McdiA`!L@H|+OIW~b`6vypi8(h z^c1aem$C}!YHd?s4-Vh@0DBC;XGE+`$`2CRtS97)@2{8m!nq`U*E|xLnc;SGvaN$u zW2(UjXszn;ZYEtJP*S;Tw$x85F@A!6$0&n!mkYpz zBo4%?57Rw58lEd|&x=kBDX_8fj#Bjh02FDX7^&}Pb|1T$_NNP`{8jch+ZV69>gf(> z-`jWHJl@uJArE0bLQ1e6Fk-#Q)bJ9_oHmXKvaFDQYC1r58VzJ`5q@Ekx^Z>y>l~6y zV4rQ2WHu?Pn>fzKn7D?=qxD@TM#rpIL2Wyh%Vv!vwbcoi%Kn(m;6jF~h9^gJKn!=i z{-YIl9dZzvxH`w0z*1SL?79h(+fe0w6Tv(dK*H^f%KJ^s!`X=xr9k_JxB|FrhQ8z` zTdWaLz;8QT@MzY2GMJC^NasRuGgkegEEU0`At>rBRhbeIF_F7GCOPk53bC1gsE8w3HPKDV9;}0 zhV+SS?X%l3S_@4VOUe2JuUqyXd#gV!N!qZbnB+YLu`7F>3mY-7g=(B287Vwc7eu$;*^|p}B{16D7rz@pvg z9R^@^v`|KuTXV&+25PnL@;}%1DDY6Bd_8nTNGB6QJIiE?E640%vTH|V?-OR`tArB7 zdF(_@9^qvmnISe^N*>|xOk-EtMxj<`1Vk<(pnSmKj~inty`c&;s2z7BgC=P z6TS;wYa4}Y>XHl&H)d>bd`OMl{j1cEbajOWVv__9fJPO~*Rrz2qC>Hlt2@s91p-Z7 zW`nm@By*6G5}@%8NaZLAXrNZxhqz5fvs^&eZhtu9-cdD6eb<9X%y7ENM2i3#!g=>F zC1?{Y)8`hv!~spz6E@4Lfg0BYgE$b5Aa(X^C)=F4qsyV}c3VJ2MQFgkcZch?IFLMC zuj%b9gnonPu^y3zM%uA|yYdy)okQX$tkX$IB7%NbI!FOFH1;sah!1A;=s4Vs z4<&L65#&le4Y>vEhKq(+F8L_Vo>y#AVge~sx3R+LSCn1BQ`dercBgLkx~jUSlo zN@?_(n}?v%f|FDI`g;7XGj6>3r!hIVcRk*Rqj}hB{j~EnmBv_rD86;o*xzql01&=n z>gW}kGiuf9OkdrKTz9_`;Z3MQnf094Tfc(CTfZP>q|q&5a}Rb}c1)Fq1&4M88`+*U zhYanzX8*%XzLyijJu_Ner>Q89-eKN%1xcaQ4$^8}u4kV;H+~Z*>~b@DZCHJb){4+OLp^!B}7&ZC|ZiMtLS9pLYdE7*^PHywa)Naq3?;Y=9bcmaDB98zgXf zFCnZ1P*npmOHo-=5gyW6O-+JobUv)vNHpS|nX~hU>m-&%Y@>`HyB7-A$69g&^{!G% z58B7jyq^+W2A6E-A#T2XZpQt_?Y3@~8Htd0QctbN75GSqLLUHXpc$7AC#{^!$iT8= z>PVK0abG|vK0h%k+Q&(p&%SrXD>v2a+efsFJy(P|_lE*q7nKqoR|E`3rtCkSn!d!C z^{o4y_eA6d6{|M@K$XQx97`O&Xey1<@>I$*D z8*%eaS$iw8o74X&zAU!%ZXgI+kAtQndDw!Kgc6p2%={a=M3*D&ag~*=pBcz2nQqlh z+bdihD9GBUGexI>oFV-1^!C4y0DJ`Dh+r!1yxYM9hm*u9j%i(AUVH#)^9;X>D!4k^ zbjjApS#-g)<5YL(_>#fVk>Z>PZ*(UBn?XBmf}*|9-`(33vG4z-4*q?vBI@M)xT1{B z6GWJFS#inV`ZCbb!z&t(@%Cl|hz9@c%uHQ%)}O*FQv{=XE=!qCV1OyTOGcBZD#?F5GomHRQyXI7|FRz?rjwD3l&xBi0rusgd`BhZz5k zIS;SCWDXr*jhxYlHM1CEm&)7>q>9poSCvEB`W3QWfV&At`n_c5V>looR8u?hRHB3o zbnqPopG>FF;tb-DD}hP>ZJH;QdsJiz{9!4)<5TOi7P(A##gzBySRNkh!P;=iI1$}3 zSHtB+$>6Pgjl3kdrhjo%cICU;$FH=;*l_)BDv`Z$_?yIqEG@4qLy76)PMYIz*QKO( zq2M7czH7FWCHOYWFHMvlSs2q<;BAC|^uh9hHLF5O0K#f`Sd9%QatR{*#w%tKfEc&3>AGGWwXAPSXCvq{s&|D~g=QMN)moR~YC@p^mg{g4bo0$O{VC^~!{zvXVH} zi8XzNE-{Y=t^0NC^QQjc7EWgpr0S-dadOm+5q$2nW|jkr8Z0-JM)p}V_~Yk3o^)TX zt^2Z`hBJFM_8Whi3B7j@!w^LkOVSOP_7hkavNo}lo%~BZ--L-c7Aw>eT4vQS6VErn zEEh$Xebc$Unpa^NcyP{X!S72>yf=9Q4JU&>O9`2<(4IYG zf@tiY+=C_4q>ev}y!5WwmT`v}5rDPCEa3G+WnQj2weP)y(2mP5ey!@-hbOuR7&U%$Fmb zAj2V;BjA5M=K3d}^zFHg_>pN7z5fLxB7f1HON9_$gz_S&0PY zXVG^Pk!=|RzmhA05Y%zsckMVM?`f|V&9jF-`(3jcbU_W*p4(7&VtlEBZJ+K_79&vK z3)&9}OiaZv_p^AeCNq4u{1Qiqd}f7y5Gs{Q**PJLNdr~SbSjixpLDpX-0Kd#6|sWpX&xeDva-Cy7I8eK(6}YN6Qi%J@9;p`)#*R)!1T(+FNFtK(SyYT~<9+WDbG6O)*H!Sir1 ziN(l|PVWyVK*_Q9jAsTyvol-rulA5 z67{khF-u)`?^a2GklsPK?81*tyXOXeH#C7vTa%mEL{As2E7yYEFe>Bzqdq}K8G44$ z2+H9Pq|)nGcsaF&R$nAigg2*ocaLE$s-&vzdpeckGxo#dHpPuEF0Md=E zZ|T3Bi77F^CkBc$wAo>}X8|dDz2yJ>L#QMv)P1*JPfZx5Jp7H%1G&=tG|U54->M9? zEJ#r=c#BLG7v!wuiVGsAexTVY53h)oJSMDXedP`XFHvWpW_+b2dWLB9;~wu&L4EjgP};4gg23a`8Zk!NLGjS`zhwsmo_s$IAg)bWglbn z73aRizPA`shZy=Umlb{9Z7KZQD_uN9NhL&;kqC_%22Ii9(R30ZTZDB5{H}QNKkIs* zmi9N&Rdi_+yVWIOBGJO3N8BR&uYViEi6d`j&8nD^nr?TW73*MgtX@E9qjnz#y0(PU zCl@(Gzp6;fgRC0w*e7D2=ojSFg-+4Sf>>LpjSUuR>50eUMYLMm{IqMUw$LhTF{MEB z@+|k;D+~*t&0J!k`GYT_{M0o6Mv%I%Gn^kzD&1M`9ajWrxu zWm55IxJd|ErAmS8km)(jAquDse!!x!=N&aqq*;CmM+rxymGJ&sq}8`e4l?`StyKAV z?6AH_yT z`sH1MyVvkli0yWR%3T21$-^;(B)U}9M^z03;GW<${K?yW!JosgXnt3PpHUf%O!SJm zpX>Y;T#x8ZmknGtZ#nx7X+4UppHfW;>v|$5S>P}zqW+?48~-JIJ0LCB86{5OmhI`5 zJ`nt)U0^Kb8x}I#DwAi9BT|?CJAhB&xBSxU%6aK^=}te>(`!>~toFeg`k~;@^K_VCk_qQa zI;siOIy$N`r)f5-VU+0tA*J3)HQD??Tl@ZV7dE*Rm$ahahjl5XL-3a#zsR(N0k*1R z;!40t8`Ux4!)GxdVU^?zp_&$IQCU$CyjEiT?)S+2M6>UfU#~)lXBFK(t|{8OcQO7f zOQD9vdIJ!^sNzE!m>LF^4Rd3Zy5Jx+LrdPn%YsE8a!9Ow+&5l9=j5A7oJRljW1G*B zY}|k5wN7JYDS&^dfO_?7W?UGm^hFc)oi=fd%KF?mCFl3t(8mhqkxx%?+J<(Y1GZC` zWs_=Fvpf>r#~Oqq^(Y*rj7gUih39SHKPwiJ=4DKcmp<;l>Nbj|2FJrxHv4rNo#}Be{lLF-(rntK-m#hc zeOCrTsUw_8h0OMCkGnowDhAt(xeH;I2Xyn9&r3Q6L4~w`3?s{22_@(}9V5x8i}VlV>PA{KC;gA0;c`Em6K^A*d+iCq;;aU;QQgX=dx zle*g*>-2K>CIm#=y!Q7dOrd`&vZM65k!Q8zlhQ54zcxMv+6yP{{V9b@$S=*KfmcJU zyi!p^h(*e2Z?e#8io?J(G&V*mrmibqs+0M!D)B*hu2e3(<4UCg6C8qp7$q09pGz($ zmb>De{xCggW2aek57zsdtKaBZIpa?%m)`n~apUwHacE+Ji68B4H@!a1&}@_(Sx}j4y(Ep(Ch#hI7jp)aL!B@jY(eJ^A@jtb-xmyd%lKrx4NalHCyJWpy9-4nC z#uZ4@NzZZz2b84iZj@6Ink^+;Ux^ud2kdE~PQs_t_4445sYI3;xs=3}NY3xb7R!QX z$ouGL#gPsw6sbM;{_$KKGdpJLm18??KA1c7wiY|X;-XdtEAO__CE6AjiHs4fH_}tr zZR#+~`Bv&50cMpgli;yCLOX><#vo?BTG;w)O!=a}1tNltLAvlf%2v&60uJ_xZplTJ zf$yg>vO~1sA5Xdwf<6;BcuVI$0~pv=4a_uC1kr3`^DS{k1kkmfTX8p^P#7T z^t?E4#-(3uhAnXJJo_gGq9-L}5ZEo!GQ2g*Pj%TLgin^tW<~JUedg?W7m|dWI!40Y zA(}}2r@EvdBDDQ!p2>`nQs7(xusP%FJ|6MeFV^IOp(1-;Ia^TUa;6fg@Q6@pVTmMz z9Sy{&Xx-wMA|i`h0zo_+BPK|qbeyoWB1{uFYJ|Pk8p09Q|WshEwH0GmWwx(42a!App~N5 zfJufCSz&^|V;a&PWK&BK8ZFg%>0XX-nYrt>3Dm^UMP^Z3{4V=?h5ex1R5(>qeQgoM z7OT{l99b;+`xQOrx5Zc1F7ebt@{9A6*5&o~#hMZ4SyX<2ao5|a33v`S`l^C8A-&is z%L@VV%Tyjqdp6mU#8asP$x7 z@Dn({zfCJsL6ASee36HOu2y)zk6taJ|2Cj!Jan7QR(2Gh8=Fne{;)O}1B?~^#IhAD zAm!dd5g`(3#KPbeGfq9_^*9s$=)u#U)sE)8=}Mg;ld;QpQx8I;?`KCLbocndM&}Ji zv*&-lM5`R!K^&&GG30(-IO;C@pw%*S^K-^T_ua|F+3KRRBKMrb^QF+fqI>aP>Uf{v z%Px6Xw}{U<>b3oP)cN;5syE{3qX&=Wb;($n$zO16^vKJ!Dm(a60QA}F1Ac{sQ5;US z{tHvaOLA$~)eY9~19e1>3*s{_BaOBQm5)WJBTOz5J%~luG<28xr*$dTD)WT`@pjrI zDAVMp^jS%HnE>h!F8w024H3kdgQOw=f`6>bwS%#?iAegD3UgjuG?_%RkS@o6I@oNY z!%vH;!ktw;Jce}NZ2;He3REG6OXQgqx>W`gG5NK{e%xo+yD9~L7dxjpHM4V zs|BTJ-tDOCe;{q-wQ0r*hdA$N_PR)W6ryYdHtVFX< zC7XaC9oyw`(0Om2Fv^j+^n+R2JGbH4^x~myO)fzBBIX=CuG^0IkV|?CVS>~cXe#xk z?D)q&y{WOHN^|m#h#`5iJ#PF`t#S*ZITXxbYA=;e%c{I1%ECkiSaYhrpB>u}CxQj& zC*A1xNWy+LB!ntqp6iTMnH*D<&(V0P{BFxT_t=(f+uY_Rk7Uz4)GKqR_|89+%*P5U4?Z}bNxVI{n1PBjjv{#KKb_Knl;UF*?Pa$= zz%b&y^XKJqydoE37F&0jWKg%YOgr~42~)u~TQ{Alz*BTnU?*P2fnKv7IuH6XUJ*t2 z_Uv#2_az;LMWu4t*wx=IY&U2!P;r!2j%IBK#dn6w=W`l?8lq*Q(PGmHEl4|g^kbjP zCFPAPUa``#hv_fZSWEL-!p|TjsvHv@?T)&~wo=^RWAGlSv?kd?S=cCA?_w=CxOlou zH`x8e{qNstEvq+ zb89fEEa%nnX1sBDP|ga7F+N+Z!n2C~KSj5Fvo|M_ZBufiLJRL7LD&%OK0w&6$y z3+fidXM8clGHZpu+!T=?F3xIlS2Z?P(H!`Dz3KPIEls2YWvQwjvN-Q8F)vrUBV1*6 zTk;9Zc8W+cVjXUMMshYZNTPFB%jIC{K_){Rm54s|4#+@=VMi$L_@JdK*7R$7(N8-x z25qeu(xouF!f*&3+G{Hp@4C?M`w9kNfh3j{1ED@$iJBe&)O$yFNoS<%U9{3BKc5Cw zGizoWJAA~xeW01f4HJYNo?qC@4 ziCq|P7}ID}(UR@!`;b1iB(E`&^?PyymxTTFrh3vIZ6LbK3W{ZVs_N_`H{!nD>F^G4 zczBEi;XS_NHxwyWtogZGTj2V1tt@briT82jB@VmJqKq1F;Rk-78+O|r<3m3nfN8vJ zJ@qmJyD$Hl(#}&&mjB5q>!7!&lY>pO^dSwinveBH{!eyb{c)JVFA5ZG{#bVO<<1@~ zMCI?5-WS**fpf#J*mC&GJWss1?Dywe*E4ZC!p#zGZB3t+kRxcFbQi;jt&vt{)q>)m4H_~vWx|n5Wb7}h4p7R?Ur4hy zsB_v8CvlO>8FS12NC)=A#dx*MjsG&`o=XP?2#OWFwTh<>HmGm2^T&`8^E9nvv$4=4 zyYK73ASLP28-C;lm9_g9#EV{?r^n)ngxQKN0CpJDv((;?%&MQvC!<0xFkT-KhfA)U0d) zAr;vX@)&2Y#Gq?e$7uC97{;_|4u+qn8>c0%Q za>QSTRJZS$$b`&W12qyg+%O99j@#gt#(4ClmPih>PuvpC9>GH&waYu*uq`Wix*RrB z%sD(RD-woE5`@%|T-aAzVfHxPu#&Sw3R1nKzf`k+QkY@`KisK6>=aaR6 zcTrPh@cuhChQYWlaa_wN%ELpTT%NW`bSIw3RoGhB!hy+t(iKS}SID2Xt@(}J3Ro@M z-a0+1Ew@~_Gd9{(NWH*>SK#WgZAncGVaz|?(?mCLstEcitijd?E41>OSccYp+i@X_Nt|6W4R5UBF7)3M zp0C&Q7n+UFo=s04l0Ib6inbc9HgHgH%E2$r8luzHc&1KQFpj{Rnx^J8@^oUBVZ7Js zDmuhVjj>)*4!Lm1JM*yzeQi3fsj)>07#L8aqX%X83{X!fyY%n|11 zYSBiw#6o7zR5A>cOx1HaISdeU)&AB3k|*;4lqy>s$$O$5kw$HniC1UduWGjZuk3DZ z2{lTFndECdk3=e^GOlM}lnk8setu5D(^-X6CUKK)*YdfCl;?3s!Hr~+1zA<|GW`7N zp=F!=f?a}n5N`~%h1)ZYLa!inLK5eUT;QA=!}<qen7NKtt$P!JehNv(&P1FjpCwPmcMHaJj}Zbt{fU>igJbOIBVLaMPX1(&H<= z;2SyhrO(E*yb5+FL7p07?eHLNglHsLT6^p)MaJ*Qv-ZDZ!y+4-{iDIc;r0spd9nRC zex^ltD>|oJlFlLU!1bgy9DY>rC&qWt5EeCV@lF#_%s;x{&Zdo)u=^(vj8RnpWoVej1&2dW-DgPRAe=5v}?25>92 zOZ~HR`|DSpp33T49Hs*+sMc*!A8?O(WWPRep@}OD+`vw}gX6 zG>x2*>}XC)JmsUVyv;m>R>ONH?B&jqQ{CjvyLdTEN>Rp%>J zbw)^iWbQhN*2JZ>(^e9Ou~x>U6&;otLrR^ntvEUgkgq}HOW6JG^|f|;t%$83u1r|Y z+VeON4FQ&Xun0!-j!m+%am+G0pkYOYOlk7)ZG2j&M5j{Xx@nR`inv%dg;d)t(K}Rh z{SaIoXu1Yvxor6;q|i(_FF^ymz9Eq^xlFPn>IG#~|4w}h)le;j6z`X=i~}w(Eg5HD znWdirMyyj_v*MXApcP;>g$-v3@nScHrJ5)f+tSCYtLd3)eGLa5zJ?+KfG5Y)m6@eT zDy8*a{%q^oDHSmmdBKAaTg@>hXo__k>LumYSTm1n^0@oG7(b7D0CkZ-bERH+54$nn zzMt+At-qo8$m!5aAfu_BlwF@-}%ilpp}x1r2KhC*%I-y*f6I+;}N{0<bOjOOlv1J)|gqMZU18^^raCwuoF;G3-NRJOugknhJ{JmdAJaA z6q6st1}`>kh(`#V;u?r=ZK|7U^%Cn|oR(<;cAA>8VHk+8la#BZ*inpsjZtS_{uy{V zmoN4t5F$DE1uKCwBIg0`B4N4KT|e$9>!0&qCAG?LP5?Qdae!86(P8GaoTEg__)U3T zPv?M?2wb-+#kdX~V>Jt}j;Z0??&KzqDODQ!rLRw|l~mY+Ory1unp~v$4fgY6lz$TX z7&QucX$O+egqi=ho|S^0m1wp-v(aQ)ic7xjjo(Pp2^$#_^X|En34~f_ibMT@E`pq^ zsFN{@=KHrOP1_hqq+xLtEZdd75r*wQ?b6>TacX5;KWae}1(gEaUXC;!f#oy6y4@U! zo+%%n&Om$Bi)$Lc{kY#52)$SbQrRbqZ*r*&`P$3WV#1nY@eqI>WSS?37U$X#iu!U3QNRV|Kuw=EZl}$nQ$+sl zBxv|zB=hz(XeTVcCgwOd!2c+wKxUnU$AJ}K4G0R)flm}5>v*krp zg#E=FGgUtx7m<4#7q8G54eZv&75zz%5M+SCh}6c7=5!>yLaV+ME0>6v{&?>EZ5Z&7 z1DguE-Cw@6cvgKYO<=rMIM10vGqOxZzC`App{t(h-!@EdrNcjfcjC#wXZM;a(yVL zhcR$jzuu*2c(xY4r2CM*6f#_^F>FeZDrf5UlW&5zPjTi9u1(7;=eW+jiTAV-kxuh_ z=+f4$e0+Lh1LC_cPe$_rZAv_7C0N0_kd?rCz($8a~z=WFS_K+iou6?jnCBd zn}=!(=>AD*66|O4mU_<*OC_nX)1pj1HSl1o@s}wrj>QjRhHTI1>-9D8A5P$gWV&sj ziKa1sk5v}*7##92t?Y$Ln8Y*K{x)x;Mp+d9I&|UIUnkYKxp+xk;3$?#nOs)SZ~Jj- zS0~Cy^hI1rEt0Qz%5ICkKKmp*fWCgJsOyw~_>Zw~}sZdZKYKI`x+2#nr3bU4K^ zNG64o+ZeYOmNs&O^C)JqW%M|&E+UeBVj8dhO(T{YinY%UUh(7Ln3WDOZavI$QTo+=y>`^6`)mS@6k0xBfqI1PWAC(83L?@$> zhY>W?jX!qtNE}n|vqbWJ8~sAqEXHLPR#@I9Wm_bov~#lD9Z2dYoe<4X=Mv=NX{KXu z8oeYZ-RP;R_RWUVqLN`#!yK7tKeeng+8VEbZR;M(KuIlj0lD>GH#!B6nBxxm)~-F+ zc8>GPIoQZflo_W-SE#WmpBrM>(k{&I?UY|G6UG5V!+-jECCU zMMp8N9JpH;;T1pyQra;_G`SS%Wi!Q?R|UDP6Y9)tzS9Iw4E;1dIIx4&*X+_gOeJEk zC7`v4TUDUxDYHqv1*_hxmCEKQQ>hilkVUV}rl`gf`BwwZip}a@l+=-`FHwOwW$FV9 z543;01=;R>dgDIa`M8BAC#(2wH;GH_rJ2-Xhv@JS7vjKR922L+(SB8YxF*dCv zN^egKAG;&U%||TBO|um?y0oN~-p?-X%epEc30N0+#FdqHsyFsW$=PhT!kU*pCArAD z*>IlF*T%fd0os(#toee(%1O>yDmviq)}?Y2Kkf28^I_G0uuOp6UR=YtaVTM9=G z;6Bx~w1gMRX$T!D1KSMIuO;sETZWizar^7S>=5aeQ)tgH)aXYqYV?Rx!d)I1v;|)t z0~#m2O7{37TY&?x7d;(kaU!qq0R!VGqp=zq_HWhjB8DS*b?d3LlQ*quk4n z^pZqy{9|oC{IjguSh5yTuXOw4bJ%LUK@TC8llwjrs@`blUsGlY1CDmu$2h;L-t{>j z8*+XR#=t8Ya3+N?L=vja4)NwD6cGSXjEu!+we<>Eo>0Wv#Ja9$f38y?zkNJ=I6KBh zcv1r7yW1&E{<)P7u0$#;+e)>;_T-j1Fo2y=88Dr0h*_;mutY(MIA9bA(^S->F%4s~!6N6Of+l}^ z3d707`UH+n(o07Xi3NYoq?+2M2Cv#}AL@+WF2$teWElz)b_Zf`kEQfB0s0#Xl7!ot z&naliBBA%nUTl7$CzBeySnB=nv%zW1dkp>Qt$1qg!_(~Aq;e`tQDM!pv>v-(VRtYt`p}QBiU}26ox`TmvU6^{jLRYD&d( z?};9WRI!=OYU>AWRwMbSY&adTx%F3|VfuEX8#TZD&I|JEAn;mW?7^I@y~;*h)^{@P zQ3-+DDT?f!Nn(OE}_JPie$)qTn!1q z-`lgY$QT@vPKs>5SRkyHWior5WkzK}ezM3IKeBqCK!JB_@|6Gr z?>Jeco1HIEkSSxJZMn^hZiHHm9TsQEt^7EBF&bPMdNO=%62cWDs`U^H&n5@Cpe>N% z!}!^&ivqnm22$ZzVN#LE14ZR$mmNL7!-;>MGuJH{^u%( z5&TiOJ?7Z+??ei9iccNe?qmW^{i_M8a!#R&rE?q%!dPT5|4UPh>kE&h4X5&mp&M;E z%+KA=wQtXLds=Wqyw4dsX3*Psdz_&9aX`?F?)3mVXw)!N9VbJ{kl=UZL|a8P0jyJ7 z0wb21G~BO$jy3k^>;S+dqgd1A8Er9AoV4Hkz9A8EM#pyKgG&pPB)>?&{y{p9Wxde+ z?!df-_}@nstQtc9pxbIg?ExvYSJg+P6+qV5{hJyd&%=?ME*=oNO2_ny6YyStRiD&Pk`Kj;+Era{T`q7h@MMHqv z<^$E4(No9zmE1qMC}Kg+U~y-9br*LsMm{JP8>shogzq^!Hy)Rp(R0&oF~72G=fLM_ z{nlyFvYq#x{ze93E4;#)j^W+-*FvX=S@p=WV!*EsGrew>1ob9sY(jl2=fHiXa<{J( zsb5t-k^sx$K3((V&LLZ_W*b#K7sdJIP~9X|kq<(liSy}j+@u0PBVm7Hm(7#utk!B+-1-psA zz#q058hI-hd>;n*X!x~Srp_>;!g8dQv%TA{9VnJ{jnPX^9kplcE-P|^#Emmo%OM#3 zh-+`(gosV&DK{=h8Tac(3x>~&1#Z3*dG25`v~0jvbv;_a$Cja&@%)tu(m* z(q!xWu$z`2B`=cqi;$~fsQ{V#`yQ3 zgurEjzJni3=pE9!pEJsTx6&WOxi-|?bwmF;|MqC0>vdR&(7S~A2DSGm2&fzuOP9k&vIFQUCcW&@nRBd*9i? z><9Qx?;rD59OvCzwi5Rf+`DET9z2OWHr~k#JebIPz8*H{xc>KuvRNAQEI-1~-MWsB zzLDt(I4+Mr+so^(91^jFn;lo<+Z&raj9jL;j#*cKuoP0aSK zUM$4Dcsk>HZ+xm8{Y!)N-xtGnDWCh+%=>yh11qe!O|z%^eLhr9C`g_2;bjsMeO3JR zCxgA^Uz_crO$wZ*iP7bH_Fq$mrvptoUzgJa&@=2dQmiUsEuiqNoxtY!B|FQYs#>8D zVG(yl)9u#QloL<(nG(Xn7XOSt{k#lfT*{ZGj3s@eakxf7!2G6nKE5G5v) zB6~gdf2saJ>TxJzu%rVMT-$t4d=CfrpSJj!|JxI?0B%3i{dt(+-$nE8&sK?#UKIqW-!(cd@|&DTk!Q8%wi+0^>T#P6J{DSu;qjb z$+{%OG`jBdO+Lukw;~ka!0;LTy^1b@w9kaL*zV3)nff;a9mw-%t<&4vADt)}!6T=- zGW3|4lT)G`xZQpJ1}c3agSyH4UiAD^+qL|$NR%hbZb>Ef(=gheZcRGG-KzE)9mb~9 zzM%ksyrkd>`Br|o4GPb?0Pv{O%gSIGLLFtXdP3sSTTOvy8~bZ_ezcjT28>d4%##Qe z?CNiw8aoh%pw}U=0&S+>#j!+&7+z851CX=#uKUf`Z{OW7Oz<&Z5PoAyf_QhMH|WIo zaZ%slHM9GHpzAWFx(23tcG`X>VAr~flQ9;~$H;XUj95obiPo<_cMp?n$K!9o4G;}O zzx?le!0xW8+sQ(2?(1PLJj{`W_;~~QVFOt({J4#uRgDzovg1H6X+PIrAeLgn9ubk$ z$wt)F(=arJ^cxRBney8oY>bSGm zy<;2ryh;2@3b+0^*X&gbMqR&q*r5^}rbyEb#0V68yAp)3?K=D2_Y?0mE!%CE8@$j| z`@bAZ%_PV9KW|^F2>%xvV9(kPB7P=;Lq;dufDI(@pQw85c8&Yl|DqDgz=pw_nskT0 zH?+}2OE@){pa|t@3P|_pxt)F;LC3&w39~^+qpfNQEY3;%R{ELm98N>e6?W5M(#{UIM{I%AG&$(IG7XHsH-{(#t2>Z-tD7X$4SC1ea;ht;HSXKb zhgf=Ve+me5n1C|`D_0Ih{jj81aOfrcbeDw+@;Y2(uq%x;__g{h>^n4#&`&6!$?_>y z@YMrmBQx*3Xqt9oQKMcy;NJbD2S<~FLi{i!aSw|DzH~BOYn^v%GR2GVax)l5@jH3; z?8j#u+^_fBrK)pXxf-yQ@!YqYcERZnGiW)_H*a|%h;w@4^kX_#eW^?k^xk7y_jMs& zf9e&;fgLDBdY4VjoiW9C61x5`H*kEg$B+*%1^O>p7CRnN;5yG~nZHZi^BmP#>!USz z7+GTu-Q2i&nQQJ!nee+<_c+#BN9pMeLWXf3vOM>G`CKOD{7aAoasq zTh0HYLqwSY8YGiGbn|f5#@1J563CxWtCgw~vgsACTII*fnNYEzr$RSV%Q~)1;$CiT zip>QnEarymU97%Z(KgI_C6Ag?JF&?Tl&H8=zlS(_`NO7~(HjQ-A1h`7d5e(_gkit% zr4;y{&-)8rci~Q!8l%F9ygmekgoGsMIFKS}r6v_zD&Q5KEY>5(CyU@w0YuJca)CP= zo2K$!Yb!jKS}F6oZgWWAb{M1!zm(BTNWd*O?QXH`txURRr*#|@{M@HYk$yfsdu6y= zbtf*)azg2TJ?hC4l9b z0PGdw$*w3N6WFm*0c%aR1ZQ6J?Hns>HXNQ4-fR8DZx_TfHXOrsXliPUuwPkOS^qe8 zP$)g-huCSR$MUK>ltd|AD}1etC7cbZ!jqQH2>xT3Su;ywF$XI?dg(jFqNXvk* zG%kyR89L~6_Rv0J)gQM^{EOec{4i=1`l+p5XE=wwA2!Ov0hVo73nLkfCKEy$5%~N1 zFBiGveU@&t$cJ&hD_J3BQdMo1|K|b({m-T2xck-GuH!;n|7mI7X)^>ju@LAyO;)U4 z>qr;G*?A}jx8nB%ecs;hp1Av*Gd#xWpW1%bMG(LG?d|-~{yNYkk(}@GAm8UKLE@p( zU4K~1Jgdi=Q7~#=-w&rAyEv^?;NlNf2W(qxr&W2pGw;Y7#1d?a`|NulO6dQ50c-Gi z-WQyB4GMec!|j6WIbCh%EPUbUr*B^AYc)UHbk2Pu6taKE<03i7Q`NfnRsZdA{_4Cx z9~dES_|(U@pX1FSmFNHgy5~`&{1+Bu_I}VFdDyJ1?rB9pafA;xhA}s%-c3Xg6V08jqFBQ&qpZ@eG<1A!n{>@4{#93D!lwH208!Cmb-Q zwQ_hlu+p@0zmNn>5T`QCDrU~i%Vs% zMfO@7dmD@yIq!b-@A7KWFp0^JOYcBA=(9rUNHA*4E!zaEtalrV&lg09NryXLj{nH; z|G?^pUf%Twd4{fgqpFrIl-K*XH$1p*lYAPKiBlbM;kMuosIC3>2yHdO#(&|Vbu*Np z1!gz`rxorqlezZClhOO#e@njWEXfqV`_{U9(EfGL-pCcY_GC0(&e$I9-g&G?9oYwM zULS`6SGP6TsdiZ#=Zgk6Klfn&2JL?5FeAr#f!ckJx&p&InyCXYrzL%KMxyM7-uyU$ zkrWO6VVHXnN{{{XpgmljBFZ_k|2gu1P#lJ46yA2U{!~AYRKvv=ec#V^C-N%|>>eKS z5DaYu?dc5VZP%=p`r5`;-XF^cgQ>Y-f%!kEQ!;DSpk1l|*(BA}L~E`#dMV5KMf$VKDE3*pR|6wzi8^{?EdGn0^tY{pmCAA%hRzthW+@F?lohu zRCO(5f9A7KH{^BUbONQ@wP-L#?I$N`|AuW??Q9;3rx26Gg-@Hc8vau z+UMJD2wdCTOVtmpI&tqOTK9+WvdUqPK)=`CoI%KG9tC01#&Y#9SEL^f{BNu1@3#}A z1CWC)XvMCZ*q=Vit$ocwOmzg9ViNPAJHIIFeQHG74~ekI%1XwLw==u2y{e#EASuKH z=n8VCBH%IW{aJI{K%2O+-|%^WR(#l8US59WL}_Gvows|#^$!98$=o3yKrm!)?)IFz z{y>=EEqS2>%tUz(ASp4m9x2KcXsE7M5Br`0fB3y3(UaF~Z7ACjG z(up1~Cd4mMd`BdjCmi*{&;18Cj{}9!V{Eg6z_$XN?#CM;?n=#Gqg96+`2Q}>S`|I@ zFOn%T9XA0h_UEUBT@OLBlg@$qZ^PemXKp8b-gF;pGvTo?b63u`|3e_YH{5>M-5)RA zKZ`FmY1VHfA#aXJ@bdkEJQW5)0a5gyNWA?rl11r4@~psao@k^`Mf!ak-e-`e$0&8i z`k%@8Vfz(E?(KVRJJBq_>suo8R;`_WpvCcH&&zrwpKT}lR80vr8d87>#Jxf3;jv)D z9f8M@gO__dpm`NRUNZdY_Qmf}ObB)bDb8VY^rtUrsDg-l@Td3L{+cW(P!w5+e;izT z!<03b!^hi$k)4~q2fSlr#cP<*RaFGu{8je{=?7A$-lyuWXZrCho}lK=GaGD*hdVMj zb(Cj0e?eq&G6snv`ivu$Ao>(1FPn@twzT4i|K53xjmz`~B)e}t_+C6*La;hiH-w3T z&)0n+52h!z`_%-3=>Eej$<>V@7NLaqqr7_a{sx2gULAWu`pQai4o`$)AD_M8bdYVZ zm{ISD3@2I>sX;@JawN)J9A;L~d<{)ppwZ$A2{%jiRqB=MBQdJv-OxVcP*7E7vP?)I zJF3^pW#(EfSXu3iXM`h5TcvTc6MG~(;Kzu=Knw-Ey4E}=Yy;s@iG3&33*V4aujWyT zVEv&}vGF(NESt^H6C8F?SE zIfvL%g+t2rxc0Z5@f8II%M#mYye1u)!dk8Hm9zUtojqkycIU${yp*~3FvUNo%_Xy(frajOmn;Db#uCA{1t&^FVnU5j*k0E74|5a!BFMD8B ze(JW^L;rV>>pYS0@$uPr>^RBO7qJyMtwvwQ2@6dC{a%C|@4K4w+_chMjsioH1nLsg6{GYW{o)xS|C1vDom}e$0jB;3;w$C7PgD zPeG4j1v9KJNxkWU^Unv_Rn0%ip z2f{X#<(I}1-18zV%Qy{}n4J5AF$O|sR*GXM zeDCWAx*h!`=xNo@d`;cTu~Q>$ms#ZW=w?_VonFT;UeTc>RDdxF$;Gv57=it>`&L6P zCzJI78THmx##jyW7-6s+S||9Yb`{iy1oq_y?GTBU6Ddr0P>#pNug92=t%aI;C;s+S z`qR_X&79Z4>YaZ=9zziwB;;_u^(eg>RLQn#_Z^3P>E2nOEBjPsxnw)%eqjaF*Qt{3 zNWTw=0duyG15v2OL}iEQWh;4VZex>bSG+7t$)-@rlJ}eDOia=2z=(t)G|rwa+EuCk zN>PXbd`Dfog2sh)G z3P8&WvMNY*#xMP&z>^F=FdE%a$l(92PqVFNxPeE$IN~qBBsND;F9UA#l)=6P{En{!5s2A$Xz^8 z{fY-k?C5`!M8X%$zfs8-L7xr|BDDQNcfD735Br6m#S`25(|%aekf3xX|HxVk-FZf| zpfkXJQe~z$tJn2)fS|#md6Qcoai$?o_XRY)HUW|Ucf|PJ{IznwT>F43I5ch@$v)VE zz4(w`y{jM^@~x~ZWIethpV-scIcq73fsHG=+x_ccFXO`h)~5y+5arhSM&iBCOfpc} z{cNw)FW6!rLyeefvOgulambj=ycd|eMals%BLF@pK*`gFXyg;{BbBfqR#n_pNcL&t ze|9l1KQedb!a%=|D~1U*>~jU0;IrcAojK$xLaU0(>6kc%{l3B!-A9eWlV+BtGf3mw zwr3enVH_gTXa9R3`00IH!g#|AYmkw<*L#M@u=A`^0x5)anavVQ6Zkn$ZHOBdQVmeB zr>VI!L(E}(h5kKL4jit71WptvW@siz4XwItK@L6kCx-H2>n!_SxRj5340<7s{p(!l zfU-U1l%mPm=Zzt23lSNZ0*%cUj9iZDTRC76A(M`q0o2LLP`z?Rf)OODr$2FnSz1)X!fr&U#nhu^4Gd0ndb0}4skwC)opu(UXqDs zyZJ8sTi*o%`Q}#1F^Mp5U;Fpd(XEGi=d8TqmICI+C~@aD4$t_~X86ZfZ?M1##R?4y5|A;}XJv%==Mq6F-W*{N;CTNb}o_)3jNll$m zCl3^E;-A{kvEI@4X{nn`biM^G-xOlZD&-vw;!qvubQy)qUa`qgiq$(IO9OFZ7kC$E zCdi(5z8T&k`T=k@zM%^9`4Fy$`H{Tay*@-n=^b*D!fO)tTQz*66s}mlMkA9%BS zHx$>orNf5iv6+kyESkGcv&YXM%(vqdYZCSh8o@61=NrF_F}+fySU9Tw4Ts3K2YkY# zsSu$vl+k{v*r|Ns(#{ckyuJ{rJGLoW_r{LC%YkE^_(FIWPhIhON=NpG8TX%7Cv@Il z2-$wD1B1wRwf!8hNaUAKCV0ABrjvPo3foR4el!-s=!Jx?cG zm(MHT7+77i^VV*!E`#j;pfKBP>3&*;&K}r_QsRar?XYgYYZLyb+tFc@*i5_SKSUQ@ zB%yn>@-}OKR3_}U%FOiAJ#+XG*Prg&YdzXvXC^P-%$Rnr=SWC=9|VR&f^E~{upURd zeSvl!GxC7bpx?T>?oqI}JP)Ssp4c0!Z&{wX2u|xL%LX9bN8(TS575UwcRKbdhAeWE znm?GGHOw>61(ho1;+R1WQ042E?Sk$pWabR9Hjh#t1Y3TuyQ@wEa~1fnCw{QY7X2^7 zVac&iwJ@iD0kOLtRl9aX5B_Jq7O!AZ0i^ymM3C&~pDV8MgNU{#QJ`iSV~hMQqQThW zFX;y?HlL*BD~UuaG?nT*N$8NW*n;*QZLwISmH(iE8*3rDI)}Yw`*Emy+PFaV3~ta$ zM2jzW%ss+12aK#y;nDT8Uxbc~q9{P8JL3MC+WcA|c;fY&fx3_yK^Er+*W$tl*Y6Ww zVmdoo@`4PPuVSN^B?S08ENH|B6Rs@b2hAuKwSwUHGL-&?P40F8VrS8kx~3p_ETrkT zV09g4Pa`7-5felKu;KeA4f&OUhPS-yTFN5!1}OsnobbC^IlL>N8w@pEcHgbo7%~%j zkk1mR54~Bi*|h7vrxbj78cOE=qEy}zWEgyq?dS4J@-H+>vOmc1&>%~Mg6H`Skn>(& zy~(%H4%c5t-s(T*6 zXUcp@I+^(+eZksA4$#TS8^})BNvKJZ>qM7Fgv-$%Tuk(pw2WcdVY^btWO~! z3m(#qnO@$16;(NojV4z_31fuIAe$wN8eI_}@9lQ}nfh@PNu1dm{fl?;_21c6bjgQK zmgNU>bVPih((?=}rRN(ykrgy(6bc)sXA0%M$6MOSdkjT}sAy%>u!i<4Htq9_kC3YX zfP8U1>T;m_$?G-f#V$;e5+b9w*SEPUtD^V|2k}YiBhvT7?t1wX<^BNMOt)ZO3LReU zvxE4!l;cUH=eL0NH6Qc5`@s}SG5!8eq|FjFiT98$MwZAv91rW1dCTDgqS0IAiftGA z#~yQcXr}EW!J}-QO1Z@&@5@Qq(EM-t)txTlt=uq>`f1q9VbD&LYswUK=@xE(gC$Rs zIfqo1eFKz6aqOdUC#kSmQ)UGWha%iazW1N(SLkc&Rsg!!Gr?sPo?+M49V9WZ2`szt zYZ3`EX{7X=tOpqfiv0`Q2=ZAcT*&lDiT%(|=06l=63Ru0b5Dtd-D8Wn&`gWvt`eY` zs+k{8u6I5~P$)wvFUzqm7AK<$_-;H&m&o$(Xj7Xl7|OseF4rY^deAt|x8lBL*~U?i zZh9gW?y&5j*4nVOAlQP=*O}uus5teVcv|+Oi4BZhfOaz$wzc-kOkT-X)9vG78+gWI zFBj37&D-0iV7Nk^242RsBak&xvJi_O+xvUuhXIpP^mS({+JOn$%u<#vGD2FH`*OBE zRRqx6Y1aY&^KFfNgt}t5PEA0&-vB?rgpRgoSOOt_zyO7JQ*{O^zn5*!ijt1h3@g^i z@Metg{gjzhn-{fk{bTc`g~y%ZoaKC=w42XuhAD&E`HdQom(0;cznBuMRLEq$(iC@v z&9(tz8I7I_A8AP;mxV;ro@*yHZMQp8&y_^darE>;z$U8b*Tdemogqiez@OQ~W>ZI~ zR#XuPHJ!&Gtr--XR1Qh37zlUUIGxQ1WZ1)zu}=vwJL-F&XZ>rCpzQyXE?{OOehj*^ z#SK5x?v+)3AB11yw6$k$hgTo@5Of=kY~Tyz=a zgm zSq^;3$8UbGRFL|{E86?z$1@v5|3m`?r8HJz=^%8MXg7F+SG{>f!^GrFP@<}9-L>8) zX4M_u=xk(>qKa@dw2LQP7Hax{Q^!$Nxn$EWqxmgp`!``RQhW|@4K;1UcK&bf&1yg-FFL32OMhD$Gmfu?kQEyS?=KEP-&x7a3IAyl zQV^a~n7gX&cp#ORx@Z!@dgz(|RV}c+rlbrgwun;>978qz3#?%*f=VmaEIRE~5}~b> zgE~o)KY=^If~-zR7+KQCUklq@du}H?3!B_n>nrW{%FifiBA+5HKg+sU8je73-QG{< z6&wvUj`P+oq->-h$^((beBvf=^xHi_)O zL3RS~K<71oL!L=_BDZx%!jIQxq42QvH-xNZ^DPDl#m{-2O*Kp#S2dji=&U-tz^{4? zL9P{e>+B=?80^6kwg?p~`HqJ??wxNRuSy+`MZE3*oFZ=4E8Xi~NKo&aEOSmct*~t; z12;Rq-$OFtuXfzF-iuuX z_}<752v1+RLS>oQ2hG>&6~M`2ANJnDP=s!Tu__%X?3hP3X9oAnj63l>@sx!yqGS{q zYS`l%_s1@1(C%c4Qz))!XoOX+kS2I|RKc5e`^wDPDkDQr+>k{;cNt9EYko7qs>P2< z>};ENrUF(&4_T3!SLW6GqMtR&J9Afwne70_sOV#q!-JqIo6p0XZlv<;UO|0Ik%o3& zW$folhUPrmkDD&q@}CL{*Wqoo&{6w&ozVysud}Ym&ormsG18|11&7FH(S!+7|3tdmDdk&Dri6^`AVOVjVW|#FX z{Vksg-fg!IyM|A{_txoxeX;xB)~<{*%Ju+JP-h<0_(JJWl@@c<+4|MB=agH3Kz4k$ z4fu!dCwPp`XUSQviJq5BW`BHy1osBT&l5G)5X2ui&)XqMlyb&+8Z$Pp@e?_PDtDi^ zw2{YGPJ9BIjU?6HG|b7ANIzKdaIhij>C|Cp3-Zz+oKNL1EIE$qObXNORp}?EfMdfo zUEVyIZ`uIpO3~3JPI%9kV_%`heF`~RV~IFDDwyvf{ok32!FIMb5yBtD&=IY$=RpL7oA$V%MA4@AXYouVDFafrNZ)4P-0xe} z$xZ8g`WrCO9xB$#E7ogEUz}26>KVwvfbx@fsyo)O?LP|hZ7z&MEUM{MHrm5~{?6uc z>IymjC7%ev+QtOF`#oSb_#XI$J`Gx|H{WzU3u}&YJ#`ko3ZZUa;U5wTDR^S<0kw@0! z@ER0r?w^ z)z3VTIloy+l+NMOXm*#t+g&GgzQcV48$b%3Cj45kN$XCI`>d4N+v%)PVg_-W&lWdk zhz}*--R!6W4589`aGQb%U2n)qoBMG(Lk-?#e&vtZrtygCz%%%-v4>f8fZ{#X*v^!6 z+jJ50wgC0&Qwjy;j+3*89+%Hsx-t<~+FtIb+7p|1Zn{5NqOblu==bTr&Kb2F4ax(^ zueN2?uO|66pjHaQ>w_*#S;8+#1$jC-y&m(p3yu_w0pjq7l;~5oOOIC%ulRybG(YA1 zLg7c;)h44D&&+GM-LNGJ1Yb?vR(%km`W+2;nDRxcl^cfbTv_Epho^ChO~}I#HXlV~ z#Y!P5R$jKlQyWeexH00sh%zV6p9lUv903QpJ!fP-5-qnLMTM@=B3J z>7IdQM04@pdvsrF6r!u)2*qBFu|BEa8Jf28gMQfOh6(E2eoUm}3fx4^!0V|wt!0^+ zwKAnc?az>1zvdq*?M7L-%X^W>H+>^Mujww}ph1pFH?dBT9?t4vk&Pq{I%y^IW>N3H z2SqSw!)7g+_uUArx_5?D{(?qui0;8v+3QItawhe`h`ApWUCYFZy45bvtqL1(xtw}u zdi~z443NLD>3$Y-uch5dRVKf5`!IIw&&#RjF*eBO587jph{)~r>HQG)U zygk1Hl<&Diknoppmp^@<&uZk8d3Kc{JA^v!*0ryW_XJ$xTe*C9)HkB=nDijF(mskZ zSMOmP(JCis#?q=BwT{-==bI%PC4~%BP?hGFi%szIvhfE!t@XMbnM{DWo_ZW*`_+$q z?ag*{;0oLzR_Waca??qWqRmlwv*n}aP8oZz#~ysiQD}zD$%SZ%a8@Z4@go90pRbtI zOzeR>WGEPQRB~}6=&an|WYw1_dc_Vl*A-P07~nJqX1Dnd&=v{gSt`~m)F z1^$9}CO}c+xe6UC`ec@@v2?htn~j_Wv7e-F;3XWh-VbmmN$wP?{k}6|e=ml5Q|P4) zlB|$>H=Ar#21=Ue2fsRfjI>6S>mjF>EH*hEd_qk|Xz2$ns6^N$JR%?hgk6di0#WP) z8x)l>un1)-_PG+#jI2Vb?yD@5T4bQhbLSEv@UMxt?@{21!b_zD)T3rvp>r(|7g}(1 z+4IOw-GUlym!M=R{`BJ%?`;Wtv=xnyxk9c?mhxF|HSw?EQ)`cel z1}nH#HlHv|{;uXGC4AD&`e)_{j;AXoxyIg>LwJs*a1!^1xKtf;p~bG0v?`h3%YHwGK3VW zNt6Y2Tq>t_jP9jh%Yx&g$N_S4`aKp{U*ttKnowrGXGbIkC;$ZSF5coJV$je)qjBP_ zAnu%mLQv)>kL-ylOvV*mI&UK_bhv{?PpsH#wl@hr;sv`{0w9$$qf~d?N`p-Wz7FrR zf>Z=0qpiXj8}Z5h@%eAuxc}Dz*cxX1F;enft1(zc2apdZ;BVzVdxD+@ToNKQJ8%WV zK(e{q8^P8uJ(ddMsksEus52R(hcazuUAua85{W5PE*)u)1sUJ9mGhF;RLA1y9@^t9 zO`)LJs5cLf+a?k)sy4DtR4}0e7~^X2nRSd8`Oo?ve6rR~x0mp$dO1rpzjokDYBp5R zg>=J_#@Orz&TmWqISqLBUaSjl8Pq>iMDl@m>~W!S5UFgh7$ zO24R)A~CJh>h>v=h8wSI zMR8S5d!>a)UHadMTSSN|T_nsPpGl}iOxTxTN_&)uDUeZ`TGi|=Y=-{l?`K)Ga|VkF zl};E93%%2Y5E>_%#Nt7yZfX;XZft?P#sUTW`AJ@V7Jk7J&P;gD-iBH6x>S4)L+Y)w z2t|$V-H#F|rDp@}o)WlxP)vgTca$Eb3VdffNuNe=Bw8G?EylcHr9QzLKS(|e7B8q* zvVvCLs9di69XR%>7$BAs9g?7tLZ7bCtfe{5MY*gOdUhs=0P#;IH-EnAcXZhmqbYOs zU@8&sEyqBE1Ts$YwCh`b8L!_L+Ns%w`*qwpj^`;jbEq0?;^@zT0%SX4E*+uE%hed_ zQ_iq4_q^Lmq}JPmm|5h&`#4Flv=rFtDW0bJ0OWCL)~%AtFun0=$*(m)^2v#SvEO{6N8kSJ9$ge<%<+Bf!0{?l$+&Nbjy48-D8ZL24%?| zITcku`>UEV)?@ay;J-B87R^hHk~s;puP*<(OAL*Jo6ubqv!k3kcb&9ut`*Se+=NsJ zzdOl2Dh~CtnUC}M13@_a-o7BlP25!%Q8nGpjxKn!$$tZyr))GYS6&l3Zd3N8kW4_p zH5RB`iEAjbYrGo1OZkh4OFBO<0a~vn%{Z&aNi}pV1ZcLIsF5r}y2qb2RG z`SnuBgeE+|hvncR{ei*n&d~`^I zYYXlUJ*n0fqp+W}Y-_RiMayzuB*DioA}lXHp_bCAv}2A%~4d`{ORxqzzY z2-wgH!fQA|x#-F;l9AltfN>^q1U8Xm-u$OI=Do0$+|2>`q$xMV34J03bvlk#g zgN7g4IE(mG8LiFm`?MCEkh$_w)hEd9#q^Iz^j>9RfHLWGFl5x{Q(}ygxJQ;Xe@P;x z%53JaBgB+Pm7RvuOkpHhve+PI@0G@SZuymF1y`usivqsT3`TWcK!aNjPZYG3WVSfl z!$V(WWzl@CY~;B4%SoFCceP!kLYMvn_JD~0VTgrB3{G=Z?Id{-~x?{HcO1(Lcx{lUS~;?HBoHO66hNh zxzD1Aw?oqAZAd&$7at#Agb&!%wd+1h?ZBTU!#Orj4VH#dsbIy#iBsSgqjfhHQ~PXV zI?`>qqXAO>*+|HZ>T3FN$$7;ds~}QY6)C7F?EBl$v!;PEn_FOzZB4ESkcwCsrD_#9 zeBLF=;4+H)uVDDsKWd_1hh(b#_oLTocM^qsbz5F6)eb>ou^6OX`EGw#nanUt?!n=$}} zoN%U`RLSOzprE)0K-g)HZw{Z)H1{@k) zee;}+S>l@d#Tn>BHp1M=`!;H1Tvj!N=-N97GV_tYeNJ`c(*AshbP4l*pUf%r(wTk` zS3`@^7OEEfOJMhQy7e%2yo2YyxU7ukRW}ii84qRSoE0NuL@mLsHH9gR4xlif2@gXCyjh9niHC?(Wzw|p`6mYVGx&V{#(C~NG4By;vBv4C z!Dx(O7%)1Dhi#$X`$g-I`dK(Qyot~@Bs1889U?1jh|#3v(B!k=z@r8l3-SWgiR!uB zcIwUzTY{%QI=rx=iy}vL8nMT2l4V?vJw}C4WU((nK?|p%GtRee)m7eqA+hPC1;5bw zh5@@%)Os+cm+6sh#Btbb=UQ7oBi4LYPH6%TRCt{2`w9p!#FXr?{~u0%%ltb7^s%AeVID5~TU!T?L_yo;$C%MpqJxC%6gWWq%@yZcbAJBWlg7 zhwJC$Xm{_)(s$%eS zzd8X`bZSep4NmX+mUaX!;8*+9qABnMvG!Vo%% z5xR_km>3no=s?Z5Kdi1^?U3o{sqbgQWh8}4|xvtF7*)E3GL8IR+Ey)s(?eq7jhst|Un_vA6VWqaVwK$E2`9i;HEL&DJd9x2fF~?NGY0gG~9J4$_<216%@` z4>&5-B8EKcBbD`gk6$g32i1FBVbu^cupn@+*IweXC<9>y(utjt(KQ*eqGb%F`kky9 zaG|^xi2~EllB6vwKguGiegSp7jqt&wliNJDq|_vGIDi4P1lu7| zNG)@HHfD@HXFoWATi5e|s@^SC=X3TdLcccK{Pz8x2id!3VE-1ts}rEi0xlLG)g{@j z2mi*Ye6R_4qwTwojlFAx6)+*E)R`E7pBQ+5$I#{@*QtL7e}e5L;CKiPinkLCHtuIN z61GQQu^FSn?J)SEs>{wVYv48d&k^3NX3fB&4kIUIm5dGsUscqcV6H|^7|D0K+VD_NcJ<&W|(yPF{MpEj$K$R0Y`Pbs@ zm-xXgE67r-?g(?~)&L}!ic3@?3DmVn(4>_s>nY0_fXMlQhhhghu`yu9P0Jpq= zZ`$uxi{D#KgPoI-!hg!$B$Z|Ur!3QjRKj}K8;e%ItE4WHikmmriULI8OSLanip>~lz|K8>Rjg`)R91r}D;sc<=|&*pJz05KYY=R`--1 zT?b-|HbJ*@@aP~VB#)Faj`C}ZmRsU59qV>dLqnvNdu7eLgAfaLjydGY_$N?a!-^*L z3?i-RkdiDB;#kC9y2G!(?N}x?-*zy9l_B(-+5D%vF4b2RAuu;zNu0PCgh7rv_QHi| z+xPNJY`u`k#Z-1^fK~=*SBH$iT9r@xn=#;^o3Ebz$&d{u6L(R3IWQAT${8e7X^uq} zoO5QQH^6G0bMnz2kHtD3Vrn7SkSvP_(|h0EoPU{IK5Bvi^1X*)U1J|7#SWBePK zzlWlm5eY}wn3+PB(?~&@VPkz-(+SnjdBNERao<}>$;mgIQ0i)LTW#}$WAWFrj3YE$7q3kL3-o7l$DzQD zQ(+k%TNs5vWweQsZ@}kAXcHTk^>*TKpSmKNtgF3!m+Uv>qFIP3Ny4W(&gYd-+qB!hisyOmOqk0Ih1HO9nff0;gLua-dmm3<0&&E8Fe7 zNJ07RM4FKeNE1ay@Rlt@^T-5W0tsJeIL>Cq-!5H4`^F&Sd36%s40Yu%=O0$YC_026 zC|>6(afNNxEg*2}`8pLRvvghZ9-V;;EQ{<9iTVnWPh&UUme5I}!ZULZ-^vi=*?rxi zms!q|mw?!C*(C}xINz+GtlILjRKAxQD9IDl7E96E#AP&|VbSDKRc7K&!{2sdnb;Sr zih229zwoJ(!R0t=Yz9WVG!&%e?d_@*92RxrOehyhtEL6Fwcs+_ma7I}p*3@!5BQ&L zuXxe-2!=9)Itk=f2Gq{5vQPY)uOAZkk~HaODIqL^=Nl%F0<7NK4Bzs#ra6;*N5-D! zQZ6ktR!=At=QqYI4*@Rxs4^9f8fLE9o*o3`Z2>v~ta7th6?Zto&nXU$^|q!^YN!Lhj6zJ2_$#Y$6v}_7v!wL7zCua^ z2Z(#fB+}s!KC26d2HRxQ!%X(f_B#TlY_5V0yN-;F>pUt`&NjA`AU0=1CU zoF#HzSnew@~H1>qCiwR_w8k?5FC@rMaAmI|o)j z!qm{YyIxJXb=5>j5*fcdPWG|pP>}rMirbbVwgAVEGVBx!G7P8anYvlN+v|r+GcczS z6LT>(JLXCk@OaDi)WdDZ8M)a7OZE?VE`(K`n8TsNY)ImpxbIz)%m=C6_5wv&%*Q=0 zw-S%ztx@2f#4rElsRJnKwkWYJB>W+gc2JBVW^@$9mWhymL3p#&F@&|?gd8lDK^eY- zYB&~0DaWWVFd=bp!yx#LvpkRkPkexK0U}TBV=3!=oUbLTkgaEDbjz0dS692#UspL2 z0dKxw_hsTHxtD$%g0JVz5ImQ;xF9-3R4o(3RWD&0q3s7g`xLH6j+M)>uMH|Kj)>%oQ;DO}O= zBBzm~8>@70MH?otJHTww&7R8F;VQKTF0o{Lq*0Lf{q2q`eMe$pS2XDEdady=Os0=Nd`I`Sn1w8A0g{Z!Tcce>!yD zg;W#MyFx=MKkhusnD8pXbRE+CGFrA5z>c-)Y1qHh2Oos*z(HaUhaNkU4WG{weIkb^ zX9!H3xIm2uXIQ>Uol56=U@5ptW+b~{h(EKCRmghb|+w-56L|4u|)*FMPh(tvF=Cfr@BJ$`~?v7QA(o;=ou-`GR*^GC1aj zs!xgw|BA)`=8ZoBn02D3ET1*>Q6M#$T#Uta;`}|Pt_Sdh!FaTH)UAp6{z*Xo?w|&; zZca++KPR%kj=^OJ)BwlQ)0VB18XFZfGkLY%ML_zry-67*tRE-*7>xxx7*{SL(TgDm*e=F4|g@oH_`RCOGoXOH3PaEIkssTS?BnzmH2z+Aeb z5CunGb<0T?>Nm7OVmxqGR(07BFlipWgiW4k5+5LP+}`b0rU>&vF7oT0NM9Vmcj3o3E{0g#Vy|p|ttLIEeNBGGRmqc+SN1@q2u3bGvxl z$SNYshzY)O2(`xNCFGhsYckN>Ulr}=fgOdDG>m33HHiL}%+Tgr^~%M(YJQ5&kI`zQF|)94kA}V{#D2fy(!Y+_R=b7t9yv zyX6GCZCUgYR#5iW-PpjX8%yPM61khPnI=JT6dKCxjC?y4P5NOX1ch{YkG1z+mv`^_ zPKGun1Ihy(pjC~SKy@XPxH>IZ8GHukgwPyiUkX)u zgwT;20tPC;%gE1caq{8cJ?vX@r>7MrV;Yb7@6cM#*r(;rSVxDvq;7$W&>#hMRpKQ_ zeq#&gQ=59jC8r@if~@wE@gU(}#=B1=1{sdX|5(V1;EWI(U+7zWZ!`)nqAtI`(U4`p z{e0*GADBAe?DFKE(B}iMtFps98;Mvty%t?4A~zoRmhRX#%^(!2I??LyCH zTR%%M`?N<1(jM7Bi=&##8zqV|IKqM>VCq`!4{@@AKzdGThdV7&wAB6#eCv2odN=eJ zknt2v++P#(4215ffQ#dsfBe0eQt|ZalrTz3awbDX9sU~)EXT~-?Q+Z&;UmCo?-@MEx| z^HG(795-!iTtF>if0_OTlTHdwo@Rcp$|#6%aTpqs_mE&qzCGFNs^QA1gpR6vJAoxhX}5wUAy=8k5namx+oZ>Zogz&02z)%=2*GS>@UyGr6e z@cqYF6lWQX4K+;}R8^MT85zofq_zxx{jSB$h*3_?CqC~3d|szSozbI}=hZf2`qe_i ztS>sOVIjMKR+yDrMq1j#n3>OM)0{%>s+-mnwHSNVImJDRf``~sAiVEiT&5in1yn8m zYBl>&o-~~TAK_;AO4rqL*SkY}%G#sMxoD5Wvuwh02SiKQnr857xhq!5P1+nJn(s~b zPvWs&@&683tI@<>IyAYZAYI{uJyh*sxgfn`DD7Z2v%f{VyfQ< ztL#P35D8|;Qzd7Z(7C!wZR+%KPKTUQ)0I@GnovW7WWSeR#pGzq{a_M3dh7}Z)u1{- zx6O)kGHS<<&$O^P-DR#_ft_>b98JbLDX ziOLve1kmv``Gi+>(l^P8U(a;`Rm#q;l-7mH*Mg?o-SGgYQypRs_K8+Q{fPxpou$gj z!W?(t7rPWvR-ld%s5i8l_V=dOLpSt6Y{-c6o2zeSmIGkvaHCG^t?!*c@%dk|@l(*0 zC`gh7LM1jq5*3XRrIW{+-+8Hm=|A($D0fBr%N)p$LQ0t-iC^n#Oe>BMR&zsYx)JFH zTDWvdf-%@5>jSP~PVQ8k-*n~%InbiuNM7d&6U;S^kU?O5u;nrLCv~@ZXV@fVN*a4u zkC<^$-Q9vfc{z;OJ~*xj%=;3%NC%Hy{J}ES83P`{`$OF9m~3IY2YUuz-6U?kY;1E0 z_DClrt@^`a3tnZ{++<<8O6%E<2i+VdHZzzL^d|~NC;U*4e7;QSmXtr|rCsZ=nVDWAe8s z9b7DHw(_&TjIO%%rq~4XonX5G(g)GJ}}mY+Z2bO6jR0 zgBD<^2mwV#ZRSi)yRA?~Z9g_1AXFk4kW@X8(LgyQcmhHl>XkC)5~sl|!?42jqcaUlAqx!nq*5;a7~ za0?iiMe7BlxJTYO%+XI9L^M|YK4gJPSd2D$XV3Zqtw$gbC7118tRC_gHRI-)UvtJ4 zDxbOzY*d4{$dVk>$87s{DouPHUptI)-4e$$iPA_Hb3|#lxK8vX7Hd%wT{d-i3Wk%L zj9sl*x!kp$7yqVL9$86_kf}Sr%01~lbff&}xH>nJCmy$`OH z4$LgE8TAqY)&g@}852n9E!Keys7z&`o5EE`8I0roiXCPDdc*yalV0!0J+$`z?5zPg z_v)}mDPQN8t+29gbRybvE_eU5he0u`^tb>I7e_rdHjktF`fKfbFXUT zAQRGGH0L04U%Ml^^!^lW(&B0J3G$q3IEzlz)yDPJc2Xs#P1EK_@>)Q$25C{Ucq$j| zg|nk|yOSFhNW|uW@L3q-j@mplV}DJGMrH&7(RLex8{c|;|H3qs5sUraAtsIpZ5J?w!( zEYwvNWdOZfX*YvVDnm2?1uDD2)=dy^CbaXKFca0iC+z9HsC)6BbQN7xFInJ#X5*iu z$A|Q~N3DH)cEM~8NORok4lQNiCn&lXX0pY?~JHZ*+YcuNt`~5z?V3 zDH_3lc?&vy+Po-XH(x=E8j&D+^VL2!?*Zez+R?8ya?cmohR&x= zRGjI8&&!iVw^a6%lbIp;BWh+nbr=d-Arf+knu}VstAoGH>;?xV5!-AHz`(6myk^YU z&_j1%3OTuYIDReF5K<|W4WI8nc!8YEY@J|}Z5a=ypV=ZPNIrM6Xd9)#c89FJdt;2_uQM`Wof^uEx+g ztFubss0V5Oy+KfAwk6OYBrQky1_-e5iX4a^oJyiktg{+9HZfs{RyLBXomXObwP(o@ zfK5YYQY(rv0iUb_MsKH9cyj}kCA<7NM^q(h?br(Z5s{aRkL4&@ta@7p|G7v%$ zwAV1~?M#%1@~PUl<2RAU(NeEN)yY-IDv{tCv3C=(?7esF&=jz_((F?Ft;nyhYGbAe7x#d!b$_O6E53{(kayBDMD%?Ict z8p3OIAULaC+5muexBf9$md-UUr4VD=DFDz73$_=)FqL~TA>>#RqLgazn_Uch+Y6Q7 zyoPd5SyjK1QUXhcbhsdJZPmff^BgQ=_}sNWs0erjgc1-!KnTT?`M1zt;ph0nz%qgV zlu=lg+WM*NVsV6?oW3K3sybqElh*0B-$x%rzW!hErR|>vpt5KHuX!d-sdlJ_^(yR+ zbZnk!A7swk1B`~lmBG1$5FDC&0etZH07`9Wp>$1(T?s3ie%VZbW-J9Eq&maSRB0hw zk_afy^g$Lrh;^Jj-GpV^h{6!BTvaULM!d-wOfLcBZ)CrRj*K8_+Z*E|(_ZR4+*n+Uv-Y2)b^-4Gx#RPFjVRDY@mS z?OYu8kuZW*(}$+%h@u#tqa$cFkj~gXNgukgxa0wGP zj&GcRI@n2JRd61q8eVrssg7wnUEw}C@wf2^mgB+kfgK+&<)xhG{F~L)B3)v(|$T zon#ui>*`|K*&D&835NTTYCg8s0AS3)HcWdeI8S2oMt_I@Ga!^6ddo-%g*QSut;@|HQiXqpbU(Z*<>lo|{@mf%+S=k* z?!A{kc;6rK8^8YV#-5+Y<^o}0kV+1=4YgW@EX#QILW_!(Edo(CROzTYxNs=%uQPg+a+hZAHnoDT9 zhG7V^#x#xx^e`c?A`9A4QBYqwI`JaAO}=}`7D>?kvMf2!lwP^EJVJAdqX56#rd(Z` z*tOmpimG9irw@W?xP49joIo*f;n4b$5PnZwJ~gG;w0>%(FbQ|2%H1Y zrD~05lK=GKkMO?tz3;MvGr;olGJp8K_wkP(`pCrR7Xh$lvrU>ytgedrh4u9&rm~p% z#Ncy!hPBf|46Mv%O~j!;z^{4HuS54kmPL=tw9Aw#4JwUQN|ot`%AxO)#L>RN8TM## zWK;apCPk^zptXHr>TAPTX1Ql|-s<=xR_D5D6ZG_-lQ^Wg`5fii^3=PTm~wOQ+B*lz zOr7cyZfARJtCHs#-PV>6ebUBj>HSbu9kW!%ZB6GHTTYeM)&;Q}(e#04c3)2;OX7Wx zVCOkFwt?JFEegn_@pI%R^KV#=cKHElIOb)|X(rJL6;_riR4Za#WLbuyC=^AnNjU#L zdCAAP*K}asabHRprcD%jqW)-D!qTnN+}9f3c2$lZX;89z;C!(~;Coc27{+>@Hx-=M z*VieEg0;0Z0M4I3Kl1#MBS!#eHk-8DZH^r~hPr16ZFzZlYUw0N;+am@X(r*t8fQ+| z0NB~-lBFRfV}IB5BHA9a#EbgTm#3XpCheCdgz8O1$^>EHVOXWHjL0fgC@2n0@)s1s?#xL#Y9i~3U!w9_=6d0es#Zg+RFdtOXz z{$O+@X2m>^ixL?>(KxzR#kNf`4Jk_lW(ok3IFJ2WUH?1|%dH+HCT&go%66aHcq<tZ9TQk=5UAK)m3P_TOQl(BD`ZL|#`>_|CFI;RB&H(3G@zIZdl;8TT-{O_8d?mm8 zyT3~mMf~zF|1!;{Shvf|%Y5*IALNT){35^ko4-ktB;0)S&HT>q{LVnmb6%u zT@=s>6iyry6Um)+7e9zOdh`%pXNNRR_LX7IYs#fbJU7{l0uRG>i2Uwuv#$5wULckg zWg!XN%N?T`^g!EmIzS6iA!Vj+M;Oa2H^idqbbZXB?Afp!0(U%9O`@R3dU;N9>4vUJRnyT8 z3suvRB&Fv<6GKr9Efkf_A--mo=M)RK(w_fVB>VIt8Cf+sdAx?EsXeJw3D=9zbroGx z*w}1i>*)xsQ^>9A=!Q9T(eyyOr?Jhy(I`y57j;(zM=B zjEw+Bp*QnD7O{>B5}CEKsJU%718UapMWE@%)b45Mbtu=DdkS|dX&fFHoK4#yPm_H& zKE2KkhUMT?m&x;V=47HI$rxtoK)!{0y&AyUkY9W2x@2yi|cA9ntSD2n z)kzxBo#rN$#-U3FXx+4@COT2zqNp16)uXtrt+CRc8!A*PrCo4dZxICt17{HD{I`Gm zx4G}W`$&fde2SvrPyXaj*x1aoMZF~cmc7?OKU7U0xX^= zE)c7lfugE&abliQ-t!gX03CRPL6yB>muquJspC|l;+QC^isyQ$@~)AkRjSPFxJ$j^ zkt7NQm)df0s*Qmz^&;Cs5ElnX2X+<7^Nga%CuaJ?A$$ujk2{9oIFDYa59VjljS5od zb{yvzS~R+UZBegR$g_-d z1IEVeonV@b()RK^gFGW+_lBX?^r_dMEGxa;@9b+OO(N`abpd6&`HjbEA zWpAR0#@+(ErW+Wxm|vgA?F|x{qrK)}vmFd32m6z9vwmMu)xpK2s6xrE|Ffza*yY+_ zv^ZUC0QP` zz1kb|bUG&f&Ly&NR860&TsOQEHLMbLxkj_uK~W8{<0uN&*LNTbC|j3@vN;?<5OD3a z*K*~RSJG;=a9x);j*%pZG)>8}Z1COfCq!vMC(2TyR0i4LP;Uoy;bIeG24my?XjgUc zF5|6pHGanG&_lwJqs$-ZYaTF0nF_tY3-g0JV&(Is6 zt}PGhi^F%nG>!(%2SriQ4IACCNRo&o5_M)p)zD4rzwU9S z44iphfFEm|K2ZlrVso=emW(qthCz96q;WJ;X){ft!Pvj;)Yxh7?yzMUki^_V6u4w* ziX=&c*Hy|Uu`j-(BF}NE4K_AgL{UQ7F|jR;Bo0VpG4^iSWtuIYJTpe1TTx^jTb{W~ z^F!ewTC!vUZ-2vaC&yWEtJCF)W+T&c;Ig<3#{)-uo!Ba2o+Q zv|Pp5xoh9lq~|-jp@L;utghBavaZd|7Ov}wnq!_4dV-3Dtf6Xxu_4XSfu0qTEYID+ z%$qs`c-@`%jR^W*iX#p5ZX8pNOEavorgC1uPOD(;a1}*W@%@Ov4=J0M_d9;ki(a&A zUaRZ8_r34s6QB45vMh7YJ@=p}3cvJAzr@HVoNeFxZ((Je&cO}GL`4W{Gb2#2dEE~ z>;P`K?j*0j>&8K5J?U%z$R{5b$8yh2i=4iZ7yz`Y>KL{|k!OUxCfF#&No)aVN z_P{FVA^(0{Z*jWKA|S3x8kSndRvcca-7+vMkYxq0vqM-UG&=#6iiM`CB$>=Car^IQ zdy(?RBH8dqKmE2n8FacY z<+0(=bYp6HLo}7`v8Hmguc*i?N zem;KuIPZSXjh}C>ioSrIgE6^?Wcti>ez|uf80N6x^fG zN4IQ3Z!x3CAeLEbSVD-X>y2d3B3qb$)RH9px%M07>hfU1FNvc;vrRM_Z8XCoi9+Hi z7^{Jsw!@S8cX-x+j3wg;%f=B7nJ3XR9koY>f7t&tZEt#sXHu5D7np6OJOJS{+6_W4 zT9U|mPBB@Qk!LB9?+q4GsnQVi9tC1AB#sj-OQ%3#s)^(GG2&FB8!D_Fu2FV&xw4)g za$&uLW29(PGyNWwDoN%xjHbmry=|c(z5jAWmZr$+!2nvH(U_XlRPF={%Z&=ADH>20 z)?1XV47a_7Q(YqTyZd4e{Nx*6$G!L7`@BpOZf$LG@4ff(rZ>KR>T9~8LalBI#zwr$ z*qD?h-yi+mRFLjJr|NSWb9>NGQ&sXTLdrAlxb;f@<@4X-!o?OxRt$;>OF@!kws*Q5 zTCG!dO#E&O$5OcU#*;*WPnISl%|X-DDY9sQW<{ElB?# zSple;SjAbkxCX<1Ll^a7-t@-T^Q-s%_YM&EmSq^0jHan{y%1K$t*gx5bl?lGJj$Q__5FPE(_iD% z$yJtWC7hC=_3dqvZfvyBwB5wu_>nr{1hM|2xHO>dCwS^CXMs5I7b9n@B^*aW)iiw1 zN0E}j!RdxI7vxn<$8xFy#1<@Zn6`tgsI;~&;8d4-rHtvnTjcpbf>bvwQDdjczqTGG z$aV|&w{E{;@bAR+vFeq5HPTGGjG}4;UYp##v}RK_blwfMpw)?}*1&NLE_6MN#mpWq zd$^%+fnQs#4Gdq4qF{5gh3EMLj;q_+p6ITg=Mq{^ha=5$A&sqbM@WQh8*}tC~L6RL*hMX`0G! z{QAF}C}uP%YRgB6pZNn)_nU*qoa_IP_RjXc)EJ{wG>BJwjE(gt*pFPzj5kY$-P3W-CXD^4u)({FwSpa0T#`Q)d*imEDHcg;!O_LFyvG@<<<;?F;D z|KR7PMumI-?L8BbxJSsC805oA?mW2?jOzwaNp_UaQ{b$V&n$iy=EAAjYis8#Jje=g626Vjw| zTOYTFZxFJgqU+{h0(qYG*8W#vFEri2w99ncI}~V`mPH&#gi%bbN3EMx-sp=7`R;Cc zBG0m(z|iC`!zz`LWMy1Yt|$oH_RR5FNs@7@4ZiArie@}|u}lKyeq>RMq*RcL$@NS@ z4O}Ah-OK8lp{P3Po^7qJ=J;MnwWiN4bMzPdyhhBTkz``{oXou7TKN!1$HLhjp@^_z-91A9JQbw82BA$n<44?1_hgTC~_ zg%XWnjSW@R=(M{;alSA(PpU%?|6CM>VEyc)S|dp^s&3#1DN&TL)ToT5vtqX`qvrTvBxd%P#Yo=HHPPqglZ$aPEh{xkKsD5`I2@VU%mjbX(J%RSp`erj2Dwirb&hBh9wr{(03igGUcjRLtzx579qK;Agd~x zV)Pg+Do7$j+O6YfJ(td=} z+S?cU{Z62;cDOQNY;0_GSt=KlD$65@)T}JI|NOLA#3;6Je7oK3B1;lM81tov9;H+= zIdY_q*E<$z|b|0 z9IDSu1RnnS6C69TOcZ!iZ+es1UaD@)2k118DA$C}u_VisDh(pv9W*U+KV6du$zKu3-Oz?J0BQ({UYEDP-Hn-ob<{L zyIW?bHd)4WKOqEMbiv0|wLxQ0RrTJ8C}O&(mwk3Gx)aMB(-!}%PWd9?MGA^$a&oOU z&~MK3f{l$PVHnJ`T9Oq7&9KHY$h=^%?M%`fRmn(`45pUSWTC;KsHmEStf;7}MxKvz z=IwHAkWB2y%=Wer001BWNklN0Kdyq&ZVM z6htqgUUzUDXP2>IXXJSy*bvpF1L@T4jd@0~SsbG2CacReKKZGK0a0VV>daAo`b{sR zNK;|vtSC^x>S}Eu;hQEgKmO{Q_{68b#s~iHvjjoRk+lZz{MlD?XvrZAJYiTY!HHw5 z{M|o&e&n-ny#6#RufBn#msC#Lc)jvv*P$DuP&)~b9ks?4&JC!tMv%G4vAkG`BTb?n z7udpUj{;IrfUFJybno%u@`hEah~MorXSy7KFt9aDn>O!q+W|BbzFQE(o7?pBNHsUvtrn>kYByg48xf9jTS2L+(8Pb(x5YmAyi0% z=3o^qH2b4fQmzY<=yvC6ghskCH{8J;3x07nK%E$t>igKl90QNLch0@Qn4+C|LIrX zH1YG3IGj1r`mT4pijCqq9*rMnJ%4KK`6JdDYWfOweU*#hGd$jUgxlo1i3t|3K^ta? zZfpEvD+*A0w~f3gka{Hu-LS~B45Mu0yKMrmGXTz6ktPvN^)N~lPIWH{yf&s?p1NHK zybkr%qqMg#^2Ow1W6$pwocqy!>O9Wc3fhvrkmsObl?DR-S(=a~;-ZVa&de6CqG}@y zj^QwMiDq}V%yDJ+4!*){fZlHwon(UFys}iGR@-%*=yrWBTx?M`Gjw(Ku0iNA+QlVth*iC26jRr%$aHSsJ>X5I)&)dp^BYmD1oMOu@Y$_@z)weO#s>xF z;czc(VyAU9O-HW?-u9$ByP^u0-h+sI&)UwVkxQNnnazHgLqfV_ooL;(kyVo<1znM; zEvx9-ZoRJA^5}GZP8_WvQIHooimZ?qAR&<^0a4&n6a}_Z5p`tUgtQ zw%MlbAjujx@Jcq~r`d?kQBfPn(mlN6SkBdE%%r83XX#Y>)})w4@eC6g&9G?HMRRp) zr;92}SenF0;w4E~PIYP$v$tuOXDM!Ly9d(S2X2U_NeqgOY^;$-!WT4izk{XeV=mrl zF5yKQr%w(sHsWAvQ!wp0f!j`%yEu5MZN5N%G@_!nH;O#J9%aP0M$1Dpq+y}3InX4J}*t4pL(Ocd8P5)N6$XQr#|yFJU`_0$wL^1 z&Yds6PTY7UiB31*x8M60{Kl`o6~~ZA2!s8hqGvC3`1=oifv2Cjh+$~lbmJM`_~S3e zGAuDfP!#;deGl->Z$CBmH@)Y7`+0GkiprmU;4>h>PrUs~{LJOsox8ZPX!7U(^&j{@ z{@0(IdY<>gg`T#>O*4rg)j4xiWSc<{(QI~Ulv1oxV?;*RsWk9rlq~i(4aIThbapl< z*Oq(c76+phCUJ;by@hz=!{U82k1RNcrkjJ~8!$GG3dTme-J#o^tg*58y^ErtTwfsy zynXcs`q39gnzn0A;;5%JKN*CRIGicGbkOMcM`ksoOO*!KB`>9suAmzh-whw)E8Cx# z``!=cXQuQ9YKa%$aE!gzRX?*zii9WPZ}7DD9j@$jKGzyFR=v&+rtM%kRVWIg zz@3^Y+T~iW+%WmT<0!ze%cKXaNylM`>0ARnfQDWj+P-}N(49bGZMDbP@O?J7+`&-N zyhxLXZgUgOu&6Xv2fFWzMjA(`x;Yh~voygfm8T{)QQ+ZJ8w)3Zk|Yfpi&F3ZvaAdq z%k!Kf%X$U@+00&4XXhd%Y*IBQ3Ot_6AD{Wzj#{H>?eI$LEt4;6Sy8Z@#RQHDL^cHo zw}u7oP=VLMuu90Xj9spgrHPOmT=G-b%ln}VFc zYva4^Uj4X0)eO8Kq1o(m$E{aWt&~__jN@9txk*|kDjA;ps>7L9n_uAUuaP> zM%~Lp--V*+HNhr-?}Mh{lQ~w026`F1s~#*TYts(_%`L*%GmWWZ5?M>il)!eq@BTC&+`o5ZBwc=M6+Hq&`lfD zE@PK#IMpR8jaACEWlEJgrd<~NYotLf-S4(=+d|>fZEfLon*?5mDDV~<#h-Lt_otLi zrNn9HdS1HxMqaV}1`b8r@a!KW@0~T5BnhXoG?6kC^)lAsC<>6JzOF)!v|ugNZSPQB zIy|z)%QJBjo$CCH0>CVlNs|b-vpum(|NR2z;gA%WTr2R}+j!k3imFkruV9wS3-NM? zO$%m)E++(`cwMbx5GC_dXeU1`fLXCwJG{ivAj$g;{OKJ^GMzx^6&HHU832T2~#^|CT& zsgHq>s*0xJw9HU5EEH9}JVe&AaNmh zk}q{WIzdNca@-&N-9V{Q)5mo+fPr@NwCDq*=v_!X`>Rpl?Y6e?I-|gw?bFb9Ui3j( zlXWhb=XlA|J-qtR&vGn{Q7?QD_glXX=l_bL`%Tn7v!cIUb!y8~w*kVJ%Nm)DFA8Ze zNi)oYo)=DSiB5BK?5@(!rc32IUUzy1?^KtF0*}vyAD;O94+5M4tfkrrEwHcuAuB3| zRT53F(4Sg|Q`E(bDK#Z$r|DBJm#}SO_Z6nDVr%$c`5QYh@mPdU8XS`Hx3OP8Y9ih=1thun>#86Wj%gcm*cVA_Sy-Cz9)}8yRM+aVK zuyZO^dLmL$KpcgFAvC29J!}#yNz!GJVmL@Vn4d*L;;?m^Tdcb{WS+!rKSZ(dQQYp= zDbn$7wc2fNjqrxOPIG15GM&yoMPK1 z=>%<#a=ymW0GLY?fH|bq@(99+m4<~3+;Ht_-ud=dp~w<`5cAjfeU?vs_M5!+&g%xc zypkmGaQ*-q`8# z*0KP zckJ7Hl*Z~+LyV1(l9ADEZemy^oN5EV+ddG3MAzpFsf`?8ES$Qd&>!3wR87Y$m4$zFF)-&4*Zt2FvAFq8J1Vs( za=Ohe8i$V2ZEh{p-10g*f@i$7PL@gJh1gDJbF`c_!=&WY#01nF-ewYq=%#2WWN9MC zeS5a+!x_bG^4%kM<{uMKDQL-(HLPAkx(roDa@3B9I zL)8tCM7c*UQW{mA+i!g#AO854L6QmmF1E8fKx63Az_B_@(}^XStVnp_%?-Zw%@w}+ zm2b~Izj-0_jmwVB@^Wo3LLSEvK@j2j30*HjR|=v;=ESiEwrvRNU@tCQY+|Z0GJ{~8T5ql)tw;Cmw1&-~`>x;t45*iThrWK$ao6E@ zkVh9uT3;qS_vhr{IbgQshHM;0F5iqA1>d34cnRIsHku(w@blcTo$3N$h=ToDZuLtbilSoJWfV;l zE)q#NP%)bprk>Gk`y5)SVCX7QB9Ue)FDku;TFt>SM^AB8;?H8$*W$-*3$v&7n{8Hb=MQ;>i`6)$4xh#;zJ+# z5^sFnZFpY5Bj0$6BuP1SYLzS(qUvcTvdAz>F-;p3dhQhkmZ5Tfz0F^K@H71ETVBcP zav3*>dGMjfIDDuv@xl%xK-#T8+Lk$1Dk^}j_&Hwp#_Rb{|Ia7L^Mc1CmA$Te@43Iu z@oL5!uL?MJxQtU4+xzY97Tc{5Rm#xR0$nLscEmZ%&5UQB+u_WqRWz-auw*%|8?jv8 zy%ha!3&V0StP<_*ixbbku*J%0Z(qcAsv|XMSy6hPhOLoWtlw>6In|k7i1VT-3eqG& zDPK+6en|XX;W>&t#1Ar@36rBmQQ&pOSa_weir;OId_U71gHGW4(3z6-09+L7(r)lk~u9 zV_B9G1s+A7ajy9_*2>pml_~>01d(-*E@(}GFcLtgs={{4af~rw_Pmg0%Oy!tYGn;e zp1vJDzrM|X{G$&Iem;I|h1b05M$$wy=hin`Jn-2^`R5P&=(@_CuezSfk%DJDv0nVF z%bBYV@yH`j@rh48%tt@@5aqJX&;RV5lr4p=W=N$Xj2)_#67T=B(Miu+Zh8T4yysTd zjx2NamB;z34}J#E4^b6`6USG1^BeEj1H2Lsf9(k#{@SS1`G5GeHxK?T52=kceKm%m%cd1scrn&85PEafa(V*+>Y+%}DWJTct|DR@lj;5Oj zniH7EV@~2w)S(Z+wLVBZn4iT~%N#Z*c{ldP-u)T0I$1+4zZkiC3r6i0k|-n!eZ0*J zD4K>8241n3u^}r8rHbGc4_^$nQzMCkk#X8>SLMtVhf!pi$DiDwW`!f2dEKy3H3Q!r zov5=)6|yXy2-21M%0vx^z0tor-zMKpz8Mk4;=K&rp7m?bYpAA@${ig_ifZlGxa~xsoIhs;nJ5{34A8XF) zrj4xVBc%sf0!PJ?(=W({@Pn z$;=pClX{bcWwx^>$OSw3v#bYCQPGw-Ub>1R(#SNQ_dR|b081)(nI3bfYH`yM;jieq z9_QBEl+BFa+uCg`?iE*xQW<2MBS!=SDM_<|%H#UQCQ0aFPnfprmpu9z@-&?pMbW4( z9ip|fK2UeFo!ZECHA`-H(NJ}Ra@oN9&VLv@rY*e+eeD-`=IINR=TPew@!G>n5GKJ+Bia;#GTADQRnSvaG}>743q5D zI*?#c;nq}zJeLMMPr-Fo#=sdwGh|XGU8>aa7Fc9IjNlBAhB2LI*3liC%F$JV0l#;C z#F9%CkJs@w!+(XL4mY!oDgX?#~=fF28phW ztd+fTwZqZt5fb`cN~j~i(N4B#_mh$UUcLHdZpvRnCsa6gxJt!8N06WZg(E&zw7MCj?%+DfA3Tx&mUTnRFRr5IA)|X)YpK!b1K+1gJ%9-z>l&(T9 z--1@V4HTO!iHV{}e2+yzn#5vfF+_k+XVo|ZuY;zWR2zqgLT|uV9tml8qD)m~@*EWC zxuX;_xBGiR+O*4}aWZF6V=p+v4<4BJM(p~;kNTMP3eM6Jf!m(D^)&SILYf-GfSu=8 zk*3*zTm0OG7IEld?*ZoF2))isv8hXmop_y{Sk$9eu~YVix`Dj8RtIE1F_Byr4zjW%QvReKZ=ZYcZwJ)>-xD3vLdOpM;J&*oMaT~0W6 zVTTh(myua`MC+?lHVJuOs8q~rcF41A z0X^t6CiJ^#hKX)iV<0_zPgNC}ER(RE3Tc`wL>KFWv|X-J9thn&HgzZ|v(p@7F9= zH|@*nSOcIGCQH$^ELEzUT0RAU+jTjAQPhleW5J=TQ0CMLQT_;mm@o*bmokDl;{1gj zjvZY>QDjaWZSdsNn>3tc>~GJql-AbzSjoewHiQ<=1WKwb?E>^H-@g4u9QhdK>jwZ0 zLOiMB+{)%g7i)sK08CyZregEb@*D8o*3|5G(Y3XxmPVRHsJd|=&5!=EEE#KDXTFRz z>l8`&ENSyWyl4I!MRZ}pK>x&}-ThbfE>JW&&CRLImEq_%H!0Va@w=`00BzZ2Lf<6{ zeGJPPt8)#TBdV%`B0CcsTC*Ywee7}#w>w%3pZ3M=$HeuACH##YWKE@XVudV?$F}FP ztPsWr@SBtT(S^UD?4;jqQLe2_l#tyUmjcd;s$n}-BuOSt5{%wWC@%^WWif=do!Wo} zl*Z9zQ6;m}RhFacSX$FK>>Q;i3bwafbh^UycG}J3z3WwsYx6;QBT8f($3oY|rL?it z!Ra*wEj`DN0?uF9;mBG8T~|4Fw88oF+cYNl55j2414)!|rtc_sziUl5XAXAlCz3d# zv~(@Q+9GNDVa(dgh%<@(DCXQ)ymV$gc+%Q>Fh4tSEeTze`RhAPVoFwNUjY4JewM1X z%+=0IIBcClN;^c&FA<&pTZ-VRxu7g5{RwM{z0#k7*G4z2g}}KV-PRUPZFx38OOhmp z4tiUKC~#3!ZBO^P7-WQsBGc)5NXGuQ7S7N#RX-L11$o8zk;tO^ktZqLCoZ7bCgo!* zM7}%NF{qkOH(KBSn@Snk(1g%_*q@=_y=<-*({7qsnhYjW(@a8D?B3%AnxWxDuaYUL#`*NQKsKr;Zq#a}JRE@G$BZ(s}tap%# zi0Tw&HZN27gH4B@uZ0{pch{U7$y~7}YR|40k|hz^5Pi`$a=Kx_`bL|>t5r(2!OBXN z?d{f7H<~!~Q8f)svu4)W6;-2LTj|+>?e84SiY!gY3klggK^}@}(ad{HaJP%`oh&SV z6CaLQzcUG>RaHZ`tc6NlizpF3n4hJjR#~%7@e1?Jn396O^8o3^e+KU{Waebbl8jQh zrPu7c4LvWoni8Kv|+uE89(55{u3)-(E^~vdJcbBVc=qkxR8wo-mdK4gL zeQ|rgv>!E)21xvn_G9NTst)DV6#}n~qG^QP{nvygGLj+ZjiM-K>PZiWW>_R~NV&Fx z-)&CJOc%NE7TwW^DMGO=kCTKvjqu&^l9p*Zf}zlDjmQr4C&K!5T18QX-(;x_l1v(h zB=KaxelS0aT39TF*RoWraB}Gsu&1Ok#f0EoXz&*;lV4qNDJi?48YVK1W236#GP=0g zndmZ8HZ$6;%a)?ByyQ@;mWZN^uHPM@-}OV56(nTZ+oI$lNfK$2kfpJh-tAp)aTF{h zXm*fDq5!RaE71i3&_(8x2hUP%7#Q6uks@{w2La|qe{b(=ZVT@wO_PO83WR33JW(C+ z>(UoEY@Xr{>kZWOWxCs+hOIv(?0#b*QAowP9;G6heR(1gwOzbNpPK#)l8mbBGws8s z#Y})!)af-!-))ggCbn%3ws)4L?+c(c-5?HwvHIF=^4*wrnSXKrVeIiq@uLXR08!f| zYP;Acmq9HKrd2CtBNLoOA%M%UoDm_ay`h^nSsD)pWo)NLo@e`R9PX#wlo!%~Bb=uB zm;tb62t(n}>k_!_x#uIxQnDZ&8RF11Q*d!*d5~eJNz99~*V2q~mJcf&>XkIMOnG7m z001BWNklKLsKME3lG9v!dU@sUZUHqfeeMzhsH(`2d@ zn?tJ=o;jD`#{srJ`gdAR1-~mkuU}5oO&d)&(F_Y!)kah#pO1*6@v-mJ`z}k>J26{J z1AzX1N0uhItu0E`$%1bENP6<5{W8Z_i+|y;b&A8*X=w>GiMHHs|TcX@6qKpUn_FlSCaiegG-n_)#f$1zE= zbgWZ7DKx{H$lEMc8bpCR(s>`toMmNDekt<&M;4?(lo~YUfD|byBTa|TbwL#RM4^vW zs$j_Sm=c<-C}V>HzS~08dedN?7HJyK&2skJ3lLUUJukvENAE2gkp)+X0&h_2QZ-|$ z#Oc)c&oZLS8*G7PSrN^mSVPhju0B#mQ50IyHX9dRER?Awjebl6=OC7;RZ1v|LQxc4 z+~`d77aWdyDdplu3r$t9ZG+=S8+`AnO_Vgk=wU@r?XH>HjbcFZbq%X1ld?4YP)nVxFqiWN`gh6~WXXNa-G4)!BMnmXhY`Pm{b$`>LkX zwK`O-HLmj3NOvB`oY=7rm9{OyO0bYOt) zTgh*?HweObFkW2b#X>wuSy2b-X#Lm=&eOsym4zci9F1AS|DZtnjF}HWdcUEnI$nHm z3Rynm0*wL}-LMAi8>>_yaHn(AWm!g&RaWCQPA^@{L*279<59pkD2ry;EH+C;iEG+6 z)wIe}o!b|QD3S3Zm7{AF?2=7dBs{bE96Rnd+t#)gdIldOXSZ1l= z3~HR4TU}Pl3+iP{0;Iq9)FxM+Sw&G4&YWK1drxh0bX6yqkQoZz_&6)7$c3!yCDMJT zMjQobwHFTnnj$0Ze4W+$3wWlvM4;@y@paG`2;1Av)Y*zB^~X4AUrkx7kzV{X{<*(E z3ZI+X?2}{@xpE6?ls9D2 z14;K!sdGaGRWmq!N_girqb)YpJ+^p~j`{A_3KT~{H=gGm`;rPTyXH`FHBv@99Bw1Cibk*em#*#A zMrcfF_De0A_+7jZM>zm@=l;^Zs}@U)fm=FE(OGTy+RI2fK0pF1MCNvT2mr~cj;f$f zlz;MBMjzSJh5ogB|0^IE&!&MG_v-8e?26(8bDooL@ahYmlYEVmtR{7eomlm{RQ937 zDa&7ziCD=`oGZdI2%j9ya-jy?7Xk;t+!&PX^2FN8bTH}@$0)8aX@m`NJ|8!~va&xF z1$5zFD7|FBE|w%yZf>B{Qc~oEg1I_$7suigxlxgl6vsgrJ(p71yr=VkzpM#vQ-d%E zk~P12-tUZ(PuXTYwvx(RH{mq(DridN<8g7OX<*qw0+N?lT$f)w@0-@PA6bx3HwjgX z92lm6aKK7ntY?5?++B}_R?hH_M|yD%oiRE9C-#TTbpu3xv#$ocVpL9fybUcibA|O^ z$3+lwe+f+}UB)>DA>*%*@ay$9qLK{uL|nz)WobmPhCjQTIf|~IK1ufJ-kpD*f2Imy z5E;O>jnZrNdOmi?d}OK3n|58!WYUKlJKy~L;FxUYW4E4 z!Fmq0enrPzy$U=m@HUsijfG3ve+}$kgLHn^Ai7xmfC0E?2?IRObRulQVtC2Wy_aP{ zX4}%f&f!la=|b_+G_Z3e(J!y*%-)oK*BF;?^*CF)O6BV#M>5Gd{>u>IRWmOIJ@QPilj2>`gB?s_mD?IhBp8{X$#cnw;G~ z{VD`+{FT!9^TT}9!Jm-SLd2{+ctsbeX_a9zZszi|*1#M(#2@rmzo0CS&5lSl)ms)h zpf1k}93CzrCbK8a{r&2KP*_02OhvVWpM*32da0u?$j`S z4_@`n+}`81F`Hl&ttOCenF3VBqS~6*cQU#ck=VRhFBs-~BB ztTXFh?_n9T-XB>rgupzm{U=14Rs|5CDyW!23300(LKhAnZdFT_fL|vV2q4l8Zg}r4 zFt7?fsdqmbjb`uS22@&V{$80Kaef{iCyJ2p6T&E9MH)~!fbJ_s=D?KnKg&;M8EiMm zCRo2JA7D$rQ?yOvyD4r}yz7m@RV2YO`3n#zyIA~@@~|}5G|K@?&d`r*Zn806DU}+3 zMrs3WS55*mYz$ENi-kl7b{e=5Q=fpWgB8D?DQXuGgen@lhvH{V%*hh)pf+cfnj8*B zb7^%gnmTcsm=%sMZ^Boahn%{Kr;iN92Qv9F;e$KgBC1~=J|2J-hmc8^I>T4j*P=j` ztSZoU((D{Dsc0RG=J}Q^u63iQEpii=PDT10)Y|w)e?4FBf1BiVtI)dZMOD)`5qCQx z(2{=k!|OQzTV0MGqxG@=TBSY(1_j)E5QqmEC79g+p0&3jt$Vu#E#tWP-)-NYkOvN< z5R)GK!N?SXlM9XoWS)p_e`J|jQ7kPc^FbLa$l6h1YdOQ6(37J`=AV;4BZakPx;A%V z2M1+;oH*(fv#&Gn-rCQf+Pm*)*<+{_R4a_ltfFpaV+W2KYLIY|6vGAzoj45_>m%F; zMAQ-TGk*ptrQ$0cwg#=(vPz7n8yRZ_r3G-h_1+2a!yTl5nRa)5V@;>;-HTxw9UvKJ zDi%_&Ym!rMJrz2fSzi8Kk9<(eId|k}Ant0DpF!hmbP&5|qD4-*wsaba1@}K6|F4xAp>$yv)xQHDpi<(S=<(3!wDb-=L=meMgvrLi7kj0662b!?mC2b{NJ^RyDt_jFlP&hs7ht+UTqe~!$rT8DxrnDkNNIbE{E+`wLAK33>1=1U3#up9S zb1nR6K1^^-lqo6u&GGT0^iL>JdX;|igvJ?7nTWhVN!Zsfc?0{CV=K+V>8A}H`0aXK z_zkAY>(3bTd&RDF=E{<;XMLZqq@JZR2C$36Ue3{tgY`7O&X}gA=4en0ccTd=5G3no z%1*)|ez;;4I@O zFNPh#_n~m{md4-(+cDC1{_=cAB=5Y*K}T5xh2oWE+Guekc<1)O!LKbOT8yepsRym$ z@Q%k27ooES#RaFh9wfBn0Y2o~yq{siaM^wAx#SqZnAzkr*VJ2llyWqI@yd;ynR6*| zJmj>8yDHMj&WPhLAOCT8Wjb|}v3B?^j3>K<=^|Gbyxg1{xpoS8eku%9ap#`*uc2D`;u>z{Qp}G&B2VoJKW~kUW#WDlmj-F{ z-@wGnm81}GODPg0Fdf!ED<|Wgh?`Mf-@D)YP+1H~>$$8ko({B~`nIQKtHv;Y^ z;uLUVN*oBfu+2E?{>i}U_MCX6SVfXx^vNWu|IGHP;s2^$Y04IoCwBZ zHChx3*p0`+W#dVA>Vky~F)p9QSjX+`XHdFvauqAMXy_M`a7EQQxb*21u(#M>glNYo z6hQu3J#tS#WqntM>l7Qi8mU6kJ0Qm-P6k6ZIJPb`Hfk6*am6;T`h~Gw_3iem&80Kk z?GL3%r# zsu;nF?I9la+8RnY>~#>cdMO7OH^g?_o@h^#FAtMfm6#KN2jBlbU$)N5*C3#=9 zJc?8b^VH0C)D71a)sQ{KFCFEM&stUccCb6PhVL5WlRdv8)H^3Ta$rLA)sgA5<>_Js zf2uh()sjkh-LDgAVv|tVC5t?Syg&R%k-0-DuPpm#tRU@E9nk4a;Bq)8v4W099@BL8 zg(vzOzTMA-s)>3y0*pJ8!RVBjTmJD*JrGZ@7L=0 z(z^+)MqFo#RhT#VXmwZCf)JKb%`{S&K#)CSr-0<|>Av3&r17ZC4`SAVF)8&5*GFGc zCaUhl|E=w>N#S?10e;t-o)i!C>1bE-ceg~_#jbX6c*~unZ}3z12AeLri;Q-(FrR3q zmiDq}o>#2v9bXbghE!Y#{u~2q#cI^_qlLedFVDkLV1QmHvGu7z4_krz(TQ8bvE2`` zw;mwLDK^~M$eqq^`WpZ7?ZPwXsOSW1XVt>=$0@g3|uNLbg4YeDgQ}-Y9j9W4G4x3 zr%@94Z?5;>@tQ2NAK;P|Uug}|$cji6&>uCTsM~)!;!hREU>Q6QEjqK#BhM<(`-T62wHK#F zl%NpdT^a2nVS#09O)*xLbDS#P3NY&3Q4tzRV5wg(`I#5jZ+>F;Vxi3np;&?pB2%iBgJ_)sn@56*Og{dzJul#kz zMXTDU@yf=h*m;p7*2v8~et7BIp;9g{BQz-=<3qV<{ogyuJ(e1>*w2s-Gg|H!*6-3Z z#upUDlK$SoljnNg=cKsJzV%PDx#i}nX3&o5?>J_AwOgQn88iE4M)5j0YfkIM~wH1F{sGfWVe1-_G zJ{aK`KClxqKaBh*<=p>H`5biY@%5V)jY|LC%@QpP{B>2y4TvxSL5Qd~_>c~{nqtig z?HEL!ib@fZzFW*hrca-?{^(O#`W;i$#N3wqXCyv~iBZoorDZnrq`vgnsz?f(E%W z9B5Q$WE~WE_1$n4_V{}4E86Q6q&-y!g2+tY$+r4PydP9({B}@ z)6x-^-{1~um<*?iA*6){yQ|;spC=u-ckQ73ET31u|A4eS#MDc1J(TLxgA)39yt%-R z8nCS57jTRlO;)AMgm-BYP{erAb7;Wuz_xHmm#Q?UUpFm2N83g;m*~ML!W#b3iB`-r zSH31u*UR;2Qse8_HP~d!CwJ7V`Z7@0Lbu}xr^x>A?}%4v8K#$d=SSLXSy&D@XG4aGLBnS3|xd_ z(P`AV17J?X3gG(QXaCsUXDaf@$h)<(Kk!K%Tc7+g{mQBAVu!)T&SXX-Lf&)H3#A_? z@?Al8G5=mLdM78jl2izR^UT6Ew80x_g~F$AO{WTcug$}$6N`)6rZgzkE@VMAwh+_rJf9f8tSG)<*xpnpU2FxrVx9y?^4Ho*UcWXL^ooRy35Y9tnxnoh ztmi`lj#p(nd(s@yb9bxFi$%Y_Eo^}0+hnjpo^-g&mW{jrRDgByjH@2z<|H<5C&zI6 zM!sSgJ|5TXJKsTjB79>QNjr!H#hdNUqf5nFzCNiMnTXlc#H6=oEd)aX+?zky_!WR_%z#P$)bsckG^nWqC@;?8J<@{l*26dS*ytEjWN>}?&!dMlpIv>j*q@o|};h&#U zO3IWA#+nY*a=BE=*cFci^?xwvdx(~cM`WNO9psrr4X8~{a3L9V762})KbXR%=5X{2 zWK7(3xD3j$)7gJiFtus&N={a>S=m~ZBIZ>qO(sPnceuh$CEr^M zkqzA38+FrVy`(;Fa`Gi5TeloefT77=W2h`9}uD9@)5*;*PNPIKyAC31vKCi@cWZ(#3(oT~d(oUW_{a64AJ*R6H z6HhnobC55k&|;=>f6zRLkxamH-x@zia3Ltj1p1ih2zT?Mw+Rkf{WRtPCCVLJHW}?M z8J?Bn@#&)GnHTDnkC`2iFH`-L3Z zTGsjvzUhRQ5vOYS{fpj(kp$HrrvQVgSdSVFZVS8J=UM+(@B=>^(@9@t;1`A9!op|o;yjET( z9H@+R1Ew3{JF-Ix3y~W%-yU@$)|bIkksr)l{(a;+*0b|O8kPHKstpLct@<&$@qwUH zenMH5u8O0piCUq_8jE!suci#aNA9LL5Mgdv`>YR~xaF6&K)b-0spv-ccWyte9#;|f zl2x}+;428sy%JutoK`$eKu zqUKv&qe|Y6rG#JGzSACh(`k#cGnVvXzpSr7eY~4;8BqplN}&}Dy=(12nW2QQ@V(#4 z@LM<&u|^Gw&vmj4!gyHMe>d>;DVQUVfp;<9bVVW7aaDmw zy8~OBZJ2@fuUcaGh4V=g-F}Gb87AY-nn;5(&Gk!Li&MD& zC0o;E3y|i8*=v2~Mqjt?L(z=Mq^zD>L$56ej_l+d;4 z%jm0GP_*R&D{w;YQ)UywRA}RCAo?acA6*D^6dL_%8)!Y~>kl~9R4Uiv`UL5y*RU)1QVnKrgPBa6=N4i|0zg zkb>xP#;2L-hEoCI(l+(8!EY#02Uxr*hT+(Fm-`YE5j@2b%74yZVnjBm-!2?HI$k83 zq6;sRJ?9@94BhGe)#OmF`h;$*=ET@y^O6mqviz*>fHSI?;&+R)X@bmn_9>S3ILmsL zwg1SR4Ju-tg<5L`wM?9!pau1J;=lWonbb&LA}d884JbLK%(%)pX>&S$m8bB9`g_eU zKNISzmOY7%Kg1UDXt(#M%$b@&QGfitYq2l=f+0~+jVH~UeQ4f9?2!cz1Rmit0QV?s z)M}*$_LoO1=MwG)RU6)9E&WoJa$G*Q&v`bd3fCFO!$$l-HbYdLIjb7quVgvL{c+yl z^Znc9#r~rzRKDNxYnt%@B*CN3Y2KNlUv@Qj){7nUDQq<52>l}O$XY2~Q_=qIuX`^Gz~hUHEJ6Km@T-?xaj=(nedoK4NwUc6Q(!GTMc9w%Q}BE3#^x-C2O_?%nz<*G&Jv{%@{&ne64LuZW9j({86cIFat zg*gA+j%74@K`1t&!W^4?0viGX9JzwtXCElme#1)JHw_KL=;rSiFZ@~*d#=hLV4uLRA`L>Yb4M0;WD z5;%r@jkd|~AAn9py*KbKb_hE|KVfw%?@44fcki;(jFN$3lOTV2YZw#bQ+%ie^tG(& z+W3KG1Bpo8HNXU918d;-FeUu4tP)qO_~}445xx9m+cPNjlMHV_TG}dO5O9d9cgxwx zqM?z|)YhIaO}^S*IKFMRuZf_f8qx5X`ZRSPlx4p39`gpx&Q5!vKK!6aG9C0C7NY2c zT&_eLmLGQ3HTtAas%>)v@@DGDNp=k%J9R-L<5b|D@)*OVKbqOgEz6woz(n(G- zg3fZ4_5i|=rjvWgRQjI;CM-$0cnO~JUX^70@SnK3icwV{i1^%XZj-BIspG`-*Q@?< zIIiBq!Ya*audUm5{o#i{X`EgsCgj_D8FqWP)!+MPZLJ!J)-c0BIbWgMBu_NY*S^yA z+@C)REk6=KzrTC>Jwb(%bry7}64+j0a%{FbHqe90Ql#3m5vg?U3q***cD7LR6&6g+;sHCOOQoEKS(76!mjsq88bx2pOgVQnjV^N+uLK7^2 zRzAx3G7u0tcFNPaugWo9lc5Wn6ag;jjZX()`ZuQkC5yQm|G8`B;u$2iSXHdE6HrT= zMx;@=_dCa(k=b#5AdAgC{dm(VY%^HIi0kgmxIuimtLl;tnO1a6Hf<51G=J>RF2JhI zGuFma#+g36S34PAAeES^t3Plrw5`o!GDR#qg3skm3tZMVN&vBE4bV0%yZv1B|3q}2 z^XQ?O|HU5f@7wF$^$>N;#f-?yjOQ}zg$KwXu_0(uv-|YUEVz4XDL1xdpKIHl0EM+_U&wbcTye#Xi*iK3Fv@p0{iP)xRT$r##g&> z@Qk1n_Jk|G5&vV2 zhLQQEs`7Sn@xZkT`u@*tYThUFD$MgBvrT64OrgTk+e4-_QoCF~+-UojB?8rA9_$&QbP#{aY$_+{$Omg2xGL`QT3CJ{~%fY&mh--HSr`qXK!i=pH_ zr~6!m8;)|6fA3B#R5FhZUQlALw7*&ukZhCPc*=BlO)$^zjmQ4VbQ#jdK_*5A4F;LX z)J7_CbFKCLLc$qo==A$4f%Cn24bPydL&=d(!FV}p?A3Y~vq`A|@pw{_Ehf{~I-e^t zvMsHT*E>wHJc=0TXUQP3n_A5Ii9tAbWaeqMjLr1eBYmAy#s%zX|6#bd{ z2$L~9SaDbx@v8m{V!L9%gj9~!z3`nsr^Wb1H@Z*kUHiW9^UM01aHH+DKYsf+7-$Wq zCtf0;2&K>I+;$1!0+{RvwM8mJWqq{Kb2IiUppbxI?*=XC5@%h1++`(&w(D?{P$)8D(TyKxz8w^shAjoI5x0r#{y=?3k`R6I2>_09r@Z(L!DlWN!#sKf5fLSh$9HpC~H z?c#FnY&OseOWIj?1=yxertD0Ex=*=)gy&uciqWgU+nPKC=NSVTxyFdOXP3Lh6An?F zM*>#|bJZCz{Q7z}f(NGKH1{Xwbgq22o50FS9%;0Fx#YPy4*kKOT5N;PYURc1eHM{sRA`n-Car;$k+fl1{66lFCD|w?^xbp(C5Wi#p2X(n}q=R-@AV z4hdL@yLyY)%>k=5tbSCpTKsieE=6Aj8=v#RWY1GE zWEFiGR3Q%4qD<_=tOR`3g}Q9fZ}8nMB5RxbahSYhMJo?Tj)zHn<<)eM@Ozj=8Ia}i zF3bLz&lI|B=psYVn1G&RF9>p||CMZmJMzKjJlyNFj_J$HSeWaz*nga-MILk12k9=x zM;|MOCLO5LZBrbl#1YaQp?9TJ;Yz;({ml&LQ{qA0=m5L=pGfGz2X-1}y3;cRsNt!M zX9bLE(G*=RY`oU8Vvq`qZ& ziu3pMG?tv)Lw&m8%bcNPJSe>XWtQ3E1&PuL^pHMfYiqJBd1C!W{r6A=1oJlXs&4*L z>rLMANEa7g{aeQyuBa}2{rDsoRgjq01a)*cAv9uEz*;I>sQo=_v{=3xkkA$1ZlC?l z$lo9_Hn2=#b{sxVeo#}ZY&kJP^Yalz8OKJBF#T9Gr~V~0n-~q^sZ-$1EhD&w@@>;e zl?vs0JC26iCVwFJmKy{qnzEd+bOq}^>2jb_9gKP$pZTsZ(bb=Skizz3%Srt-DJeC2 zd#Q&$!$FU$;MEl}^)*wVkft5xX+@vJKaE&~kc1F%tBwsxhBhn{I7KG8QYl~=P@Qc~ zU6{1lwZp{}-d%q=UD!xW-cw|eP56Fvmrsc2K%l5_WECt)66C2Ust|Cx2n1)J>L7R2 z)^glER905%mkWunQ=@%BN-}Hr35s2?P5@yB<)06DKe|B#40Bf5BZhR)w;IVL7}`m^ zZ(UNy1q`a|=<2|dmcV~fkKg8p-utCDnJQzmpx?*SP#C2|c02krgx*odY*0Psr(5*a z;YTD`iT$@qnHsi?Om7kLrbN)8y=ZC0P-<{^Rai}QOX+zzc(Kvn){tc*Vmq^5pOx+u z7HhqnZ`xrvUDb%L%6j(K**HVp!zYW$AorUlf3xd3y0z+Sgx)i<^5pc)wnar8aU{V#J%e6YLDta@3*f z#hY=h5zKtOBNkp)^PsnLzs`EzYV-A5e+zhX532mzHI%V_)7u8iC_>B{F!$wX$sWb) zlrF9b^S<$=LmtQ0`z`{x%TT?W5Qy1wBm1~7c`#btulG3^cm|I;p#n7G>-sWPv8E5< zc0T#L*$yPed_kojP!mAjbBF?AS0VyqKey=-6!z1pX`BIYc?(cOd!(?x$i)>#GK~@^ z&)_twgn^PKxjyQv*2v?I&Q7_o*9p7+M~Oos-R&>{S-GYbV(q)jH==SBDd<3etVktA zWRQ;ZBUz6g|7Qc^vG+V%4P2m#m41CaLGt1=@9bpCKf+5l+JjT_j)`8#R~o)XxE|Wr ze!Dk0;4KsydWLnC#tsyBmAv-{6|J0Z^6@Zoe_D?LUbPUCy9qc%_;IJ5berlmg3tSs zSPf-Bx`wj=X&}keY0B1a(UY7^t$$t_I9?n}8rVE@+^6)Fr2ECH#WRu7nwyobqr}me zz`$)6VJ1f|x+Se)`X!UcTvzd}gvw3&6_dKZ zl#R)v1t(0j8^2G)SU;bUyEX66RTmteRgbSVGXMQI&wF`h_B*FT>KfjW#Mm@>!hzQLuas;2@BeoiTIL51Awl1w${c-LJY|z83$kzUt1xtFf zJNITUDYO}yBF_$>|H2SsWw5JQ=EWMMG-8^%#2t~0NJ=`yPULM8Tm-HWR=}pDBU>7; zt+((PT#K^BMGL1>`D3h-2TGfJ{Qiq3J1Xwz^yF;6Oxp$+M+zb+d*P2U5rObeX1Oii zS)=e9@_h2baBXA+{x$X_d)4YsE3TiTcvjcuNB?ao4~6>|=~{YxZs$U2A1>U^#A0RfQMKiKDI{%_&dB z97BD1T2M&4zecCcgSHv?DYOSCoHYB$2bZ#x>F|>l@Yx(q4@GxriG)>#+-qH*@(;Ff zE>DHz@{e9kUy^ALH2kDSrPXn{AU$q^Y8q%;?B9XojwV4*6V(>igSdjgdp{%j#c7S5pQ_BlSbc_E8W!z zD}HJ$5L`*3p|>MtReMacqK=u|2GOFuKN1d;%fN!t8WAxBR~e@=B&Q|(tIE+;2bb*G zlacOdWM}6{FKriOQA|5rWlK)u-s&_qwPiNby5$P`8f9?(tGQ!4hT+xP2>Ba;#fEN3 za`O;oJH0UB$u@`Xi%QRh^B<@nx0LK%6<09?R^EmR*zpw?Q(wKZD}4e~JC+J{T!(%L z8eV!CxC~xv8Pa1&A^P6>NxL82d{m3p*hESfM(sSaXTAPCIOer029^2_q~N}NZ15*)p$d)lAVlN|^(YF@t@HLj zEDrJM`*}^4%URWw?=ymm|0zvrlnzTj482{WvKZJ<1d0>%uihSI@Vg!>D+aCaD4jn% zk9&#?Rlhzp{ZgBjp$TJ3c<2y$1lzq$Y1+SB62(_++zBA4(*>~a|L#^hoRUg@iM@{R z9Is5$ocey`h9O9sJG95GHTYMuxJ5W6Q##E32iQ^>Ea{n@7H>umpnk#XqL#~SO#pIW ztcCV3%y6LV=D*9mkZ;ZmQ6LK9ILhb2u<_4|_3k(g9=u6Og2Boc2KA=uGy75#KoGl@ z;#-@R7s5^6l;97*br-xY9^GG#Yf2;>1_HXNnnR(AM~SD=qyOv4Nmp{gYV{d#?dVl$ z_)*4C!Gv!)o1vQW8jfLNCR>}x+igi@63ZyB8U|KCc=-X-q*A=zJ^fLypxV#HHT#iv z39ww3rQ;wY$GWEfY@tKEVP<&b$U8S$b;L!hz>5WiY1Ap;z~fY@5PnOBfMu)1(6NHz z>jfcl@quN8?gchlGBPb4CHv!~OgGvsIq?K2m1jO1D;F6I;vDxZIJ=kGTzRf(U+ zK7Hlli02!qmnVDN!3XU85pG@AA*G2-*`Mo%b6)1)NV?3k8fZ*X)sTBr zbKaKP_pK0QoqSn2I8j%tk_}#w zE3P1mkE5}MlwU4=%^J8C_c_Bq6Ls1+!Db=9ZyUUS$gdW6_)z5&W+FX*zt=S3xG-8B zBC)k}y;35+*~eWDa+ti^9;YE#s~_~@KQT7j)0>nuilA!JI5U0vbDr<=W_H34ahOE! z1ek|({%>x)H_H}ajU4It$a^T5iZy7pFksG25J5d($zc4r5DtC)6zh>pt_09pyPFx=0zrcUh;P>hi0cl_) zg!aGckjZiX(4HSmqxQ0MK~W;Ku{s5p0_pTx{7RXzgtbg2PUVvMhstaTn~~y!G9?Rw zfN})2OqAmR#)Nc&N(fA#ExJ5z7e#-3^5ddMwy>>@9Tp8cux&crDFEsKl1uZf8H!4Q zF(IzU4~>{CI^Cb6mQiBR(Q1_3_@uXbq|!L;<20Q2$(4s=z?-jDKOwM%GkyB&MZeJx zrCVX{Oq6x&;66;cZ8XLwTYfZQ-t#@|Bm06BsO6AK@VYhjJrPi4)p>hQXz=|QqG3fN z)YN-P&8?xyAmngF@+r9*?y3>?pS~(2KK1tSNh=l(6M?DLsZ4-)=%d908E z=*TUd=FqhB;s=f&fsug{+PY%NIIbGw1mXQnowwX)t;gniFI2>^tlkCv5VNC9kr|^0 z+925K&OAQZX3d1~u&~=_bWm8e&o-AdTJ_Izj_}P$Z&tqr00b!Utxra}et-0VEEWxmK`>)#W)5}0bmS2wQndaI_{LhH|SVgD0^8*VNhAK>H z%G`Y{2**F}bJ|6p#QW(_l*5{QaE{6K>b3T!@)FK|z{&zs@A*^WNLJ$fIn9l}P!ngJ zv*OV{8igIkv@@LK91!-$W`BpnKJlfdHa^BHqQ^^A0>@tPE|RxwhlVA~i=&Th6jECt zj#ph%d-6*yZPrMSb!WPe7D}Y-5|8-M!+r&y-0NMM->9~e#`!K?X0UNgzZVZcVMe=; z8z*pP3{B3xrM~qT1#lLHue1=y zL4L?MhKi4>asi4qy!MFF&U4KgpHQ`5=kpU+xpMANNqY8zgH*~OGwKb8`oc9mgQudu z{2LkB!|G^}z}P7+G+i`3QvJhlIADRNEQmGdHG|T3U%y9+hBWQxl`^CosW53ZcYHHt z_}=N;w!LS&1nCp;z9a+`<1)O^_vi}X)$hGVpYNw8E~oJgCypG$fWt~G4M;mU4#=K| zK(o~Sxb=Qt4^V58Mhzl-fE<_+W%tRw*b=Bt(1EM3b5 z{EUG73|_?~{{IBV?D7sn28m=_$81lGlYXBwt7!^ZZVlW0fn}G>spYXrB*LVtI}z?~ z-l&dWXLh~ecPd!K5*M`LFzga+e144oql;s#&TDpMRnFXM%Od49Ml4QT@B%<#qm9jf z%T7+L5#qcyT)hP|t3AJvngJ;wF$X`qEH{lue6BfzoG!X&6w>2Gzp0}ASv0-qzJq69 z$1uzHV#_5^&*(+Ttb*44he!Ts{}@_yoKou60DOx)=KZ@{sSvBeA4P~7$q^zR{fYpxn}}Uq#mK}CUJ_`+wri|{&vzCdHrG>V-9KOh)5st!p@=X%4?_Zo zW|2Jdg+bym%A|^^jfgnJFs^{EBnnd{J7+$JF@f{%Px=JuQsq9FW54c8$vts%d~Py? zZiW^tc|3uDF5UGTjw)dT;;?@lWWHNW`>c9s#ywzTm%`fZI&+yT(ejD6s49lF=7=o` zJtv!_YVTvHBAG}i)u^7^6-HUn-7cL|-!(Puf#ugohW}>)_Ef%<`@{j%VV>0!(GL&( zOUaT~{=R__x@^^vY6(Mc;mT9Vki@Z&bC^oWD%aHIg7rcTk{JM|4rR)a)p$mU`<84X zWXuVW7JO3|@Y>G;-BCs7Ea1my3tv%Lj@sIn}u-46iit?pUulBIz zv)E2#P6zNDh_EFoZ4HgvvQwT8TZbT?Kdp(6s*Dag5sqtX;QP?4uh4#L*YQzAo|dij)ZtNBJ2-mwf{lPUfcIaCt0?k_Tou zNW9Dzj&_`1AlvQ1fP#VJii_8)+}Fv|N0QI=k!Db5-P;xjNPPwoE(R1`va<4PFzFxW zvBy!&+kV&;^Kk3CaH&?j$FPsXYn1H6= z;VcCU_NWy^{HxlVUF?{+U~D4RwUcX=CBg|Jqhd3pQd{qefbM|%bC{Y3&A`ZU ztV9x(WT1~De?SLBYUn9y`P@cN#)$tLyU$vg;9#cW)$*%x8(`u zfQEZV;-)f2e>#Gqu$L=;RDvlXg+|V{2QR(@C+X*s6r)(Jw3FO^+XQOQu^MfIt~2CV zF2R99#)YZU&6K6>5q)gi2JvQuohty$-HGR&tl`}9k7qp3>l^fK?=^k->zI!_{o8mB z^603t8y{t{8pB5(mid~~j6>%yvAB(mD|)_H6v~M|!P9Kt0q3l`O#5Tf#CC`81*T%w z-<<g19U_4X$2*NFrY198(ngCZ zFMQc3o$bZjO)!Ii^XwiZIy3pFgSLx~Ln#T(_ti~ewm^+U_3`a;FJbC+m8K+S8v)Ml z>9+0)sfI@NV1-c3tjO2q7mBIS$OM`fV!whP1z(QP?k03{2CTh_GFR9&3}cK*Ku7^W zH0#~_6OY*I(!T3ymZTq?{|AlE>j@i_w8rT&ppi{FPlG6<^E#hY|E2)~TAGch&i4J( z*6ct6z+Nb-%v;fFpI`?)h$Z3r6=n2digvE_J33xt<^rzU-$3UZTmH-~n2$D{76^}& zC7~N~jNDBe_{*r^bSlGZgF^`Zw zx4;sZ4C$~vWhE@^@4_d>B4PP4YSG`{b-=1DEM#zyX@gm=7|xad`&d9R0 zo~t9Iocm|&#pLnpYQZq*k%XA2lQrBROKoRk-_o_No~Kt72obRz_E&+=?4jCf;KF!4 z=3hIEtl0CCnolt27mPNEY3moz4*Zl}&C43@+E$EVWoyNC)Iu6bidQB`$;yV0b(P`T zF=ggm8E!-Jo9`a&W{wxzRz&94Ed}UhS1MU_o=#zjh|=ok6M@ei`!86(o+n(=?)De7 zRd;N{=g+ZhQp4^_FP!)86dh4#DMg6su<^=lEOAS($0<9fSL3X1VA-p;^>0Pdm>4fN zhmOfZI7Ttn{y;S7)8`j6E_M3}{RfO8iqNG+8|8X#vX|9`Ar7E|lJ|~I90aHbmLI*2 za;q4x|Ie|Xp8D~q)b=RRle z>s#KL8u+VqO5v9934;m*Re0@a7_WWp&*9 z?tLSj>l5>=?PyV&h}=g=WlEVTM#5HVD5fgDO3}zaOshXc{Pu&8Wzb4bXZkJC&(G;G z^w|H7)4i$lGB2|$OIi((<64WkSE(*dF@ePw@28(5D za7Br~u(}*JEwZ7T^LXcd?zMSSNyAOElPZ4X_4=f+?3Ww0<`K6_e0l(&6)s}K;7BO3 zWLh@5M*=`c4NaNkBEN@4vy^R12K_Amp1g$)R?8~pytlf+|MboSWDev4q5K-(T zEIYCKBXBP~;H9g7f8u8LEj~v)hZ-g?UJhsh@KVm5{n)pR{&0JLif}uO{)I3}W zUDTgf*MwklD18Csa!1ER^NGKSvz04q zzEk*QhUai-83L$Ms^X-{yMXQxp3u5J+&5kOO$y+^5r^jYOBn z#e+!58;=CAe4$$WZJeG5b!5UfGynb?`k98~&EJ{cQt+OxC`GbuXnNM0W3R1Y?V+?> zTwR(Gs>S+FCsu*J%WuEcE}l;T^iK4WNz%^A;)z?)!2Z6qQ=KL=Shh0CYQ8e8tP-pB z``^`H21&#`&hftuPEm2sKTyTb;Z%tpz6+uM_500_Pd*0z|0+94P<^e8%KXY{NpI=& zj3CT~WvZ~aS%MI_ot_cs} ze#@ly)V9**1q&gws=WXHW*t8`IIR9Gr|f|yc@GV}$`%h$#9MyAG#B99V8@!;et0K$ z!yKK^CQ<2vZgrqj?Yt}h8PWAwov2cx$7i+#ARV|oCiX{pMl zvM4CUEqqvO*)|Bs{J&2=*?GQeY1=H!Pv0nsSd?PzX@WU%dtYJO}7_(QVL%~%PD(7k6rhneHU>zWpw9cG() zuDb8TsI;o8^(TZoH(h!{BdiZ06m;_2ui~vWEb4yc9g%C*Mbjwt#0pqRbYVuP9Pr{{ zUr-J=inV-aba5??^INKvi6bMbcr!$h&OB> za+7tiIOcbG8H2hFo=QT^t)ExcJ@#Mpv?i6Gg;e?!M^=yrfaM#!s-y<_81-7+Q3kU3 zpfQ#eLk1exiqC=={!A_8=R#UqJ%K)ywaC8|YB-a>rEeT3zt1i8Dzz(74pWzE%bW3# zYYs1P$?|I1{IzWPUGU7j-ZJ_rfV1WSVjIr|GI<|!!#`m$8s+#zQge%anCkL{0r&1z zB~7k_?H6Kyq4Ob5ap)iL;9RXdS?{3>V1xJwM`R%wD~mr3Qlb8U3FvecWi*Vi4lz9|cZbfK+CM;#DIDCh>N zZlLKoMfJA+bMo4aQqM3K@P6I|UWC@obX`w-7L$>+qC5IubY%(vno4qve8#%X-k9}jxoPA55vYYb3SZhGj}9)Y5SB_xRa>u;qyngBMJRtFkQd6 zMP;Jk^yTaF%a>ZLffGKD3X(gv;#CI9W&CjumV;9bwxz>;5xdu(0@*0Q4ykdY|0g7? z9)9H>X7%9lD%Gblg{24ovZPpJfuE0Z$d}r}FzahVJqz^7I#Ialdt=X)Nn{R&8wIL^1{yK|y;>`axi^CZS zHoi0`qASANE@v3-2p;k(D(WzU>; zr|3t;&VMJrPe)uxQvBW!#d!Cy#w_0$uD2*saxeQEwMDTCKS`u{Ub#1~VcD#9_`R)0 zS{cFeCiiS_&y0mHlSb`MJNR`k|1z=5zY^o^(odl=_|SXUha7;dzNXWfvM(+-HYI^X zukoR7*HiM5_<3yYncVVH+=C$S)AXlJ8_)o+{`^PZ<0m<4#jmrfX;0fB&3C`gJ)Tb5 z+7%z?w6X(PD`VlghHL&VB&2~UlqFZqp3a+VP8}%ZjszYg)`vrgF}9`hDGc`3xq*abLRDJ+ zAF_hUA6RGJRz2KPWE^Q`+jq??y}c9Vn+~l7`+^7g4u_Gjy*wR=C>L`;JD;fuWXM#m z!v28y42++$&n+-wqq6LK!~-Nu(_qgWXDr_Fbfy)kV>jK`Uox*9N0|`+s5vf2kYZwA zTQj)}FFv2lgojeR7q#(5r16G8pKT9SCYR>6%~Wmuv(NfzM3q$J1Lufdw-*Fd zeK+BK)It_rU{$A(7_b?sK8~bH4kA)b%qk!0b3>1gtp4Y${^)gMkmkCM z-ukaA!Sx_n0!JYl6FAYg!fb)Z2e&~cbz_>_`j3o|2`;`@9vex6Df3Gm=VZ=EZUWeL z)94aSct6}E zuIF?)SXI(w%~FKn=sr;QZ&yjFa`Lb%q^138Vog~OD{Hg4Q+6oXTNxGjPvl~i|D)@c z8_@JfX)QR#h*xG=df={LIM(D?n{XY*j@x!QupTOMb~9?kj~o}$T`w;6RO>Xh%9s?` z&Ao-3Z@m@e1h*1A9`*Fb7zZU*l5U)OyH55CkD;$kY34w*-Ee*D(QTZ=IifnP%VR$$ z*EXrBtE!aPYkYNGB#)-Stt{4W!dlLG>RY6`41BO&UVB8T*~XS;<6ERAD_Q>iMzP5) z>IVA!U#I;)lB0oc&u`zFQhywNIQV$jUL_kLdu$=S9?69PSud}=;68M+CDmFC`q*g% zoppR$SHTSwMR?(N9r5PcA*ElTo64y-Fw;g#$=rw}8I`zb|5RKwVOH&B6E2LrvRpGp z|4dwQ4&#kSSDdGGkf6w`1&*-FoE(sGaMq@>o-@DasG!@*{c`Wj%zHCJ25{UJTuq( z%PYx>H(__)c?;7_c)eg@qv*5IC z<2~QoJbg$gb97xro2rOddpCjwmr)D*i$guajMxldO}gs5wbqY^PoQ z@Z%B7NUgvpcx~O)cCpXVO#W1hd?o`eJWe@w z$m+TS)Q#AEN76WOtdP2tDj=H3M*Qa{NC8erY)*-iAB(3`7Z{N2a(vE3oKgc0<7zj`^4p2LvUKqoG zLo6D6zP;LF+DKcF@28}%$`6 zy#7&jjz9S2gGlrq?_{}>S$0Oay5dJ8h;J!tjid9>qiHy(Mffzyt&pqRX&num+|g_q zeNriH7RmW-S7c>Bjq&9b`F8z)pib`P$M9JtmLE07L0K#wmM}UTf9bR0zZ~_oJ^#BF zZev8;F=6p}GPaX3j6sAt(OZSt=XpxpzFA-(R$Ti$RH08KZkrC>X7MnaQK?MOq485y zIWswO;&&q()0^)vMe;ah_%MH_Y?b^Oc;WfzW^X1;4YPbOhWQxq=Rmrs&zf!z@X2l= zYp%nEOx-!cMWpX_t3Epg9AkY~utEY4COi7&MyOiGh(`1p*=hL>c13RDO9`xb3w;fi z&g12Q-_bBKdOX(FYuvn};nPTZvUy~GnxfV<+v0r@?Xg4QamMViq2qbMVt#1Db4V$x zG4vf~V_nYlt1NblL~JPA=49&gPjv&vm2A4z`puti#}b-lKD&$jmumi0LL4LdyxBqRKoGbHj%u@atV zW(0HM;A`J>0bIJf*%8q@{37>NB22=*8yTPhve#vkd;etHE@V9(T)a*|U-TNh{+>LK zuS9RX=Cvj}dv%?*6%}yu>Jz5&(`nJ@83OHi+eyUrnrj2NXd*nHEIb~Q5?s#@PLf0r zm7A$H4e50)dvS?*3T*F#`2|et8&)<%p8E4|f4h%c3w(Ux{^=f#~;{eGT6d?iOU+xG@|2ma6 z>zG)i?|x~P$FbjCfM5xgs4_B~AEi!$qJuJ|>+Lu*9oW`OIfrXDHn&~xqT-q0oe%{$ zFCU*N^qe(Pmc3AjDk^~HEKns*X^Xnl2}a=HE7J3-Tjj@vY`4iVaZIP9&`a-zKnYu4?wpXD`Wy!b^wqX8kaCP<-wrI{SqCDs0} z(?0LTnRAtiSnV7)D;t?`+l64aJGq@JSG!4r(-{|KkQnA93?uq0`j`l=l;*C$+m;|j ziie%-(FT9D1Y`8PD$NIB;>!YVmq4F2P5kAsa7Fz2i+0fn=(~y~gyKokkIBwT%&Y5r zGH09eX;Z`W=k&fTimm-BZ@<|?+v_D4MKh=546rPVZnJdRZ1(KIxGC4}^}TCaKQ><*^Qu7iT{Cc%NqNmuc{rA0JBpMnp1clBhW$B5aL z?5tuc!5?xxeZ=V%gre*JMmR>RnEoyZewWPn7|Rti-g{PIr`D;YsJ0D5lbDXAb=yl( zl=&Ew?66B;z0VR&!%lWLMTS+k9V!0849{@E+ITyE?_h}|6yvl0X?;r+R~ce2YviX- zw;=Z8>9PKOxX~zDK)Tpy!it_vOOPpQL-h=-rbXIVbDg z*XV7u-XA9m+qk=vu3STYvB#I1J879cDJg%Yf7mr+7T&8k;T6v`c$6X)10Bnx!leZj#;JRn*2iB=GqUi`VvN;7B=jq%9& z)o2w%@OL;CrW9^4*q0`D22)I@$Q!VFq%HrQ+!r+P^nm(+n6+v-*Yf1^ z>I>`Txu^56(Qdo)7D?lh343#g7rb&t&dw6}jSg%b+}|I5M_6mtUs@SSq=g?VW_+0W zDVz7<^QuHFY5ikWxY-bvYbnjRP+t^q#G)$!Z)#H86 zQSA6Ss+ackRD#1Xfp!+A2aMxV4j8}iN z*V1O1O};|RvPPVzrEZ0KH(;^ZIc{lbDcAjsPwsfO%4GCxy38xC?Y^mPgV+0<_cmMP zj{50B@i|uS`BE=^9`|hlns4-EQ;)sv@!g>lYKk?|2%6sA1?7}mqbpb1(6RIZAtd9w z94_mERuawJ2_%GR!=Mx9qd4aH4H9Rf*1 zmkB8X(;2!|y}iu%{hi>JKHJHl19{4J63xskX^8wgF}lBdV~3aTm$zY$NxrNNx+ zus8qyk{yGM*~H4BU!x*!R^EMUY8JfMGh-D;Z#`RZQGLOvJ>P>9|2i&qp_3-6je}3| z-D_&O-p+CzBN%`DhE2m|68Y6np{NI!<)f#Iflp+2op$Kvx7PzVUM-W6G?~RoMwG02 zkU4X=YR&bpb>P(VorS{_7Y4!zg`FPFy){O|aLB*UeDC`GcHD$6#>5Vfk2y$6A|-{Z zkQutkHjLzelUVQ-iL+$X-IS(a=pC8^(p8?97ZHbmi`G{1b97yi5V+9|36|_L8^dK2 z!%eXXBp}4yuKTB#ZT%`S%I;VSB@nnc0VhdQdjY+9Vt8F;OnNSR?QB7FAl4w|8L!P@ z38{&WUsfNwWQ%bE$)EK!jV@Vdm;K3AvTlY{-xm-91Jc*>F8muz7(vB-eH=lZoq@^j zQZKYq#D`z~zZYQE$P%#3p*%`Ys#e==>%H!+wpGx&*nh3=i>j-U&pE|b{jyhs$BYj< z7(qFR0hQo~Xo!-(o?(ldHw!rcQqq~^12SpCU#?3l6**2ys&Rw!dE$<>{{U>Y6pKmW zc#sWHo^3EFRBv?}>_AlSn(4PO=ja(nBMAFb+k)C| z>b5Xm-D3BiO4uFU$S?Sa&!_HCYIpzctg|aIW2HfXAbiZxSJMG)uu#4?Ox@TtnufxC z38@>?N8zEzf7;tVlw1J+^UZF7c1JZMQ7S6iramvB2=wU_yiQ5ecF(X<~WP zrcAeGz?QFzEp*Q?WHhN;JKW2b@B6bpAJz!IhIQ&wJC+JCRhWX0UO0s9UEERb^2P9A zN@nf2nvW#$^f3m_^xZ;H)z6NqM5B|UPjHoUdh2PG1x7x?<2^k_VF%fyZ%`T2{pRQ; z6kcm*Xzu3Rml_N_9}6q<*QH65<(#!Gu~w{N35M&S3?#Yj)*a=_-LVr(+f?Stb;7<~ zqxG0IFMpL*Hc`RN>FMl?Viv3afa&Dj>k2ZQx>gBIVoPrEF=9-y;(SN%u~pPjme$M`gWQ31~4A(0?}@5e}#85(??U!|m-a{&&z1Dl2~O?hYYhdbYkB zNbST0evnRXEPPFu@1N=o$;0oIf(adBUc83H^A553DOVXVGfaPre-pNS3iLAZ;em#G%P{wm>G7Pv5dc8waYEJZHp>n%NUk?6rf^ceoiQn*Xih1@P|U>5;)2B!Ui zo-6|a0tq|WcIt57z0r*|z0{i%6Uqd}AIlx2I4*mF6n~o!^j3xco!Fi{i+~Pi@i2Lr zs*=Kax$Xa}K&G}xVGR;~&OyFOj0o@!GGkr2#utCGwIrgo&CgZhm2fZeFA-l{Jg8jR zJMVbQTHe++3M{5y76>%3pVuVxk?DDzsIAYX?Otd3y7l^WObq9gwC$ACu}MexEGpvP zxybW*oOhAWt_KAfw&@&yxH5eh?Sy!JVHcFoh08miS47{oRziuw-VuXt2#;S_^|WA1h60 zQu`-JG#?+?JCqk`4Fb{(2!F)>cew0iA15?q^gP?!X5vF#OApt1lBwUOpE$w$3sl@F zuJvP`gatln)5ek8rUgd<9c*{Xv?TQ(H_jyu_L^2|tgpJ93?e>Lb$BUb>Macy|MR3@Otco1nL^m_pO@T+_$mAGw``elaVE4r zPYy!(c0P;=O?u*VrDAL957GKpHUeX`gh~RE-rglNeD)HjK%eme9XGhR>+qGM3p3Nc zNCSNy;=?A)hl+^n@TJIm%RC&!||4)X*>`eTK6n}Pd03-O-G%j~`ck6l;HIcbX!M#k{@!wxuB^<#Idl!H$*wr3 zkXr%ys;PP&dQib#tG4|4VhS4!<(ELBaSCal6(i}22FdjYvNN8XC__V6@=F*6vve>q> zeqf9=n)gp->Jc}am5W>m!CN1*CL=RI%yU2(1#7Pp^J`i6?6l>dtxtbs{ivHJ7=Ls$ zO^Y*$C--7WV|j}>zG_N43@=F%FvTKq#&Z(e*V0T`8k`n?TC{{_|4_M-#6%_`$+uxL zeEXBgHpxw#f*R*-E@=W)G2SCB>=8Q;NAl0ALe8>f?4q1ruO*>7hkMgmVs_D)6dSna zK#M6q`_Rhsvc+y4etE1Q}^N)HU@$BnI` z&;?Sl!#6TMItEbjjY@w*&2B9?WkxYEz;ERT^O5@K(|UB&u{WXl((3F zTO9T^JlGg%WG3^ji;LVY++<6|sk6f>G@$6K_pvL{fq$b}$j<{3Xa-mw_~kWjHo+{R~q)uXBWjOX&=<8gz#J2Mkdy>3n)ysw>oH!^QA;3AQ>6t&a=js|_14ja&s zhl@|a1&v^p-x#m&Uw2mb%D834@+FDfjN`OMM0g$=K3v&6^N5^tiga?03U%5%&zsCU zb8jlq7*(icQxHC|id=#cSak5pOo&b4JXj+!C+1gz$)P{JZ^TZdbTCKofogKHM2GCo zaDOt7+xR!tU;#JMXT92gmfu1IJ8R}>rtZ&?2ZQ{9Ahk%3GQeVl=L#>7v_A^T0z?gY z-r1QsUdlsi$gaPW?857EvYZXR43Ke0bI)fJiE^gj;9;drV>_?4%Yt{stLmklhxhL# zSn{q0UaC&!r%OetwlnMf_M$w`&*td;#1sf zGq8^@0zm$~k1hrWDftx+sVN(c`Wlp1UI~5Zj|WDV9V4rZiUa8tWnpO6Z3b`z%n{~SV7a;tX^?Cg{bieU9ed@J7oP25R+K zHld(T&x|vYgb0>Z1g5}%oUSc+J4>a9$+res}BFtx8XWJ3j(VR4!$ci&Sd(NQfxq0`YHkO0z4|+wx^z!9KY%n|AZe1P$KS z2*R%o%=2A#5u%|`!to)723=nHb~@sbqwTIjFKz$qVeZ89Eo>SpgHFrJu!#wqyzR|z z6Wy^5l<_en;H#mtzvJkaZBymf%&7Lp%RS|hd=yimysBF0=Ot;vwBh*79Wwtjs(v1u z(aK7tWP$e8YQ|*txaEs?e;5#s?vtwjWk2y&EZxukkOm5SWeW_Ej-+4Bg`e8;l8ww7 ztN#_h?W!U=Sa(?G`^3xzM)sTwMbjk5^JRfV8Sy0_D;f%E44Rx+dRID1-KYj-v0be% zY78UX34y+GqVEg>=WhM!tMO6)YT2J6@9=nPo0zlK&`^*EYBYW{($xNi<-Gs|Z|O-p zkB$h02tK*r9oWV)RGsX_Dvcgr{cqr#sR9?$@F2_ep&@+q9rtiO?e&3tIiv?YgUCri zqAb@9v03e6eRpF^V85jq;b5|3G47`O2{O1c-^HaLvnj@_6YWHO#>94?q!xFQrT<6E zMs+`BH&4FI;j!z)y(rRHqCmTJwPh4>D$ltNF;r6P5uugFNVE8M4!#l;YxKo+8_%C^ z{j>07cQ#U~23hvRyuY|de|&);p0HK7K1hL=xA2dY+uOCD`aefn9` zq@Ay=`kmt9(^v!e3VsSoai0|jNRtu&?fVTD{;QdCp&6M9_il@>-r4P(s`$gq{q{^~LE)W}n7Lpv=v3}g4}|XO7zOMC8?(fvl72Om*gk+! zsU7~xgWuTUzr$*a`tbJUr$}Fg^rcA(eS%h$C-rSTKEY4Tw;$wAaNB*uJ8`4C$lQUL z+HsH^m8H${YxnmGp1{jrnAS>1xppk~c7&>ulc8}#CMW{V&pnzGTh}+pO&*Sgi>A&? zk^v}O^)>GmO1RVB33?q^G&%Vg0$`=Sle8yGAA@zflkTfn0dB!Wyl#g5uj;zGZ_?b{ z9@aIT!12nYAw#Uo;4@|%Lq5ro+5|i)O4jD7t%b{1(XScvN=Xk7t8ae0*PaRmbVkXD zs04DN8xeNCyBG$^m|9zvY>tz}iZTx{^@~}I^r#{Qj_)s`GVB5*zXX)UD*aq2{XGAI1c}nQ+|xc^uI=A~ z4SQb}htfhW-fp{B!@Wdifq0nwGVOQLW@)5w_SiFn@4~G6E2jt&M zny=IHB*=VT>+q6BzF<7C7z&(g7)U&;YGTfMIFu}F!iJXDIh#tT#WJW4QaA(a++nqq zSaPEB=lM@lm}=n0FPhm??YHvyw0=di?#e|)T*H~#*aTvGSAvHzc;c!pr+n=hHeqTJ zCq9v`DJc6wSZ;eV2??c#_&4XYVAbil1#{b#TymhoG{{+VqY5I%e1*wvICl_9#}52A zowO=aNQTMnQZXCvi~LGeuprS$>RBuWm(CY=8C4^OaURlQ0?NLtP9bQBT>r)`z_yr z$pKQX_r#v)V95%qpA!7$oIPkJkIZgMGvHCdo8$tCbP^iP5*ZpBeK_ArfRy1MdmDI7 zY4u^ue2E8^B-S_xQDPHH$T=TZZbM>KJXsN}_A1hdgIm$^9^0Mzr3jG4U0a6~zde>L zYr`<(DBeUO8Y!J$=82Jo5?|uvr++5Hito`TGH|~P>%QU@)nz1z9zJHM@O8T#pzMSO zva{HA_1j-zzT2iR!c}{XhO{asaOMEJZ@Fl{WDTIIS44T3ZJ&92yx^oXkXXcf*Zgl? z-rv`a+!6*gJC*zxN1h@&nf_PrMSRtCxZb9 z?4Z5~&~EW^{Ah*D(XEOsmW^FTCOokS-W)=I&B&9Q9Kwb8|4IN3ivoD7eWQ8yD?NwI z{3Nbg6Cbv~2503rV_eBjjt5|vo4cMqnNIq0eY{ro%z|hXA+V>R4tn*jF`&O1oY9)J z9o|~KL}-5syOWkkfG%W=KL!e?9ojp9TWRuBz?x)jAy*MELrLX!Qcg4e$3B z4=k6r)CuCi@@zFe@i7J<2KQ9T6?d-)FPkU#L`zy@Sk|=T?j2*NbS9|l78L9ugkXN6 z!|+G(qCi@FXX$(Mrl~aBLUH^ej7VLcS79**rn)eOX_$QoV^NLb=fz^N97f#<+|k2p zcl*i<#@Mdbqyu4;TP7H|cxMMejhjhfHKf>&FW}atKY0!1l*^v<}&!T5|fB?eB-5&eDJ%x0IL`M=D7e4X5je5bl z5}Is%%DtowJl zH@8V712K+ePu#SlgY~~&CBMcr3mP)V0FNDacQUezKY~M;3&@XU_4#3dJSSPyoj6e8 z>XDWY=(#|oLh+Dtw?Z+iM>1B?e9tOfJB(EbH|5~Hi_Ow!Pa(*6-R6l-&U1biSEx@O z3xy&42hF&7LK^IUZyVe*@r<+(Nmaly$j5V|p#62$p^S|whU~~Q&LmdS7u*QIZk;GDcSB3c)B@+#q zmaC%#G_(}MsYdi2o(R%OEJQU@e*aQqw?Fi| zWp;s)a}GrAXFaboy4lDcce=QqMtoeHaf52XKpK(nIbuTcbBi=*YXqkt_GQm_h9sP( z`NAGYb~L`LBKX_alD>>daPPvGEv0xuva$-bYfUwk6wMd|8$G`7yvWd>sod|aXg?Xu zeZ-T?S67dNIZl$`lzVy?goY#%i%9KVE1LX#+1vNwmXf@1@XFbNB2R4Jz)(@si zgC*7!zh3325Li3id%=!*@!fB1(RmBgS!A|5YD-)R(r?2!t)Nv+ZdDN$Mj(4gtjyd7 zroiai;P1CWOu;gVWZqEq*E?pMdFymBgc6}HHsv?i9IyF=eVq@qFq`fPBv?qM;(a%` zgQ&d)+yqWVEV*90?<|CUjE0X}Pb(SQh3z)BCrzRnyepsmFn-BNmaQ4dfFTJ&gzwdF z!ej_SdA5apS3C0i{RIXHf8Q3avoC-5)IY93tQHfpl-$Hwk~SUc7G#c26;^R=n5AzGlxr43I?TpA1fmPax9siV zavac>$oeT-o}z9r=X1yVVN1s^i0@`yy0N%Gqn7syl`QNiy6YnM-J1HzE~7{&!AN=u z^&rPmr!egO2FW_z&|7pdB2k9m2^n@T7&Pcit0~fHQgaVweM%F>mt~(l?Aw2`Ea73J z_%Go7R3fLkp+1y|ybw`J@eKhI!uryGFd?$5pg5MtC!QK-egKkenf!Lg%HNlA_S$ob ztCu~PmcbXDRCF41AK652ekc=c8jAk;-@gBi0OJx}dqcc#2I0!6H8OKPg~CQ*JrSrr zOl5+t!0AS?_tB*xFB(BIXU*cJ#41T%Jg}aUx*1fMJa4yCW#neyS~`ohXHg~iJ3n{u zq4cjp>9brEd8i73DmC$CzULny*$zX7aIp&|m2Kk%2MCR-eVeYlke;ZGWUj6IGqH5pPUycNdjSBKwyd%q zWkY|mPAtxtA@lRSPo{;mXESF>?X&Uq4_-U_U8=?RTnL``)-nE-%jm=KeR|O`z1;3h zD!vxTg&jdC!hz{-%pk^Od65;KoN6HZdHDD>j$wOy&I+lm)o3sG`M}V8ITQ@F(K0ICZ&6jQvl;%T7CnIFPOD3Evds>x#@}(Zc>?_#dMHk4S^B>d0i+5 zn(>gBL~vODgb`%b^rZy<4;*f{G{oDjVm`PQBt|Z4J9zd@2eH+UWOzP0{2SXDer@fa zD8n|3>~SJv%*pn0dgIVeLn&DzTvTeuPPneLs^LI+Z8w)DK)x3Az)9F%Y9d}`^S~@c&*80_lnp`4~X5uhM zZa)@b7xtjR>8n4LKeK2scL0w2Oap-%Fr!o6n|chp4)gpVv#w6YYpdC_T&4Ncs%KbIe*s$iAN*We2Yn z+b>?n=k}+(4bC$ED*q3gojS`FCG*eG3}~%Z_0qAEN*=$trBn@a@{Qd>Zd2n|I1 z>C2cS=G*)k@o3`-zK)Y#%P{gDsi$TqWww24*{`1pKp2=}`H@Jjg&inC7>K|)6ahBA zs!)9)7zVs+rVfOdsa+O(+xq^vx6J+Vw?tplWm&gWaP<3CJkucFWMu`I5>L2aAmH}L zrL8<~zC6j~X?!&g9h;R+qbyJpDfsFWKHXKMcerM(I&Sng^wK*$gassGpsUV~Va4zT z_e})$UH4CAlP@VXbtpB-P`8SotiPc6pWCYMMpERI>Qi$5?N&|KwFIJgCdv@;mf@g@SPkH30$cn5x2mAx?LPcUW*ZalqtK!F+34>6 z1j+w<0jgUXFoiJurK3Z)W)w{G4 z(R01?vO3G0G*wQXSGwoxg_*rdmXZqAQh7Ktvvj34EMH-g0LCHlC6r1|XZJVIcLJ7R zy7au*KTsbt7{N?nS&v?Tp-fqFJbyIk9nX2dI;UTId8OMY;iBPk7x#0Xu1^B4D?7%GdLD_iNm6mkhJ!);1_C>MkC>>Rem}4AAhVk)$o5Ndo)R;G zos)(2{Yw^Kw#*+TqtOrTl(kw?(S!z0c_034?I+iQX#EX`Bd_8I)du;a`V`Ylav(Cq zbc?$vK&3tj^9-$Q2EP*I$97}*!pb!7He8$NsWHw8_*59r`7|@l8VVZ2!A!DPl52lk z8fc2Pro`=eJ}^aevU5*Rl3g-!BDsR3ai|x6z8yUMhqh!`{8g{jKFN;?%`7$~*r#|-9RQQX<-4A8KeT+g0iRl}ei@A$u`riU!8~n>V zmZ+bvML9m$6zdY9um{HmAC=Rr&1lY9zmk|#^8E!(9JlNUU)ugLM)M6(H=K<6gSg3D z16v}kWH{W<-9fGpeHsyC9YB{@A_zRjOj~^2{Xs}jn1X7m8VA7(su9-V1bR0=k@Y{z zIp%;IN)xp7`&}SJ!k=Z(6wW}yPsFxXHdE&eiHWr3>MFOCLvDzCj{2?cIig)t!7lRg z6G_OKZ1j*m7hja&wb;Ues4t&vLo07aoROtf&{-GZf4&5K0%Uix zFXVSoAR5+>i9>4N$Ci5S52U64czHX`ZzmS>j!uMCIv`6{DjB2*<<-8LM#ToB$-Y=% zvl%pzgQ`B1--+eh4Q)IS+EfVtqLGayyc&V9jHgT-tXF(2@0&Ae<6Ejm|C-5TOoA%e zDzwvPrVl)ZOxi=aQu&DGIe)1xc{ud+YbfAjB3p7LyT32p_6!RvNG!R%uLM#OU;Dp+ z=e>JRpKQt$@)gr^$VeQh$-%Lune*FRwnT0~M~wSAJJ(MJs^Vin1jD5g=&$F$I;z-T z6I}4FxL9VrUD=L)TJ6yq1I5jsio0!;6Rj=#C^uxjHaurWUQiSYxy&%-b05`zZz!%9;oR-kI-hkoQ}@QdCGG^Ep+bKk=cvMVIJMmAR{gVuE3@=x;hSca zv2u(ENf-fXWs|tGwFb7eXUG_Z98t+eNz~vE99m{eIeT~$tW$zS2eB)8tumZlX#EduVQN3 zRlcO-#vd0vn@kz$+0F1unwKlJJJ=lC2{6P!6LDCj8^T3kz+bd`PdQskVSA_IV1CzF zHTf0#lg#;*x${W*EH3x_@zaDn;A1-VSX+|zXVl+^BwrIkZ+}p(#7}i z24Cqexh8Uv=qK_RCxx6dQnZW;NJq;Vx+jRblvQ#;^IM<48#_<4$t{ za*fkllgtm>iE_3o+tD^rm zrvKzw$<~ZIPq#WHcK5&7t*OYKF!8~XrD%)s3*r#%lx)9~ED#3GboL)N_7M46>Y@u? zp48vLq#WLl~+q_`J2UB}d;-Ddg8s*UDR!0Yxf%iUdDr;r{ zYuXwPc5lwjR*0%88rhO#R$rTTRq!hVt|o@FubK!!z|1jcRyMOZgBhbgM;#JCQ^=>L z%8!TMs2V6abmqb^`lh9KEzrP)0v%HC>np;7j`(-1->p1< z@0ot9qCKjMF(Lu8t(x4J-?^^m@kk-A8dz8w&av!SnaTz{{pzDw=dQESYT(di<4DT@+tWyBD?6yK ztxLfC(2a92daX?8sMuk6*(_t^&{M<-m^SPZXk><0+GlBt0N>ly4hhH-2KqPY0IrQi=&ZW@pHkV;0pU1>pVr4Q zRtB@tz5cRfZ@u)xd+7`?j!7j{L9 zWbSwU_#RUxjgRrl)bapVO8*;!uuAN=+-Mzm9Eb^=^1qP$6vHa@PQ2@HagvIv8+v`h zmdh^Ey_UFjtu?1BU2B2MPp3bH>aK;6Zzc7Jol&vE8E^n@s-y0cSy&zBi?&n{yevtO#RNRVf*c19aQk;dJqe zK&3aquAFwxFJTez2${*6_O&N zD=#QS0wKq_kmwY}@|bs7mZVvMVHrzOvASua>c+}a;Pm|+4>6om zoi)k}M$D2Vqnq}LooBK%CK&aowRTR_VB7?z?J^o15cxxFufCB?Y8Aw!A{-E|hSqOKgzRaBK{(l2d%5Q|w_R)~xwO%kM;jANF75948h@iC}UL7F7!xfcb`%@}80e*?6H3!x)(qBr$b5l?A=c0Z!W}kfe;~U+QxAU3IMScVjya7thID zzS0wm-$I=-4o9S=NsubsdvR;7&g=UT*KhW@X?>YUnWrGmE*y`@@5XX!tYhCSmN>*@ zp0wnn8Tte2Tf0QTaJnNbN-8OK0G92{F;z^<1xY%#$!)oHF%7szl2wxA={+{7W#6j8 zW08wpuG`om@;5WHJrwVBH65?nCJsg$XTyrBQc~WrG4m>vMNT1$d+9_0 zdZLd}1zFMXqs`e2X%bJnplL2qACGq@X@O-bFxKEu7q-!=rW1@W6iq3J;sj0CaUC7i zG%*d0DDdZs_f=c*P2e@Qj}6YVpGQ$O!YCt5WDL{b%&voJS>xX)^!h%%L5Qsvm7Lx* z4)L1p`5R#&KpzfFh?$c+x_uPAD?yTf+1(zWyixxLAmSo8a z1vrc2*sLAlRt(L1PBl(fMM7`AVZb|M~(wavK&QS{hH;+g>vY(;G~(J?d`p%kJNSFUQ=k89Im z54P6^W$dvv3GD^~xI9bi0M2V4APPoX7X#H`yc(=-R}(^jbLF5H?qps%=yk@m^>mYr zb3_d+YFV;IF(pgt)HTfsoN~N-G!9^Jl<8#`+0q4@pTg3(L>Q^xciIm6gQ(^anYYW5 zg#*|P?lfoPNq}L%0A}OldKV|x_hDKV(j>v@X&-m)ULcDD>^bYv8UPRnXYHaqrOtqtSTocLtukwFf~oOyWwYmtYuj+&t;PFlO&amgRW;jh>R5;;Ywm z6Rkj#>>5z^Xf$2*KFsFc2QY)5RxE&Sdmo^zVTw@kaHzh4dVg%MwRLn`O;ScXLCHv2 z;!raZZyu*|I2nRce&uomP&P2JUg$TCLrjL};JN|F@2q{VG{gLJ5f2ce0MiwV;c~HR zC1RboO%7pKlB7D?k+QC}r8$LJa!O352_O;#W7X|no@|_7;WQ>O9>++N1eRsO_iTg> z${Ol#$j&-vl&U)SuJnURPLbp~Zk+7l+O;kWQ*lQ;eAH8@fh<7B$rs8Q>nuwXXodx^ zy^qep$$~&@l7yh7KwhR-u45oCnw{N8T0gdSADV8gsXwolJ-DVrGt7<7`R{*03AF0| zzukOt03f#ulDru$LATXi+ZO;-*+2>bolA7=9H-|~4Ei%i$hn4FCtans6EXAyj^hI# zt~2}2q7ZoPjUH^hxHQtF$a54Thu1k+35xPeJp-ogZLAHOwpVi`i=x1Ec%jC;m$D$G z<_%0oJ(#wmILx<{HQe?-;&8IFI4&(w9B&r=!Mw%c1VZF$l>7>2SoTheIdL#SI32-q zT4fn((Jb44Qwh@6nJfx$qalI@)JoWd=Ae{qX|P@XwNlX<0pkpuYe;HVeHC^(a7+XZ@q0O#kk>rENM z$@MNY-9o$VpxvHjHd0Ew{zeZvQ)Q4ZiQif&wQP&(vm{n2wqe0`=j-Lt06$LG(iC!zM~@PFkE!d%gvG|2dyy)DpOqah5!hz9k(!vSmP_6r7^;ZqLbWI z%F#`GCkC!u5R4;^TQ}O^T*JN58+dd&0!NIN-K^-bi%BV!bk%gUl9@14AWqb^Hgs)m z1ih&Pt{B@c6pm9$n3e;#y${`*(L`2}^RV{_`$tc}u-!(!<9|3%Jj_FDb7^D#+#Xlc zZ&%BbxMrD~&z=m^TB&I=D$%xcj3=e2XIb|rgy6=>9*zzcBdR<1`hd*fnMGp_{4yn% zC>SG&g3=+V>}j%vRLZoy#u9~U5-#3*2?EQq>XJ&d7Ky=1>8jqP(HGSse;HWaWi8KA zgyUhYExC(bT5qznBF|KbQ%d-q18BOnb2jm~CZ$l63)}|{621V}DzXewFu`Pafncoa zxm+_~yDeC*56kgZE)HWH-^%`E>yGE;<$-dHvS6@nwdzj76gsQwtE?g2ZdOya4T14E zL=XhfbpywT9wt$Oau;}OE8C`8J^LPlQOI!XMjN_r;Nj#R&MroHMgJ^3 z|M3*ZEA^5*&sLgtoaP84bq#clAzw4BvaUSC7)M%`Hx$`bf+(0E824-7{k(GyrUP7@ z-f4{Hs?x^yc0YZo^V``yzZrg9s?@c}XW5f(+Kn$8DW?vjD8{`9y?R1z*&d!MRgbpa zyog`69uBA}xXJKBO}9d9WR+x`qgbQoDFs>K;mEQKqDVn0gWowo_vj|P)_$omNy_ik z(C!{%+&|k{{%hVSp`}9mch5m9BN+D;9^cZ;%h|9_4wjo|ouSDqZc ztW~%Gesb*L>|DvVE5X;r8(-v#7Edv^U6e#R25hfAi)f`p5MK=!7^eb;sR-kfB!lCq zBWsG-H!*{GR)PBu$9U>V9iHzYj50(?xR#(jm<;MM=J|S@VOm?&y`@xx3OBB`VVV}s z!iP9Lo#Nd33Ph3PjNFG$yi2ioRc5;_q_LVXB803ok|+@f$_Sb=x^|jy9js6@tVTkt zs{TChoaZBEZD~>VTKo8+k7@9OF$V0CFTj=vy1Hs)?%$7VSrVhjGWeZ?wT`zk-zqSP z6WqDi!xK057n*Kilwvpv(Y7Bya&EE;{b0LoNZCvbq;UDGJjqh3Yq#7a%<}@2C=#9u z`lg;O8?LV=Ie95HwF$+w$s{D0rmtN%-VC!GUr`cgX$>vpngO@9w^lug^4;|&H`(rl zO^@KZ{WWo6VQ1kxlzI2mHxKT{ZGN)hI3I?cvvDpEbz zg&;5u4oaC)?`G@k&xF#A%?C=<5W?xHI*x;b7LsCp2>>W@tw{{8y;_$3_yzc=RAt&Y7r)>b2?DU^X-vwwYk*PVc7V)zh>YogAC8z6u4zSzw&*X92ME-bn6p(eCIsB zNUH4V98wAx4cXJY*}6cQ6iBnhYh_zHZeH^+3^|zwB;oDPwtahYDvYUm1@ zCmMx)g(P5vfG!oG^L$1%THQ-26@)R3Ll6Li^9O1GjBBvHwi@gA_h8yCxMpmnO;rev zH@`tRZ;Wf@2(g&^S|Ol!QrTsJq?p9u&uvHr$1IcY$_>)cXiIEYf{b183KeX zHRfhkWk^rlXu~o!3`ZfR(^uK!&b$F2yQgec(e9qv5o zx~l~VRr-<4109XVV2tDB*u!w#TvJ=_?k`)D6IuC=1}B{r1g5E8ph=LSd$14NZ9zBf z6~u_PittZ(!Y$9 zuD&p@O}_?XN9;A%ba357)Ih#6AMI8z6(a?*GP1MGW(O@rvG4*>%4+!FvKf}6B*^B* zSDT!3W&h)6)Ohz-$!`Eq92$92FsYm7M8O_x>nD1YNh2a^>HhM`IsvdAzQoFfXxwc3H#Ie_K( zHE4g=nyzORxc6`jAq3iO1tm+C(JBpAY5O(VG+}TY8=butgedUJgZp^IzPd8jTNx#E zXB>4k#k6dk>y5Q!MhhgVay*u$HNpxjD#OZbubH5{B0btvcVBkS#tULaF(u5$_;UZZ zaKn0b?f1;=@}-M)A`kP%=Xpe=EIEJI|4p8yn2s*sc%3>5I-h8`ak3B3cabD1-nc(P z+bPhp3*5Os!elZ-P8g<%r*9r$PdR~cCM>rX7WQpUt0k6FeuIb9jUt+(yX(JA&$WrAH^QAg>I32>W z7fXtU=^&2Yyn&fbmPFItN&8E=Izp)mnivCRTydVZ%ly{V3yCtX;UI)}RthVaY`oJts6 zpyT9t@Mwb3aF%Ikx{haWUc+_vEV{|tH}30kO(Bd_bjUTuPcmOd6S7H*P^ffy>5@CG zRoSw~F{Q?|>Y$YXzyTQJ3fg&v1;Mo4h5OpnLkXwDg=s^}^}nn2@XMI(wM!IS3s$Ml zW0($f(}J#BupCc`6sHv3j#5vT#S|ib2&!|5G))kdBh%N9JWS)+P2R-60jLNp$S>c~ z%yI&^q!*or=>q@ryh$NY(AmxaO^`M-!@|iKZ!` zD5apx#PP98VO}|X9cTG#m}>Vo9)m&6og?VVNl>P0XO*RK*f`=!i9l913e^kQpyE*! zbq(5byvB30z4pdQwPojAl{Q|+Z!~Uy&3tmVGQ`#`RyU+OM9`XUEG$A2K%Prv1woQi zL@7m(FiawbVaU-BIC@hJqu4-iT;SHtE}Rnbd44egl{s`S>md}4N!+zQkF$#@dcE1A z#yH1~lP+$UPhk{(cVJiw_dHt|<8XpFnAEchfP#MVB^a0zi3DUspAb@K-~X;HoD308M~J2)M8Q~bN{16AL>)~Lj0dE6j{>EYd+q%-@~mNd+uOS{Ua;3K7nZW7!1g5FOb{w=?8G`8)&XQub>+fOGkfJ0R zg&+oQTvI8>Yv-@yEWVGi{`%JQ)2RiKU9JX3DOa=L1rL!Ecdl`L2#2)k$mUE>&C;~IMDBOKsp+i6~D)_b16S4xFg5K=iMA%Q{? zjPLg#q{8(}Nug;3sVu-W2PUWBOldhX#=sZ@Wwddi=i#FvqA*0u&KJrSUlP9sP~bJ| zw?T#{CL1Il@==JV$@ zaB>+Ff`FB4NqYWi zK$y)p4>{6^tT<@K7^D=9nu41+fR`g@&UO3)5oEXk03ZNKL_t*VU($hYh7Wdrr~cgL zK5p92p_e?sx5qEx{q$oyo$ET7UFCQy8dV_(vYcQn7$#|iEad>9;G9C|6kMY)O95TZ z6iE={tZayG?m0*)m9}J>pvVQ{RKRmhOr{CqIKffZteauWR*(d3C&xHQAkT(4JZRNf z-O=G5I2)or4AHWRjT)1?nrh;%FAdDt{!H){9uBb(K`*}_Z-#Bs=DTbJThR+7;q+2u zWx8P_i4`uIm+(6&L^&d^N-v5(yPVKFlv14arf6BkR(0-erknOoPBqVS z(53985TaJ|cKkgAqvpD^rknLRd_{Gdm14l#%(A_*xxZM3YE(m7V}w%JZVN@8Uugj; ziX575A_~TE{Jjq>)_gvkBixKEBuSCw z0%=wt&4hB|5MWe-5~wNFJO+UTqkyhSkcObn@lEJtRx(SX0J>q}IsZNQ*7(cy=P%Na zgAfYG-@{~Z4&MT%af&zY^>Fig2V7H&OQ++5F@guDQ?#u7%DgNJ!LYpsTL_|HtJdPl z2_eB5g<)IB(zvls?06j%C5mcc--ZQ$?+D}m`ewM=M-D*NLoGrS<#S6m0t_lscy$$^ z?Ao_kHbqIHui&#cnOcP6n%R*MQqx*glgw2~^xfG18ngK46AvW7uE6+BG@n_tB4Fnsb<@x{-05!QNPZ-aep`M1ewj zaP?3%b(1}_!2L&KJoA(V&vOyRIr{wp^ts@?8c?`-y$!=OaT+|p+1UhV)>k&}f7uLb z!Oc8G*xo#KTivw~9mch_%@sx^@_e&{7NURJ zlB(l(cgl9+jH25%R(Lpyya3}2hG8`-oM^gwznWl{X%f}-?PxMufwuu=`6Zkp&(eix znK2ICa$uMiOvgi>rO4AnL2An=TQ@8iCH3i>!6997V&_+s?o-?}i{b<-v+&F7l$KF; z{H8kWv>@oX7V^QOpCQa%bx>YU9!&b@bu_&kC2E?6gRYH7rvqHS)`g`rj3X=nAVv|# z^&=&L6h{$GABH%yURn|T+-Aqt?X7$s07~J|apTR_3=47tOpg#C%?ec2V&AvX4-&{i zKtQ28CTR-BTo}3rAtlm6D9D(lfiVhNjs;Un%m0%4T2@%i%S=NW`s{HMqEI|8MS-Fy zkmmw;&>njS)RdcYPKEm^O zH$K++tC)^@@Y?&Bj(RKi%rOLLn&Fi@ecZm;u9b8gSIKC-c6SIVv6dUA$xPebSvfk+ z2=)&adk0cV495xDc82kwIc+yAcWr=BLFck0g6+1ziq(L@u$;yPq$qMk(-BBHsaQp) zRg}#%4dGb`|nzx&hPn)R=jm)=~E3@O`8?g|2f1Wn-{1!rfH| z4FE0Az+jpo2m&~cgX04a{ee=Su1q&=oJKFLKe46g`F->w091LS)lySG%k-j}Zq8~! zmF}RXZ#{X-_3I&wBnoPNjkx66;F?jY7Wa{6YTukwh&fHaQN(c2_29S;(lo&<_s?)< zzJ!8YzJc(p^)8H~ZFG??iY#p`-!QI0H_VkqW}dt#&Inv*Hmq>%XuBTZP9`OUlx1@< z2c;AR2*M~uO2!~k!jLU^u7N1dlp`(x#t8a-MOKsL5`-x9041ulP({9`ZNaq+M8N=L z&4g?kRaBpwA$iMAw^^-aGyn85d<|HX(0Y-697UcXoQ}{rxQ@y2VlBSi(iP_TwYx*y zzC~e{C?(Uf@bnW(MoY+S1x3_kTr)r@L%Kr^IL#HOx@|A=UI#%0Mun0NYcR^#Mudc> z8wg8yYd9T2H*Gk6rNHI^ zER2HYgIedD0YDN1wpGFFQh0L@YnH~y^Awt9!0{9`hEleXgoSZ!WnxT-qNZ;2+6O3# z48gb$LVzqQ6|xyasilcY#L#Jb@LL}8EW@k!&M~yV3C;ix7g4c0xZdUMt^BiGGeEfp z#yFBV!n~^?gur&&E4B1_=R8h)Ts!V8=;BpYH4dee9is}K8O}4{LJ;g*--bj1P5AK74#8RJd?6u0&}lo!HjvZUuA0Jx%r;}8 zcg-H>&b9tKva-oWFTV_5TXxQsDMjc$Y_DDOFf^H|3D~ZO*YEam{m6x1QqSs!fhTY7 z;qHS0rf~+>+>{*=SdO=%zFdk!PuD zW{sQg^D=+=CYdR>)h!Vgk6$jZ+!i3^chxyJ@7Krl5@?fUOEQY?o`Zb!y9=N5_Ir@^ zKDX$g6}~t`mc*bGu=N~g7h_yI-oxR6k5^vLpz~DK)v|9j?r@WHHVhk+358)8$aB?Y zU(TQ_w!Acnz!-;ST1q9@azH7sp)r-iw%yj+2U$viqR19jbSV}3fiVUl38pcF=R4?h ze2AjJD-R!HV0;@Ho7Imkw!4!)ww^>1Zcsli32&w)b*sO3u<*jW?fsP-KJT0-sfXK7 z9xjv<)HXTp-0LALGEh(mk|QS(9OBh}OGS7RoG}=>p>*+>1mWv_nAdLOpL|nASs!i9 z?)mKo)P}|g*2QCPtBW|CLKHc4vssI;GP&mGmF+6>|JsSj1_Ov ze64e~9ABlfWkacgrZz>Nj=zUEoT6>#cz8BJQAl(;Y7Cic8gAX_;^D&q#!&*_YIa^u ztGhs2waFyZOYXXh5owm?7)?^_d+QxEp{#DoEjwvKX(O6J6gf5y$S$k70 zcx?oe%Qda%jq3(nf3IY@`}3U~bX#2nZfp+L^|_@LcQU*{t9y(j4i=)a$~j9Agqe-Q10SuHk2KA3 z_kJIFo}=xnXjC^eu(6H#oM<8apEJ%iL_5HlC}ntPs0Yy0wnuc!FNu1#mYPUXl?!y! z0%Tb?ma_bB+1M(}B$Tld_M|UuClvt@gsfoe z0bn{(wvZ+9g2S$4w1%S)c_Hd&jSzxs$6cJC_c0tRc{EBSbi=AuZg#ae zqd3@K%}9ph7>3sTe(9zSN-2^oZR8sVl!Lx3R|lbVMJi75SFaDb<8TVEb8smK%@~L6 zcMu2T`dT^u9z;>>BvtpgR%KMXM(j<#H5UYFp`qQjkzFj6H~jZPiUPzq0_XaAaZ1WK zTz?N~(Zi#&5pJC9quXuc)jQ{~v;#zJR`1#7oPn8oH=yW6pFG(|n#OgMylk6v0}ab< zWPr2X7V^1>d*wTcqF>Z?;N+U(mU#8-HJm5+kXhx^qU?vF}ZQ*D%3;(O<}L{Sl1&rJmx&cNMd2Sk6jDbrqY&3@0ZYHRrKZ-eCSa zk>@#xb_hDp0X%P9H(IG#zP@fRP;I z!MTFPXgb{XJ{-SdbW^X{Cj7Ie>no9l zAw<5G+haQH!ENtf?w~JWnqh%bc4gwH$|fXWr7B!1w0qMb!f& zib4@@4=>7syMXPr(Aql!rK~ZER;%seL*};jkioQ*Xw!^iC>4r@BeILR;= zhKTID^|qHSYgBe<-fVQhv?Lm8S_mm+Fl`UvbdDft&N+vfjT_hZ6!b4i@Y>x0Tw_)m zQuTD@Kp6#?oLwt6*O)1a9C0uyxpXsdO^4UshwZgDszJOmbdU*&7tGgoy9k7+&U_ND zjna3DZOVJyMDq7j12kIrFRnj1(A*A|y$M zhmZO=J0F5`hG(BTM3iX=l9@x(4GWspLQYIrj=wPGZkRT7%K-?%#l;907b6Tu>eeW+! zO(tb^-}ZLe=Vh##QhXdO!Zars1RSk)2fBQS;LrXpvf&pO_tSbW(l|m<fOQm`g4UdG;MD|QCt)S(ln~0 zkNK5aHQ9y>kqMycbCa0isV5Gg>#OP9z54?U-LLI*{PppbrJUt5$FX%A*=Y6Qaa!HA zV0^dTU8qkjIOp8O&65r++d>k@xN~m^-^vzv9Vn5=v(iB`20HJcIbTWj6jzCAY*kT! zZdmmLoz3wS7?y)Usv`O$e?8uP-Zb6B=;GmK9_$^Q>P(qq-F8HQHyTkJOEu^k#i9O2 zHyuQCPHG*8NS4NsQmmcyG)xDCkh;%NjfOAdfS0Z98@P8m#6SJ#UqBEfpp>B9a`4yx zqfg+eC-?EKSI!_L;M)>R)9~rfyo|5B{3`zY|MpX0lp`;tDU|SW| z7})Q&@E`ox_rc@}nwsST|LCWG1wZk(egJ#^cI6`_mZ5`dS}o>KM$Lz9?l_zs0Aj8cP{-@fC4oe@#YA-QpRE0-j%V=ai*wl z9ml}6jswRrk@a4I6sr{i=Dibf5~0X5Fy}hBW&4<npZipf`%p?fTgF z_A%(CJ3Hu1P*}DNDJ9~hfZs7Tu7(vpHP6zz+pOs(yjB-N3Ps|bD6*vKXt6_@6$C-T z;JGHAI`V7hoaY55(-^K}f-#C%gqV-%t{Od4!muX}5MuGgbX(nWGHUr{*ia6$#p^ZQ4r})Mw z#*3}r-{~3{rUOyrDoriX6&2#5ilRu#9A6DN)MyL^$*8yMm+Xj?ad6Fq;~M~EEp#d& z!MKhj3Sc=NjKV2@uNEf9@6?MEB?_gj83rH$-Leq})15Q~^DIR)9Vsf$xkXktEKs&u zDoB$ELJD~8gGNpmb-o<`>RfeD6}zxEnTQ^%dV7r1ro)#KK=Pz%nrqdok@kN*%jXP8bS{Omvfb$sp%U&Rl8 z{2dCj%rzwGY`l8jmdg>EZYsICs%NogNG6;pa(qG=Fz1k$pE*Lv&Tv6MU2om6z!+D< zTBeO)GPpE9N0!E*jKQ#)Io>a0gb=v?9>#-BgJ%R@d%fh9X}dT&c50p$DN;yK5biV4|*;@2tgD^ z;4}xMQV(W~*W;uM@a0dO+ut`RF+@DdO@3-dZ<6p{$1F*y0`NV z&GGltgkhc`OJZ1Ft6oHfC>9)Pg}A7GuFii`Lr9kAA&MM%8Y395zGPfCKtL|V$_J=a z+OXWl3Bo2TiX78X5B}aECc}$ber@gXO9?59lCNV4Zb=CG!zt1O8{0E9qPRYX%f|o zX;I{g&5m)7>9Ak2Qf)R%7w8WoxUP#%%fax$jkOM%aSe{wL9aK2XRA(gSk|BC$37X? zV3fj-3aZpR0zGe)K3ipBN)hK8jt?Aoo)V-?;uz<>De^Qy%Mc)@L{N@;$7zI|UQLpH zxxRkec{|en>{vA203j4$|+|d;|P@XT8m69YxE;!=C!IL*T&-j9Ds2VX~Vk>d{Wg3v+n_CAYPQu`+hG=Oj1xO)aIW44dur#H)JG^O=!0MCu#OyoQY*Pgm zSG6P#p&J%D2iGw;f3S6XuIb3r7=%!8t~WBfxqi2PSw&G`GCYUZKEQO`QxasTSoLNi zfi2%e5M{V?w}+E!Z5W2Shd~hI)z=>4Z~nDUqO;e6Wf}OhZ$HG_o;yO43v^ADW&GK< z@8W;?hyMyv0Mj7C$3OCJeE5TJL7wgg15-8L&F|Q<5kl8yWAjmUQRJY6tqT4UqL}PV zyMB%*!^JGg@jJ+p%^2!kEEo^eJs9;aMQEf3QG&I&YTdNJwHZV?OxIJK7Nb8}`AqU7 zQ14yPJMV+$s0@5~@d(A-bCt#+xaInnP7_UCVl)bIcxb|FGq}AQ80cyY_yhd=;dmXS zafom->niJpfuhJEr9`WHSkv|`L*=9pP-PdzNT=!MQYl1n+U5m8kWyHdg(nYPXu5h} zN5e5rFO;m+VaJAPw-v!nQ6LutUiku~i9kUwhh=QSK3_ARL{yG2GsfZV9U_ea5W1-9 zUDef=opUBMKe%9cY@4$z+1wAV%9> z`xAQrxUcss}-Zg^WhP)D} z2(37{ro-`9iGYCSMkp|I&ehLNPTF#O#eA5?5JjQXMjGm`jBBtQf5A}%;{j~9t;$$Q zq?FM&kj+nr7d6j~Z4n3|5kwi#W=av#_xUc8<LpZ?7+<0t>tCl&AV((zDARfCf<*j^js z;n`N_tWX`=!aq$ccI%AmdaYJpl`nQODN9Yk)f#doi&X_h+olJllnBNHMLDpgX=zwa zz3(QQAA}PU7)Km?Z5N$sOP|mH03ZNKL_t)&4G_!LM`3i{3*CQ9IRzbIdUkK8_k~|o zK+)0#CX)cIwvStf9gHRkOiET(yfi0hwaTiaDFjH631{1QP*piNr%S$Gei*s-}fP;l0=f`)j3=N#a!1EnTn!7I2qPB zXWg_gnp34nk`P&;K`z!RXuv?VW^z*_Z|E{pk(y{-z;GzYQ^w*V_bv3cR0r`w>ZLG&UWvtQ>P{gQv~D3 zo7!4-(rTny)GxkL%vgogF~(P%b7kRl2+Q%|m4x-%99>W{;qBWxj*mL{`Cs~7eEg&D zf+!?@`PaUP7v6FUmIlC9+ z2QZiBO0t~7vQz{#nq=rYvlEe0u9c_B(*#^M)QXcU*j&41;o6B;kCYCE6AXqS9HW45 z&A!+1J2mN$Qu$VsN`+7`tZ6<%M%BaiIMMSp>o(GGJ&dO!g9#>a9nB<3h#+;qbqhC7 z6lLgWI7Y8OLEA0>0ff`V)!uSjD6+J1Ri{MJiUI(kvaUmKn*^&$8_Ujl7x)>lsIpy| za;Do+0N;&4g39Kj=cdoU-~Ox68o0KLJX4UmvTIM7iZVB);X;T@Y1oC6AzIyI{AYjt z-@~u|+8^Nm_`f~_L)Y;B_dbV@efVw2k_d*O;g7%i8gAY=#9qg*BV|L^@I4=R0bl+4 zYxv~H-U9&OjH2CgkYyP}kz>DO;=S*B7GL;-KgF|8e*{?)fq>xna1X!o=`SrD%d=0P z;6s0TAKw-VH%ymVPBhC~c;pRyjmSxnGzU%DXgFagJ)oSTicF>dndo2xT7ZY4N?%-hG z$E$ZzXe?bo9SAUJx{fqWz#Ag9BnqLM_6kfb&r%Q=7)K1cVc^ycua*)Tk0y9@9>CUf zbezQ%$#guVbKD-4im{YRj*4KLIjzER=b76 z1CQ$aBPD0NYb6d+VID+J_Pb1pvwgXrZk@?3QgFv2j&nOig*t#b~=-gD8e#-*^%Ial^E<5L?2bBiKJFdo3~90J(PEvy?B2qj7pen+dImz*;E*pGY& zKl(%O2T;NZlL&d1fKZALf8aU%g%_Vge-OYjHMCobGU5Ba_nr8@?|oK$DLHPK{g62WWlBTJLH`?gIZXT2qHi1z+96@i!U6r~L28eV6{wR)kJQX)tw z7&r06%^4p%Aq1n*`sbkCb}<=GH*$clv)$Acmk*k8_?-i2RMldJ!*Qu{>|qkmUeYut z@JfYdMK8K~QL{9LF{iGO6$F!*p*Ph5%5m-59!{?BLpKaWVT3zxoMA8+W6w!f z0!lUF>i?^>tPlj2p^h!dGGsJ(tmwI;A8jS(pD*7eNr-9YqTQJ}=OoF{A1LMLWy`Y! zl(D)wy3Qy8igH+mGT`mxd$v*_{=JXQqJ+<$t#6`jGRio3S&t-?Ktk@EzHOcUy#m?I zF3wqHC7WxYO6=hrAY^TJ$2A>XH+Ghz0#sC~plo9V;{lRr3Mo}XJPO9;}C(v1rEQt_|2MES}#K8ozZo;&^ zGQg7!E~udo38Ig=hoPW1VrX8{mAoCMZ#q3d&VFqv?hk z0o9FKxquLYwyz_}1oAwGW!pG9R1vPh5@ZF%p{Ja$loXc5fnss>WsIxRgV91-0Jg1R z&*acFtxg+?JVy{F$g&)JEgh81>L^ka5K`0^JdGomwoFyjL7!MW}ym_qiPDTj4R(BOGQEEPJ8V%REgl82vJ0D}O?KEza zWd%5AxF{bFN+euUX;02)vXnAFss%{X&5esV+rYElL;+mYi8qb7U&bh7u-&$5Dvo+^ zTW?ND%x!fMPKOXhfnYL#*WL#qq_K=OKe!_$Fbp}mT@RhMS8o%?DIT5rHAUKe(|N(0Z6>~?k83HZdjnq zz*oQdI_^L0!M07j>+MgW-S&`1K$;gY3?0Au*)PNQ9K7)C0g@;KAR(k;m*cvLi_;;# z`Db@mBCA_B4sq?Miy(~f^4DKmL0wTw@Zk@=1v+Q={1?B4IG%I<A3)1Ah$SAAd9&Sijfu^qhn8>E&Ur8lFc=0nYzZ_q{%yB~EKBQ5 zz;e8`YUPvwc~Pli5J=FiC5~nL?AfRA(ZlUdZr()0fm6nzoAz8ouw>PkYZj`R!fg-e zY)qSR4$HOY9RAGFYr28q#Y23|_|!%x{g?c|R%_y2#wLSvxa}^Y>9}^TZmYX9EVW9H zr^7`Iu7YU+!Ke?e8Eer6giwI+dVr8?C-bGZp{|S(P)aZ^D#WDSm4KLvO#}@&Rz>A$8Eg! zMjvfE+es_~C~MI79`w*3OwjG9)!{p@KES7c^N;c0{NxYADPd`vVd3t*^D?x55|nXh zx{06t7oR~8#CY2aPhdQb@IU>p{}Mm`H+}%OZXSVaDF~(b+BaUuJKlC1gs8!iI3=Kr zqti0sdJYEPnc_D-^T+t$``-!x^~07O<#0@jFcO%SJj-|Pp5gGY4a?9$sEWok!$1(m z2!j||QQ)ONc?B=N_jy1{w0sr8=Y^_4OGu=NfN-u(?EOCP6BrN9YVML{Q(V>RWf+GH zu4m)mKrwX%VSg{iDL{W2`J+*EcGsEhJ{0M6S>InFnSH1)`6kBb%3PlCJf7k z5Q|wffEx8dDTAgPZ<;E1)dUPDL*(INmYpV1O(lF4bG#0cC}8C1n)FDY`8af8__>1Iifw>Cb%z$44D} z`_QcBov8(9`N*8eIRMY)6< zCqyF6l>>0(K8E=e+8QN|Ci_t5v-thNNAcOSPvOPm-7)b}h}8+PTEunp-|k8fx~&yd zNoZ9OPz9x%A5z)W6x`LOqdwaE*VJO#kU4No#~TmFc=)i4f(eCbXt@2vA=;i(!@+E? zjqkkr2oE2vM$6AUeH|y)4k3laH^1`$XJ@koMbmZQnHx2<6i}0}zx#!+;@PKffOC#0 zO5uAJ9z49jWE$dw?|&YEgkhR^^qmKI`Kv?qPL)|mCK;Z7%K*H-!1uVQL)xP>CmH{Pdp6sOzFc3Vix25ggwqCgx@VS8;* z#t{eOx(Pap7}^~l?Y3G-rIfgTzXvH|_*+UE^X6Lx9-fYIOXIL?8;AP^di`;&Nm=oi zq;aqU*IV&0geV}rC_P_m1a(~FFm zAcP{y!b?vO*4G9E&l~TlSKBm+YC6Vwi-Hjbp^oF@7FuOl4ZhPNc+SZ~?D< zfILr?DCveYJQ(-kwfD=0kEqYHVzg`d79O4s;jR~=0kAk`ZE9DGENkaj%+6<=7AbtXBy7WNBI2je*-seDDwH?D8SGE((mA> ze)320+%q=-03sLo#eefTyzQ+|;BWt@pFpA~;97x4r#*b@JNNLew?BzTXHz`=G8$c;=Wo$+sEDFCvSxGIgqOP4t;*H@IQTS{AbmZ;L4C~D_Cju=`k z4||=N&w2Q$4=G~U`sEN%geWI{_u&Y)Z*ur84{4SoNptMAE##S+s&-m?lPa`HNow0GwZpU>X|U_wJ{Wr_Ir(C<+|zd-%ZnpU40F4}K9Zy!95YAMfFrr%&Ly zCOnVBEJ4xAZxXdiP67-@F(7l8T*CYRnS0M*+wStr^S5%^@uZvYRZd7CKu9Pdga8vv z#u#kOc*5)l;6T8QU{$e{i=G$p(zUU<6146bZ^GOE;Z- zc3gR_|9tqbox|DZN@n~N7u~z#+AF;4{lD+?K2O)3xdH=hvCr{IY zXE=Ii5kh8_gC8TLwC7k>+q)x)JS9nDR@}qvs4;uuSu*8d8NeNtkBpGq<0z0~{9_mH zxt*NjN0%sh1ud`@5cmO0rO5-^a~@xmPup&6Q(0OY$u_d=)ludy1Tr|PV-C;L^qHq% zzjfh)L4IIDI|)g*T&yX$9~KeBQIM)~pZ)L$!7j7TfHr=oYx-F?Mq9}MJn_vF;?T9=h&UOCb>kshldw$Xn&_W12*XH>b&-1_| z&-0cyo+@-cBn&ObHnRTBt5SCP<&WPE2n^Habo4Ai)*$N+&fRLo<5xa$2dbu#r3ruW zxA*Y92cG6*A9zc#jb=ZP>bh|t?Umu6+>V0>)8*dw?>B?Ul*WbYW{Mzr9!V z1C}|z(V$!@u{<;#xW2JR8V7h&Y{VAY9@{{-OwO-2IDUMYm6bZ@*7w-iXM5DrJ{Pe*7%!n+=W~uFSMwkHdh^{Nmeq>GTdSy|Tsm^&LL{ zrTh5xUwuEf+;q*zb(m#BN-YLmD%ND}M$^=O4IIEIT#C~)kwJH#x@Hvl)RqoIdwO%j zF>_iipXFtfQVq&`Cuo=pI8_($^eO@|()|{Bj$sX47KDJUw!vi=uVNT-*RF3h>9o52 zvc@>va*a3)4%EPk!=S(9&e8-`p--0I@0yv#J$_U9hrp#%pEGTD=y%H|ovQ0-ih-hP z{dlVBCW@+|4@K=kU3Q@TELF}b+`&iXdkgWLBnm-+(>xX)9tIyOpI1~+ zltG!LkTnhcHV6(R05l7h<4yIx97bn1Pb1-o(A)&9MsPcCRF-RVC!<2o8 zI7HJ+AaWEW%`Zt}vP`8?cG=wiu$&;5;uV4-zW zSLwEP2LW196z;h7T0*~#s_7(2%7YL8lwbJBZF2_@vNYw`p%N#KR8iF{ICgY}`yYIg zn{T{oY}!oVnmJl7K&bu4hH=#`6&lF~SLkw-HHjoQRM(AtwTvyxm4PImzU;D%ob6qo zdcDGt@^SVyvjYX_w^rUWwLuhzfgBGF1io!8<#)USW%<5<_^RGpWY6`@hgx-v=xX!?XxGZHAA(rW<|1B9ZGLMBg;F(_H*QQ;YHJ*J_H*u$-wJ z*&a;G!FEdIA}5GqKK~_YVbpBg{=M5w0wyq zuwHZ7Yeh60EvmH&Cyv&5`OGd}Sts&k>`IfE_THA%5E|}0D~cjBB1NUy@>!~t`eHEY z*fL%>Z4}MohmXC)Ti$pHd6r_>4nY`W7#eAsW12D$_b$VpHboD4mhxEq1N2;)tttXc z)#@)>dyNQffdFk5!!Gk~CXSiYX?Lkq%N$v%pI&3M5I2rkQw- zN~s&3NXy zGyMAh@LsOE^5oEG^r(mmA9~-7{O3RVA`kueh0zaDh7OsKluQ&^e^%8VzZ_l>Qi-zF z@_GKnb>bx9^qFn`r_a2bi%zVdX>tO$cdQM|CQD=DFz7QpO0^YC$0Loxg@W=pk~rK~ z_$UtjnanAWF+fq(0}T-M(2X=K+hJ{Ozzk|Mx^(^ERRw2YMCDM39M=fh-c2zK4cGHH zade5Z=Xa=$d2DxEyXZ!tG_|$eVyFxB2ov z-p@lndX{5{m)Y8B^31bm_#Z#>9>OTaGn$nqL=Ik^AD%CQ}%QbxMFy>B$ZR_#5 zgDcm0x6Y&!1yN2jNVx2hHB?nW2*Jyzcc?fCUZD>n$@YUF?Uw5#k&oYQj6A*{rUjoo zOVL%8Fix>;6WcP_=_pLGV4R7o%(HW!PvZ!~utqZdyr@BsU>{9_KBm3o0?c2>A)A8x zXU9E3 z>oIMQBnn89Noh;Zv-zcu-$s;V{QiIW0-M`SuDWvY{BVV#>>7ORL$~ske|&(qy!nd3 zZy0)=Wf{Ed9dAS<io#_VAK|h~ zj1nohnp}0o2|n=Nn>lfOwYWpe z+Vb_+T}qzkBL`Fgj%X)2&kH!7&U@ecrjZRZ6cgJr0UN;6?#2?KXmQrPZ(`@(QT{N& z3`y1~QE3L!ky+O@vMlGh7dLRMd}3Ot7ow6gu2qb>eypMy4u=m9JOx{=E<3v|YHmi@ZDZQ*zGlD&g{lh4>^QT-sS_*IY89e5#Si@v zmWZCj5wE}M$k1CAoKl4(3TW?b^_MV79C7_MM~lD9<*s2lIKt=p*Bv7lCy6tarFy9! zoO_L{Yp%YSs;i)C+Q>zoL?MlM3!`Fj==$+Hqt8k0Vv;z-Ff&RO*}#13TjT(W-);3j zU(@9sPSrH3Wt$t{c#62F?HZOtxwcBsZK5bDmL_Pn0$zAIotYQyv7LDDtr^xhAr7 z!S+s<<$8%E$z}$&@djb9ys;nEP6&ZvSd90>rv>8+PK2lSoCeGAc`z&+l*O8Y<7Ng^ zUsIIH#!Db_(4FUpa0UmfS}d#dGv`F`NT)xHZgkd`w^f2`};=7gg4)G z4fXQa8W))XU;p~c_|CmQ;d}Q#!Ch~EqujP$!>_PU(@l$yedsp+;~)H0KR|1$KqW)u zf_5k1AHVV7$addy(>3Ioj$*34!B3J@A&O((`sS4qekGE&zb zM;!W;s>>u%a3F?94^h~iIWar^T+`q6CRmJtH7)D_PP-HrJmQ5^Mr9ifi?Ut|{kLJz>wgH9~bME{umtK4b zUDvQ}6DzJ0X);)8iq2cg@1E+;oMZ}3U*mZ3dxa4D2Iq2ZMUETK2qJ!G58EqGoM@Kq z(u&tni&>ODZE>~i}pujAygCF1`1E?8c!a?=fR zh-4T-WT={nVOXpzS9sIwFO@6DVt0P@gSWA>+v-ma0=)C>Z^W`qvOFbj2UKb+eCC(l zNwei+S~f{+qiH#-D^;$4{iPE}#fmI)R64KHgdXA$j(lK<>eYj z57*e*Zqp0`N>)ByZZz~e6ISyemv>%esj#z>C$Jx@D4NajBXv|&quFe+xznLyXGNyy z;W`GLmO>PCa7$GT%Nglx&q7aVJx$}0fe?}BblZCvmW@}glcgz9Hh(Aec+)*-s=zS> zK^RjmIoOVh9Sj2W+v^{jx(tp}g?40e@yQydWzlMfoISrsy=-DA)3?E^)Csz6R8^g6 zRO*!{t=)CQ@O!)a001BWNklhvV1;h0fe<-q9&^RTE1WpKMy=|iX^8(1__~`$bhX0awSC3?WxT?`IY0xdVnO3CyYAA zk%UsB*tDDr8bk^cl~kAtFn$l)#qsek9!?rX~CT~1m zrA`$1gVo0rb-MAT6UbG9<5hTZu)4UgyoE~ zHYUcN7YxwTw(3F!B%`22rHjoorzdqt_Z0M~;7Yx)CcYWn9nY64#j>pyMd$a}(WCjXY0Bf=H(@N?co$ z^_!jT2JKF_KVPmWkftelmSGqMVU&#Uh{vblhB3`UZk)*>8wK)WOd_dYVL4vGifE3g zRyn2W)Mah8R^|Mb&njT(8d)ZN60j1j+nviAkwQz$`0WO^R~`xcimKw3>r*p8 zuTt;pvk0M}>Z3QkEYF7ok_J!|wLere{`<9}DK!s+z^xR6G$1l4w73vLA zu?<|uz_ATX%fz%SOv|ENp7$-U4&82-Ml<52(_5H|+OO5_hn_{%@>029qX#*XzrNX` zY$XdNH2;#QI2myo@bc*xvler5>EwJzl_=;^TRlR1Z+qk>`>T(P(yL%^Z?*yIaz6_HYmRqV!I9^0SSNa@!6%g?kM(t=*cocMI25PJD4x9(mcJa5@ z`>J!D#$+=PBx_(1g}gk^2>mwImSgp}BajfFjoqlSEbohn4WrZCK~=Sh zmCm9lDjz7tl;R{tzcb4-B0r+jkpVjs8YNf9b&URJ$^R&Wn~5@d^n2HgJa>?jkIL}Z z58i8`KxwA3x8pD!SR6-d2+No~n`0eIM zX3~vR4AbH8;XxT^ui26Qfn$gxNddAPZ)R}rA&JAH)G_+oZMV!$=SAXV|Hi|3kj{oy zENMPFNWSOopXb|~ALXsJdnTUi1?<)2IG4xQ%`It&JVOXEa`V$oYv0MpJTJ|CjS$5o zVV;ww37T%>cx3{=Jra<0!<^cnnHH!m+ncMWAqA0|l&VW)Svu2;(6k&$=~|FAVA?K0 zr-kj6`vVk?S0?n^6TyGn5eOg`ppQjM8K5V>OXN91Q5K>az8265Q-Hx*C?(Bey6r(3 zWn}xtKR^r~>oxxJESq?5@2{CKD7iYds*7dYtghBsTB^`#ciGwt$2qSA|VRl>g5vEY6T$# z=hyehlW?Yhh@n9kom>8aU5A17bD*>wp-e_SfA$^NgPfUS8>ZV z{Eoc9R8?|_bzQ?Ub<%uL8t6nCw&QT9SH{_C&~A07T2z4yx|O9hy3O60!MQhzoM$QB zu?)(z9J=W?onZE8@i>Nqw5DbRVS?w`D2fiuzfkXQyltjXzlu6>MU9K}=Xoy65L2}` zW@8b?Mvo8D6uUgreTW-_yRaM&r&b~K+l6k$`~jw3pmxjkejj4iak1SJt-UQdoDxhQ zPO)qkRnr&d+p3!64~Ibq+btDR1R0=AoR^wzNHf&2z#pe7C3Ez5rfEL20jz1Go|LnF zAE)CWn&8u*Ym(J*P?(l%45rEKGK^QLu(#Xb?70BlFj=ZOcqNZ&twOa{A3X^=QFH72Cx%i3y% zYPCX^ro3``3vxLvHEX)3R9o6)X9Q=Q2%rGG3At(NH&{*Vvm-K;}gYz(6&3i8d!@AznV3@WXgwX|6H^bIKc6ORP`@#lW+fDLZpsEUoRx4b7 z$svv%TjkP=5A}m{5X3zH(k5Bdq2{Ll>Vk9c8Xe#7`d(M3>SQb}RY}u$f>W5~lJk4) zNEO%fNMhOXw6z3F%lp(L({e^^g)GM-4g)kLCruJe)0`ThL6#)ka!rcpbX!voRF#KLFj1rUQ{0E z($ed(HIFFw(G?3-QE9|mxaODm*2ahU_U1=(7oL+Ll;iCS8!$hO$2^>uE}W}$|PY{je6L5T@)fs!^hBeOCZ=+vv~Y_ z$8XfCrXlilLUUr8X{iu0NjP$-GU22$tHdF{Lw{8gt3T_&+{5sBH4Wp#D4HrL*%>7= zd_U!=g@&(j{8$~= z^N6E}7f!sPO~6bWM!{_{_%+3s5 z!_3Q=s)Lo*`0SrQh89+N>CupT{^1N|qlT&4+`0Be?p*sK4?cV?XLfJvf3B*i6CqNF zd}LxuOw;37Xrk&M7l{-V(i9y{(Xlm;l3vBpN}TbZ<)3%{hUa;L%F?h;!hbW=rsn1p{WoRB@SKJ zSX(Jmt(C~Kl(XmeQ1fWQL7`^`8g|4k}_q`GOE z3<|lB8MbLTQtfbL+oYCu5=RIzQ07w=S$pi+LXE?*Y)*Pt;p!DsR1~4J`EtbCNsH6r zlcXZ0q}Mo`yntbu94ehCWG^)|O+(f6e!^fFvYi#jLE)_@i#WDZ!tu&uT}AH=wh+2=av2OY0{4e@GLB|3oTn#5U#T?Ec3 zRSA;efefFs=Nqil4RqC>JBn#JCEATGR8^x~TY+YSZji8ybQNf~6xin`KPynrW5qW5L<+D$=Tb&h%QRxr1pr`v&Jy zb(wawNf?jTBt3f>OJCxid!Oftr(VIb3~s#Pa^CQUqqI8b(IXGft@F^2UgF^&4K%G? z*XB*vU&iW61w{eRF-SXgzVvrL^=ocRah?9 zdHSaDur(LaF7dg~{fJL|=FL3V{RXE>*Rb)^obNyI zBp?6aEx5LhuA6-6YmZQ?dE9p6Wne0(hRYxS*ROH;rAN8r<}1;3lPpV6GKH<3E}#4R z@A2!u`fgOsAkPPXFNKLpJJdLFtd8f(T62=5ymDrjG)*~nbh+*l>=(IbmZ?>p;8F`Xo)mCQ) zXv37*Ua$5hZE9-lu1je`Yfc?{8pZ>)t{eM~ff}YYaWRZH2FKCkLIcEc%FAbVDVgyI z<7C8jcpr{wn#5?jIaArIH!>duT?})y0i>xquD#5E`>O}YvYhw4>w3a4;qLD~PT;59 z`j(4nM{*SqgfY6VamQ`fA%tLOx6K#7{5@1v<)$01B1~dLo^yVE4*|5(J%q?8S<9R| zzcZ3ms3rLEPoAUG?(*;d&Cg?KDtVUE=>{~KGV>EfhU^Csj$?82jaNzAt73)Yx`XCh zw;NKaxZF^T5N~cZ`R{-GZGQEa-^tZi7Pd_Yp8Dx4)0egaP!t|}^cBAO&p+f{KlcW_ zlEoK3cRz>LYA8Y(Xo2ML#FH;0#G9#_D>T+q{_?Zm;bR}ZmDSZcVIhRxXmzBafdZD} z^0$BYJ)$__)|;;AoAoNHitUzpjeKxil)SL`V*w|{~xvMCOY#zS&a)?>ZUlZHR-W0!&Mlniki!*sVYmXfyKf{wxz0AM=tq-7xv`>4JwN8~se)Jsgeb)^< z@bEKI&sjJmaWpqMfL?Q2uGCE1mB)W5aP}A*z3U|O+nAPvTdr|#qk~s+SgMcKoreXI z0FpUP!hbE$O$)=Y`qHHPB{dVxW>uwJU7^$3o#1uvc65#$8Dz&@_9_GO{#5vE7MIv{$LmoUGE66u;|Jsg^0Z21yoQ&{$=j%Eq8+Inv#FOhb9N z8{fmU#^5j%RmHY-TJ3;p#i3Sp*xGIZ8HQ;W3Uhn=mMf;A+u9o$X}8@HimHv=#G;@> zt$dX2#*1=$6qO(l*rv%+rH05-6h-CAOOJ5TZ+-yRwQ22jhy$NqX+cpGG{Z!o%41e7 z^&g*x8qzJgE98E;=l=Kd^Eb)o?z-c8{_Y=sz_r(0#Of)%Pqhoph_>3IYOD?F&xS4i z141Eap?E6V@)@B@s%yYDCWA?UCd{{crTqG!?UH|qG4JH zk(0zy$!z!)rQ&2*W93NK%Gqmmab25|XR%Z-(e*>(G?>t9UlhZ^xrarA?eM<6QN3%S_w`$& zD@z{rn!K=gb{e$i3}pD7CZ*a+|3tHFcW!pk6ArIb!Etoj&BcU#W+9G(e)%NNrKq-B znqFg`))?$TRW+$!n{Lx+DpV^{da+t@K(|pfv9MCwEOeT?cooT|PNIN#qN$kU8LKFc zfugABy2;CXEfiHj*9_KoyWIPOCy=p4;l1yABYh1@;LO=={`k+o0YJAKpy?Vv|K7I( zy~fMzZS#~8H>hvtN0;S*Tqa(6(IMV;%eDO7SH8zD{n}f|$)qn{be?D1Kjg^rMF<4X zzi^&E_&+|^|E$|?ejRVQ{v=r{>#9NsUV3?*Kl4vK)dj^+Zc8s4q`aHMad^K4*(38=0 z9o@8W%nB$fSrYfPKC&$B57Ky*IwH>r{Z3!Tbi7m*$jxa#uNk(+9}6LRL<9#>vA zu*}M`3_;FAV*17Xv!uycP6@-b3favV{{n>id(aJ&N`0;0Odel}r-hcr(Zf}|l1G|m ztZ%mP{eac-^yJAfZPr|e?d>KdZw-L8l`1cvj#-{z;=CV*gY$16ZeCDu_9}IPPKz7a zKS=irKfU0*wY4XG`}Pr5i3`a;Rg>ya^HyAjCg}JDr_?%F9eU=5tC}2gL7}#K6jh(} zn48rY1bNr@s#4-pSEaVAAIJc)R4=jDIJmFcG?qb#A-)8eVtxN&FzT5b=Ibv*2*FJ^ zT*(8EJX1`$4YKttO^Jdoo#rl`#x|O!Pc*W!G@;wtBkICXq^ zBsh1vQd7OBDAz-p<>boZroacmqSr7Wm-EMwDvY>?`=)2 z#G_QD6`7nozJyouNaBdoXSY$Z?#w{zmTPFbPU7#Ok`$|AIWSkNdW6Zr1@`~L-Sv@w zUubZSLVv+)U?@NXoIblt;QLbtGR6^yzMP&bL|?SR=WP~5o{?u6re)0x(2AlK`nndT z?P9xS+;WXlb(uvZjvR*$OPED#-OI@c;)&?c3i7i>@{Qt zV46CHY0lNNn2TaKMK9@Wb)Mn$#*c`T+1W*$bPJ=+E=d#=rn?zwl2Y|_Zom0zuD#|Y zxscA?!_ak&Yp*)WZEw92$2NKN@fSxr;+m$CrWr|^p(v6)k!E?}DX8$jeOI1zwmQfR zG)3@>AHALX@Bb-{-LYE#P!KtBw8qg@m!qpLWmhdS=h1CDbcMq8w;Umk6JB_F2Sc@{ zQo$4yG)+g-^u8;)s;XF)NzhH$*l2LcRg#_JcS9^&Cm(7q3L*HVU%8FM-Qhj&e*^d2 z^90GRP0d_G9oip9k1lb;9fvq|b&2E0R`}{SA4JhKD)m)tx5U%WoFhq6KL4fr_@h7h zD);^137&iY9P68{nOxjn<~*y;Y8Vzt6cUXEaDn7IuPu8c4c0WxIDK}PvYquCU_E4+ zAX6?p7`_^)nog;@Ec;Wtn^R>J4vLcY16YZcK5pdm5b+D#OcAW?cwZsmPEol^reS~_S=3p#gU_*rRl;%F-I8>N0M*hV7P$FQVY6LU+eRfr!_JS(~?cYBI|L>H91^Eg6{_;i9Au3 z>K;LKu)D0Hs5qr6s;jWkdW!X(r->F2JrYA1p%8+#l?rK^@uSCHLe)&-IOY2fJk3(A zgzFeg8}txa!h7F+1K)q(DLUN&%cfki@m!k+A9)Vlaxg5Hhkx_}wr#Rh^U$vx$iw!K zrU|ExFLBe2SMd0guZ;c1!3%R#bkjyRZ4A>coYlwJ1>|(Z4)6N8H*oKLPhq7sl(CL} zoMiHb>{YP63bksfFl|-2>WUNGch66``IgH;6TI?thb+rkUUP|unwYj_QeU%ZCfh8Z zRJr!ri@5t6PqSU_VI3%tOhZm5-01elg&b}vP9DC;`dIl_z$fSog!w&FWoxIy(Ze;$C5Q9t8nFLrLRB^C zNSrq~-*~*w$XFCYhs^>@uyw_APf_J;lsBA8JSSI(@g;datP_Z z001BWNklK7{oIX!;Fh;u&7b_&uMz|?KYT=I zd#A+*KXe0>I&}Reo-Tviu$k&kbe^}r>k9tw|MQRm7ElwO-;w?8^ z&bR*Q2|oR6Z{=)bo0m^-@X-(6%%Rnu6l}~}Z@7}LeEmV*bJz6~$IdYAnPcYTjE!M* zLJiZjIJ7oMYT_v3m9x84oeay!iBn~&)M)-MkU`H266KyQ_G?Jvb4pbyWjp0M?yW3p zh1>#+_Qgt-m61lPVL8~2N4LE0TgtcXlDC}aG4y|rRoMc>d>M-l;yJ$qXu1zjfHnv;jx!~|x4NcAXFW)g~pGf(4 zYaxef9_KfktSy&GP^MeNX8mWNw^P}k>eE~y!QuE($zW=?eRg;D7AoiVvgdhC!5h`P_`sh$#T#$CizG?$gOE5)IrHQr zeC6LmI%axIF?4Fx(6m<6W02`iUvb}Qu|P zbvGgOQ&d%Dr6QMgS=1&GIos_T7En?nf=)`^Q;5TMKMOe*JddfK1xq36%H!IK_b8bq zJah8+MSiQ$zUZ=U{ul*?*bhlX!WsWLO#L*9u5d|wm@G}m{T6j^@^e~2A?FVOo_01NBp|D)5psK3uBXko)Jo^4L&lavh2U+J;mp8IBk=pP@vsO`* zzDJ{?DCBug5{KktK91v16s0gaaL5W5oN>gdLOV1#akPr#I;2U$+4Fm7#3Oq1QP8Eb zw1$;?_^rl5*PpHm8XY-oq#&nm&u=K~w|9mo244$WqpImsR}C|_+YclysK;HcmQCU$ z!!hN~?v*p9xf$<=ars1D%}L@I!!*hAgLhGT$g-4jZ57jUNRt@dFlP#^cUyb1VJJq& zVrRiMbGG(6EH9VPG!56bNU{_|6NTJqnO3;Y=Jro7$Xb3H#P}ovJs-Ex6HhPIMxP&B z#Rwq?qa58RG=cl?7gJAS>zbT*6dA;{=QEK`WL|L|kZ1P9Yx~V=<$vO9-Io~G;rx*q&c}z0wVksaUbF~!YGPo-mC$%g1cKdUTLm>J$ zdrg;OV0o4j`fV)Roq66(TgLXNVyBK(Fs;Ep+}Ujt20m3c!*37z2Y#%gnWG^@WN=cw z6i2;y;yW*tVz*zA2|7*Oa=m{Ig?XMs5+ctDx-I;6 zgP_}@+ipnRj~OtBlGZFDz-GoJqV_(jnS>)%k;EP^0-d6cA zKWP8szOT#Dlx}O6IP@vk*Q8;=l;3Jias27IdmLHwaJ>QbuhD4HXa-YhtwJbMnuIws zrlO|?jr~d+i@+_{5F#h&H1Uh!u-^F}$Fl4ebX#;=d!%Vhb7!4ybC+&wm)7nko#rm8 zqS0yW5Jv&s_8vi}iDAltvmiB5b%&EDmN86|PPxK0nwFg>Bz4~8cCwr~KYibrPw zBEV}EoIy@l?&sM#@_Iwd>2@Q$;-qmMn>3S@l!I8B_Y6emSpnIWP84N$o>aE;J0bc7 zN&rToG+zyhdU!8LPs?Zw!y*_8sB;4hP_iTmzEW|pEQ4G~H|CxAxw-GVPzc0Khm2v& zYmfqDxrXb?WpfxN=t{~gWvbrN?dSmmbV;vKuCMf`{-ixoZ{G@Z(?->F?&RZxn^@st z)O)RNSfpCi?`jV|LV6&np|m$s6wp;;Un$C016QwbCVzfv7CsAEmeShYK-F|H9Id-H>)R}BF3NdK34!%1_HGX!=Y&~VZX(CM1 zME0lMuyn&J$~}XiDuf{P+idRmRIBAalVxwO$=+U<`jEWDYxY}oK{zCgR`zVxbDeoa zfMLeQyuduodXgmJ_kQp9_~IA8NVogiP}X{IJcpa#_Xa-rTX#+f z{a*+y$D3KkQ59`uC25#;Ul)BCZn-)U8}eMC8ECAoNDDoLU}I~Kzz?WS@%wx&ps9kr z&LBW43Rsp-CL**c7vXT`Jnua4Doe!C{3%M?o!uCnSDMldO?vXBNrG<32vjMV1peYS zB zrP<)zMw3fUt>SqWBCnuuZsz-54K&r5XeP}<=y$lM^QDo;-oVX(%%FR&#eR@c+Q*Xq zW93&rXfTdmBWczi7D9j!eGTJjuM?us01@&=++*A*io(_A4H#7mT{mTIIEnavxPN(K z8g8}U$1~B7F6h0($g@ncQVhwl$Az%lCeJh4p@weg{ooAnd;jS_@x&8PaQEGJv$8U~ zG5vWY6i{{WxG(AwnN@ZNsBFkzqfjU-Jgc}tF z6fHK?lsrkNxoFhi_>Nqy5X>e^hx=~XnK`Y(pos8p+q(Z52wOGzSOVcogw7ewVXmcyfOR@W9z&K z91)!!OXeVpw3_O!b)gbj#WXX`ABH6#af*UR^gOq7Zuk2sLNXA|+w=B6dQT~_kW_hB zE=1%RrQq3D`N?|;4158ST)iGxKl>!W*C;-PiMkM5(#$CQUKVLRDZN)X{pu1j|YmJ~K5YBdF;$jtApje}gJd5@U#OWblFrKLU ztzWCGhTdDtZo|)HsD%M%skVKELqqUogP!Rp+p(QS-owPc%`lx(>pdIWQBuaiVAd0f z4a_tvvXVn~zb&B*|Kf*?C<>;cLXu3IfqK=d_Dzc_UtM=1YSWSOMP4!1E39~I>34o@ zl)en;;`3eB`0np)LJh=d<_gXTEXdP3KGIg7~49{DA%|;YsHg#lX{!Ffc7t zS{A*+O{QrjlPCjz$yqN-m3$+-&pVp_X=d%e%-g@>bzKW~!Tf)(*=aL#XcUi~9i4Yzq)26E@ z+!1MxG0=z$hi@z<+|vXXC(5$}5QE`cmwC9*A@z%N;DcdmzDY3hwY_7$*Mjiv9()la z>#o>kOMp+5@y_LcyynxHqXQCVp?y__UT4=WuJjAClWr%W;h!0l>-PL)Wo3#?AT))) zp`XZs9~G8+ulA2mv`gp z%#dg68V^m-eJ|bS>eJ1;a(n;hm6xULSHk^?Xy`PV*8wG&=gyb68>N5s{}#{xy`96X z8ff$cF{@}2&kUz?t_p$3gkf&C*9G-wiHfVInXexi-coF)1Wkh# zoW4+ma%lHWqKOgTrOlEpLh+TUfp?T1sJnf(lPSJ{sOx|EGl?rz={Q219DaJjo0GPB zV(of2-h)QBPp^%D=~&ZZv7Nx*{Am00@O1X#l_dNZ*>Q0bWK5f9QCL*4CdxBPIUTSR?rID!(yj{kUH1!8Gj48&@;cKIGzN=~U z#N`o?s@itUm2~r*A33k(xz2@lQSaRdb#ynI`e(XXYXkvZ=x+PN6;B}{tWNCX+Xd!7 zhrFoE1^?HDRmVY6RR#p;pXq$*mgCAmaL3(f0c~#7aKl+F@9g>CkX?6h84LCY-Jl;K zRp1KfbGN6rcPtzc0P&qNh0Kq(JSYmgn3(eN zR7in=g@}#KkfhB)pjcb(AC)hwx-4HsvA%!VVWIdzf%b`)z<{l9%*gBq`x>mWRp)6x zQ}~6mj-#BTytb@OG&41VC2_AK`Fzd&-+h*MOwn;Dly8Pl=%ROcCTQv$93{_5O98yX zfr-B;V%cG~0;?K4OXTxPaq9*0koG+BOda_$_ezxEVDn|!SJ~R%f7rNWEjvp_(o%C| zzgC4xPnKZ_4CB!|l5`gDip8b{l@W3(1k!n0$FBeV(f*A)>Q$(JH zac)UGqc@bMz%j^@6?#Cz&DU%4LmjpCbq!l*j%(t#+JWSV$0rJ4?S-nq( zyZp`Y>zej3CNQ4yuHvuZqwk+;NnWA&1;x2=RQogMb(PD95TDo(mJ@4+!wI(vCEs%eKi&bIHh2eETyfE*(B zxSGy1GJM1iVEdxyDgB3YQmEJWer<4H_@1B4`-J`NsOs(Lf_6qP3^25@v0W zbrY*T$2KtQN`9)d8ue+R*wz_QCu=aCEaH*e9gYmZF^I?Hx=dcHv2A?y_hH z$Nt0ad!`u4fCoAzncAW1Aj=CM>N!vRCcrRXl0aEeG0h?wqSOAw@p?Dkxd7a9kd^+5@`TI-w(s9HJNkY1 zJ0sKWM{ap@mdwiWEdway3$B1{)i-DQvw7%HU64o2ZZrU>nnruk){7a(=Y=pz_BZ?;oAt3l;)wE1; z^=xc@?N{L7RUyos)zPpv$bChBSrd4%XdD}DuSfng7253c$f5ssmF#)$y)jxWd|P_C z4FGQaL?%nQ=V(I4hFV4|!{f7khf>n?ET#SIPaK3% zjS|#LR3`EY;kO~L3>E0fpdy-Ja?r{^6kNDyCpo9AnhC(`K&@&V%W37RJn0NM)#ad!=Chnl17=92*JV*Mz|8{KRG(?_r^fVUfS^MZR8(BWYsk&0Qu%0)>A>SsJva=%@WPLvGd)-bEg{96AS>u;B zPLusOWp{4#tCp5PLV^0{2t zZ7DxL7FvH1ku$R33_uDd8J8iwhMVeUT$V~VisDwNNP-de9ErYLBJOLUt05Uqog8N2xp<1c8vDwoC3T*+P zyf?#J{+yVznFC)QzbHscB?0`pBOKe2?hEYkwp0=x+5x~GHqrz>l7B*vO(0`<4o5r? zGw@-kN*PUqZYV+^Ij?0qlpsV|gK1=`TbQ`j3Sk>n>qe$*2O?0U5JOUIewf^s8>_8N z6)ui8`lVY~ZfGXRMt)@#bF@^x!=LS-`rDMIAS4^5ph|zOJ0&-L6YfB>0(T1hLe@~! z)zJ~X8@3*4Mlfh#kGA37J!l!+tMWnvO(scGqx@Z8GffkdS94i!w``H-cwivSc0g8A zqYEvpULhVqkDOExaY*poP=u1O#* zSbKd(gxK&KzsSbUm5;q(V6kyHwLyT_&W%1GKue7rtSCh{nvk<03gRx4E8npc&~O-@ zMQL<iR?u&^)i7q)E-Am=npuG>g+Ju1=0}bfvP$4}(?mrpb z6w2JbI%y1}SR&XzZ~UA0E;iQm$Ixu*&{PJWsfP&~Ih&|41ByQFuBs%emhE`{EMq`b zle=P)Y$B0|ZOxQw*@hQEgA{hv}vBx9=P}Uyx-Cxb}0sa0+MX0 z5{nJdU&Z#vt0y_FA|u4l_FbMl4L~qrL`MJ?Wmy74sFeV$p zs$LCXrN-l>*M2WQ+wb4(x&7C~Ec9@*7YYUE)N5-vlT?-@Sf^#Zmt6&|;yV;K!^*g* zdO?(K6sy;X(4}!0;F(PmYPT#CHoUbx1IBFu5J4edfnvN|J#0Nw_b_f47ukKs-IhAh z5AVxed%pn8j`M49mtb|A3cE8;6S6Af-E4DNZn7{o$K3!*FB(6QlATVrz$2Z$A5l zXK{y%%zt`8X$@gGgVkjm_=!I~GYoNe$DT}~GzUe|zdv4j^g2zuh&KZ<$&crtdsf0Y zo{G6RJCMez;xEM<5e!PY4Fk$9@A2W)m>$y_9EA-li=CEzTkg8drDsCGq8zc|#;E#V%Pf5HD&pW=zufR__0qr($LPQyc_XqLFa=>!38aZ;ARsw)9B-ikO zNVhBYxb+#qg#`Vp{XK0&DEBFTcXHR`rzqseRFp(yEQ2}2;mzfzHz{p`LJL$Y{-8h> z;KBBM8kmbvoEdVbVz<6(WNaKNG+Cm~m?6?6-$YI>gNYEoG!)^+^n5@3mxoo^x;6Y% z{h)zo(8PUkXleb+JI~TX6|<&B2{n^wAqD(-!K{XgJV?kxKNx+s{nye`u!k|-1{#n)}zH!Xo;dt+)237xv}ihZIlP@4%Xw2{Kivj zsVF-@l8Hi3`mzv10Z!rxKc>3Y_U9~9$kp<$Ez;KJyY~O*0xTODFJ9YOn0`v*_@+kJ zNk34SAT$|Nb6RcZr|dwsDbvfyDV%TR^|Rs1R>)zGB*{vWZo1-p%I@Bhj}Xpd^KeCj z@vD4R3%O|)lDqrL0Al-7t<$cR=rEN!iYLh6($a?spPD$hXXM3T_vG133U*8Lc4SiB zosr!V16BzJl^||Cv&$_itq6s-> z`x3w*>txP}-*apVfpz9k%LajZ!FQFZlQ?%xYs>NSANCB@!+TvAEI5DHyEGKwOCkFG zI9>eBMP%dJCNpwb{~nL@I%J6#x3|9LWW>Y6BHn5IV~C}au0*7Tgq(~;NDM$@P|oY} zyc)?R&n+yhNXVv>Zqp*4Z4fv^CnV`}OJMJw+)x+EW5T!f ziMY0r`8D{Z>mcF@fcGMQm&eIsvNlu2gu5?~wzNcgTs=R3Qv`9#7mHybhZ6OY;U0P9 zO^L#AYQ@s5X?#D&q)Yl6UvEEGwg3bF;{$v@M^m-pw%=GhDo^HNpH0y7#)g2{;Q~zD z@ghjTY@&=2XrqnK_B1Y+hU}?^CW0ihqQ44oul*_IGN4oR{d`Sz^Sq5I16A9~ zQOXKZwf*=$d(>}a7#o*qbgPFy@bnZzR|E%L0wM1f!3;7v>~Zf5ObdX6D(dM$ z;`1_T5{qYV({7S1@xVhjZ`E>KXfju$8#I14I=ImgtIX#m$_Fmw;A+~)eZmzj`5SXu^kJ3!H4*^HAXu*#993uK5kfrGK?D}nV z2C;aVKxJ>nmoX=2-X{rGd<3>~71aJh`f4hB z_;GZTe>#Urbd5L%(=uiK6B-p<9NOa18Bk^g0FFILVU~uKE`5k7gU|Q@-IZt#Bu`sX zDH6`dx*?YNM>KC4QrV~TL7SrH-h9T6Lc7g@6u>yMCC$JUwmyl?g4UuuD{)gr)3M%r zE4iCCIA}#fz{X1UlqC(1-L3_fVp=M}E{ub%T>nYxmuu|=OQf9W=M@2?Hmo=AgA*Gy z;5=X<6VFB#N6=1>Eq{1X*hZtCK{@+EWs^ly+feP;h-@JCDED$FM#P0M-1|k;JY8rK zk0xdk)dc>B=b;2>w*=qW-q&)adis!1@9#k!zS_;JPt7gYa0!?IzhKL8s@6!ERa2xT z#b}tjp4yQ#NmV!o+|A!2+*^`ytpVg zTJ3`)3B0gHPB|ku``1V@s@|w?zft5N#(;nauK$;#K!bI=S<{utVoA4sZOILM`PiY{ z&BZ0;et&J}?z08Rt#27;3nDvz-1MV>)H8H2f4pk&uJ*l}dbrI74kbM@649=H+sqH?6$7W4UvoP0ga# z0_VNvymGrj0vl7Ptg$3lBC;;hT4s&vY0g5Pigp@3tK;Vwq73q+Yza~qcX*na8mzd4 zsdmhxmll3lx@YR|&5dfyU~Mlwbr7uCnn;o+4&Ot+w=ZLL=g4IhYAQ-jjfJ3#sL_`S z627kg_?cbZs?zUBde&-C+ptEB(oL*KE*XzG*ntldRK{`T69PpQ@^klQr1lSNe*ai> za?368OF-*Xcy!binru^9#Y$3vFHn)ez(x?;f zo%7DfdKW$6l^@Czp;E1~B`*c$R;=<&DFVjt!$+O4p0E(c%7%CX5SO`fJ{?M}goSxj zrRS!Y(f0ic=V6?&?H%E-B_;)B9Nb=~edt0Af-du?d>q(p4KwLRQ;lvC0A&wz6z4<7 z9Ui>4a?N&pyXl7@H86xFD$k*BGV{$Ux<+MG`1S0mXM3%Qrdwzpw2mw_2rSsU4MqC= zR^motQ}GU8rTIMtNv>GTxtPj=%SV4YD2CeJe70YLh88R==&g&1&S=dfK{b%Qh2 zv&)jeJN$5nGOj2az1NN2iM^5uh}CKeThhvYegOTqSpLJ@^24c~On==)hCn4YM;L?5 z)t0ao?ml8E&5h}3UQVY^gr7Mwtn@qNGm@{CcAL(z)iz>amO(oSEnn>W<&XKx*Hzx^ z=(bNEBQ~QC_ll<&ruOcLR28HXl1k~jLD--d*4z>XtT>5W0$%bboEQV*oS`Ypdx)-W z^{PvY4|h?nqJ4JUZ|)G9R@*C^`*XjlZ;jtz3dFtjgTw!Y{k78+pQcuz#t20C>I9Rx zfHgf4na>k}>su9hDQI(xJB05aui01`vzV^`Gx6-!<9R+snJ`-~NYlwFOv)%x<=afL z5Rb26``F@F7g|{8q5iWBrLfEH_`*q#XH!2*Y~1T&N)u#Q0K8v)PON*m10##!#T^* zy%wjnLaWw{17~YT9EA)-uS~f@od6AMMo1#TX@~lw*Jv#VZUF{k><$D){J9bs5&&NW z>ZE46{V7eP8I^N=O2!8G*8FFi?)qY9y%EYd%;9G(!q`{NjIQu;%lL!2qkeRY+Z?k*7`g_4*}J5FgOxStu2{+84o}0l&v`WD}aq12po%!##mV0UNTqE`mK;> zl9r!kLccQO>ZiptgaP?1Tk6c>9o5i46w=bB55k!~550M!#C6spl%pJ`o?M4(1|Iq3+`!ntj9twuT*F$V9vF_$D$8(zPj?S^C)F$VX0M8QAb z)qh=nyinxrA%Ebj6z?#bB5V%DsA3{?-=2e-AO9NDe2XqZ+_tD09)w(2jk+|tKeptb zJjO4dYICrt(CF3&oDzNDZF z$}S%Wh&i~YUhW`}9AT?ZNc(2Y;XIYeFgU*AR;)rT2i79iV7GObZ4(2{89LYSf))Q# zptTAj$DEVnQrE?T@~i1!;tkQMb`zqg`Y#w16QSnk879*u}7BBm>Yx8XaMvQPk(%-Jxajc(o=x+6SZK_hg$ zXGzq4xS9BKbnDK4diy4yd6=a65Xd>5ksLWs8;X+)r7bn#TYsAbymVF24wjniVZHY( zv6^Cq`qDCC4q7Xiw+4U`LiFc(GSFbEP(?p?V~NO0%tRXcVF)!`uf)O1wG}vLg)U>7 zUHNttuXoNC)c_Cm1wnUzt-cw4f-r=K`lSHVHlGoWI0LTqB>enoB9XrHGQ0HB9JmjZ z7tj%eS&mEa#SKNso`-=$5(!+idp~VxXVcC8O5hr2MK6XqekbVysedcq79wol2da|slsJ9H z^uj}H$iY9Ge@srpc-8aQfBzY+bx|?t&$&?>taYmH?|j;J*L~ZH>Jdy-Aj}jXX>4km ztg;Z(xVSjBSnVgnvgXHZu=tHb5|l@`RV*eO7qj?B3sDJQf7|Xc86E^IDZD7;ikHBa zv&=_Hm&4gEE2*xFe|983CsEay-RPy$xB1^nIcR68r^cE!=;x5KwoW|ejm#QqRi``& z8s2=qVxGaCPQTEQQNBb6HwLnF-q}t4s7=~rt#8MU*8a%DJ^bjplgEbD9v~ihEOFH` zrs=Hzk`!e-7zZ@aI)?44o5$Q7Spf<906>m-N%GiX{hg&TDMMkd&$3-l@&7hsb)FrIgO1zLTDk#IA_=g=XU5+Z^FiKdpLgG-AAb=XK$RG&u>M1W zWJ#6Iy1V62HE1jb%^B*i5tKzj-y%9~t$sj*U=f(dSQ#hZ;BJ({#6bW=cHi zoShoj?Z{YonQ|Khjp-B2KMkFY$+yy7IY!H=xo&co9KsjO1;O>p!sWC#)aKLRbN!tI z&Js6Bn$hx^4&expKnvJJu2QvJGIEmeo=M$1t1oZKOjwmSz2M|9ZA#(urS8^hDovH% zvdQp@DT$_dM>tpbr!U+~Nv)xP;g^M?&tI3l^+>qBaPRSxE1N(8heKe^2pyvm`ct=9 zsr-R()7W(0mF-DyKp4(V+d+}5!J+htb9L1{JJELn?hlg{YSTAs#5WDm3IeMIRk};h z2~DI%Iexra5$xwH*`mG5P@YK;H@Y3=P&5S)OR-Q9OPaIpNNAF7#HSKA?#Oml~6|Va%@jV1rfD%%8g>_)wfRusuD> zLHhT3vl-78GT(^?N&uKZmZU4N{S*5)0G~{ikiI>=+95Ghj<&^Suln`Ym(FEe?i3my zn*@8D>?GSQ7l8P3-#7hZPhe7Vp9(?e211L;IXkGI^`xPuBSM=q$J+1-4Gy;`*VgV# zN6tFFHZVEOgclk@Y5IPO2$R+RzG!|D<$`P^=OPZHL=-5(y#eK95&{5||HRZ|l1>-B zx)lW}fJQbea8KFB&4U>$y%5{+%UZ z=rQvu-dLPa3z+aG~WS~x0s-)bl) zzDZaUOf^o|;R73gE=9y{MS)9I7g=8K;4f%mA7!8&YS#i>0SL$8&YLcgNdx@S`B2zx zk{dA-j&ca`vOZYqIqe?NwB{xxwMBn}fT~v+Y{^x7)5~6E5`s?WES_@?SVkl$c;rLT z0`=(78z=!x3)G2lo`zUMi)>+M)al#+dO#)=v-fueok1xi_muM%9`$A8p10{_bN?!> zpZPs64&L7h*eT0KP^IaY^-2kv)+JINpJ^fxeFwD$rSjZr`IXhUl}*U%Qb+sfwbV-{ z6wDs8zp`~R!{DCVcbP@Hw7IyYG!L1p5`4u*S zBmp2nT=C)R*CGp)G_XSV?Hl(~MS|`1qp|I^BYUQ(v$WOJe=RtPv1zkqK05+8AK{NK zU{t&~vG@r4m86Hmx zbHeA@B@pdMI@@PDArPUI6N?yiuk(R>)IS5*Y{;@SJWg-%LbAXWsQBv;S25V#MQFeg zHL;5U9TMy1VD_s(*INxOUz55hSdw$MF8dj&>*B4+@$RP90a;xZN3s`Fo#tN&MEYXJ1?t0BR4-!|rDC+!*SqzaeXK77e?Wv=gq(mRzCL=pA)H_?8( z0yC3F4jTa6m7eVA0W1B(8N{nfD&p7c-*bPPcrI;5sm-1`L~O3??t0qz7cgGIQk2Vn zA-?|HN9?(ywm6<41OxD*~isWblCo?ni2ZL>Y!2xtHCh5YqH zrs5Avi!JtZPtAy>-KP#bV2~l(r>^A-Kg=4LG)3OlWxpoJ(K&|d8HwV8&>m5x3wuWYT)`#yf7w8e5B{VY9Sg}ce?&j0i za-WR^;T2BJypev*)C#SdX1BHCy)e@=CBG|y=+;5lWc!#Pd5e4djT$$pno zQ@_hs`@wpWh*}fly3soL1#hXNmC5@tb&j4XAlum3=JPK#86LoNR!oN|d9J8|hS``;b6pN`|R z;eaq6Ub6i|^*zqDJx(^;a)LBi?Lp-z*E4)RU(^JV{|wI|b-fOUf=t4&!$lr6{KxP8 zFF4NqUdYh6#W(?P8&z*V=wu&}{~Zp3a8gIBHg;k~p1IFDj{(-S#6jIZu#&jOA1ajE zL+6qhBq3M%`1+f2`aaNq59sHTVtc>yFJ5@F#h|8s`y!sS<$EYqdh1)U!q2W}oz1f2 zb21ps1~J%HCX(>wYYAv*?ijw8td?j{&s~cix_a*_Q+E=KlJMK<-!}ySFb{^_?3FLx zOK7VE#0mx9{N_u#G!AZKogMgELWjAi8N0~tCtI-k^c|iVh4tkZ0)u?(>T2nKq_GI~ zWkY?#Vgm{P86)*O7Jj!+>J&P4>;5@vjJ4zQYovjkUgAX4lgFJF#hRc!3$}4D7 zRz7Q0;=q^xZJB+~y|7O!W9^nwVnTP-YdVPFmq*+7?>zM4Xp{h2XTO3Ou&c^u+YOo6 z`VTB;+0@_fYP8fFD>=a%hARu)9@Fw|-KwRRR9%p9P4d)1&6loN2fx z>zoAEe#Qx?<0w|m0cA7!5@VCT6+60|B&<(s9ZF05b~z|taLB7;W8$_f6UzR`0vw8H zwKq58e&A^m*#7M~`vG&V_H0!k-xd(zJkvN1S zP2BTuC#TQ(Gwaoa^f}xvT<>X#o6PU{o6vot-1EAI8ZM67=F&dv<-^MP*7Js67MM19 zas3RAuAtXRnG)pi@(Auo^6#l^xV|AeWkoj;=B!+^qbD)3dcFl`Qv$I@<;XmRzJpEI zZ>A*Qb|$+?`E%K=moY}!f1eSVg%&hD;%>F4B_-7;7~pa5fH zMA0x??dHax`&x*i^-B18Yh+WCPQP9dH~jBh8M2}eMVA=kM-$j0;>QFk%jyzuO1>f~ z3BCOnfyg>ISwq$?rC0Rp*Ym?nq}4P0ur1o1S!&^T)m!wUJektL9&L13jXR?dQ&EKj zy~QOe34of`lbV*f!p*ZY<0*S%Z|=&kd z@GI37BDO)>Tz)~{Jp##~nd$JZoW5uL95(uqTBP*47iRWzo&EoADCbC4`kys?#jBag z%F9($jRO}SBG*_e(>If;=k-^qw=3dFr?(Rh5x+NX;hRYN{ZV~ir0}&G2m~qv{~e!y zA8Ovyb#u8Y`X0SnBr=!+NASC@5Na?5zp-SA4BPu3Ay`C6@S8}z3=ER(w~2V9nrHh* z&+FgD0mAhk|56Ki+}{kkUzu_~ZY%08``= zd3z@ULsxH~YUvao;T7EcrPbc2*VFHmcU_Tn1E-1?Yc3fezqEb*@4oKlnNk$z`oZ|# z>5@J5w@_zu?CG2Yxc_`}lFj-9rDR*fx4$=Oz~I9-55Hs(N~QJEPW z>1=(k`VJz$D&Lc+3q?vfWBCBgtSWj^8<61m->@^TE;HM# z6QyIbb~h>JROt-uy{oLm<9BtqK|Rf6q2u`HkYAjZZnWy_;=?msN&3$hg3ZqX1Pnvh z3I0#W`VvJ2b9bST%8~yalg5}Lf69}2;rc2`Xp4(!x^poDm^Q`osQvg7`Ejo)i&la2 ztwY}z`E=q1^L(oXmu|DF>-s(1obT;q&K$4ymJh)Wlf1<0y2P62`LFbg<&=gX6 zOqBid;N9%t7VQ6wKY6jd>pGDMp$va7dUf8Y>>5Z*))MJ1;>P+FOXTI!+UJr{3GTQ< zo{?9c`K_+!+~>&9#ytrT^LUc&6WR5$7yEdt?~Ax}`QyE0{BZ4iZPvwQLW2|}OK83| zgCSM^`;J<85bDePhA&A|?nRQwE4^caA+J*yM~%_Ecn*K2M=ch9cpZ-l3DEiA! zbMA5D*Li;v`O@>e!70O+N{gK zI~*|=`Q$t8{t`>_vX#ETwWJ^UYRXY)jQXt==gB5mS=2Gde`4=H5J}DjiJm(+-Ts@T z8|^0mv>K9HelN1xw>iC8S~~nJO<7h1u2AReXzc61X5>m!lijuWmL!?$2j{SaTK!sQ zkS)#0n9}%GvvoOA_)(mhy?%2sA242c5OvhFJDVJ2)l4w&zy(f-!%3BGi1}USb8D@1 zUBs)iBl1u|OKA-*_@>vEdzC8kg4K1mDSba@&;7ygdiz{d4N#CP*n~J#E8s%UBiYFC z(=JWu?Es;!r>6F0CX7@2GtV+i)X@5;ZHaOwNp(LwlHyh`xrW0i31hDDk_#F+ zEq|qHi82kxm9meUadEE#i?ZtK$p5n^hNO|mHgPiTJ2dnYmMjs1*m4%GfvCZ0#oGcj zP}8kemP)~YEs~$E*gx^PxA(oHip0oA?8TM)tN?}xLbjj0kgE_!Yv8XAPVi?*R=FCm zDLv@d)YbD&Fp^9L+peL*%=8k#`t?Wc9UHtku}~3fy~ah^W(lD9`zXiE_VTOvy+D!7@%0D5oX*4utmgKy@`V1zRMD zLUAnn#P2KPq=d`t;PFM0pdCkHMoL)>|LYfP@SssCWOpkSj^t98)8J2L612@0SdMvT zdxVW@@Oa$L2ox(V&N3pwD|p-EJec*O_}`wlMcN24nZV$4mWP9;JtL?Ad(jL|0rfd0 z_DA@rU8@f_wDnjJ-1w8j9H5ofx9UI1@W1;1Fwm5>9Xi=L)_-08a<=ho3J(vfMS}x4 zg0`vN=X&A^{YQnFHdhn(dOI6$ht50NWSBf;drK4gb$5T)d{n&!H=gepA12%3W}(Fo zeO1CCrGpvNIV21dud_`LJ$r+m(y!?$TGq|=$pcXETIQ`|?>z;;k*`tE3SHGia(7J2 zxcU8;#nq$f;}5E*Xb`MG=HqnX7~7b^M!3QVgljrdvokX9`UHxFKF&-lo(YC2FBRbr zZU1+=%%lE%XF3%tqco$TYWRp7Y!M+7ha=fvIUC&eYFiCWqYZIuW4D6KbIxZKo)^az zz>I9%@XR0J5{lTCe34d-!|%sjm$(!hPq*K#4LADVR_M=NkaQI$oVC2E%@>N4DiwJR zin;%=sZvf<4$(yfQH>5oFcom%dY%}D0{mEDJeJRGCTr$&3Cy!cy+eESbQ}ru`uS=b zAq8_3n83D4Wr>A&9Mpy3kSokCKbS+Npjz2bbZeg>W8s|W?FGdvav9-9t+LSbbP*{T@uR>n~%S;RGJlL~34 zIO!Rw1<(WDiWTDfJMAAQA9lfA-!dqo2S%R)t!k+~ZcX*N<_Bt-<`w6QWYyqBU7#Z+ zgcfAdHclm?9;X_~X&nt=9i|BLczvQ-IJIB9Y`q3xU^_L{VgJ7Re4mLcbYIKlahQ~@ z)6^;M6=pn1gXGU0VLka;sS!g!v4tYSm^}|-BIL-=KmrG2U|W%+&q6WY}alQmZySr zz`6-3RF)+!-`cb)tia`DYm|WYtFDA+)>wZ7q#CT;V$@J z2AoDFgm3T7{glb9I{tlm8}gCrSw2zIgGaGsI!ThfA7KuMP$Z090bMe_#Vwzgoq|1j z7+W2N4(Cwv9Vi@%@8j%jc4MnplEe>ufof+Srq~FqFJf7l1i*LQdcK|~7nr2eh4uQ%ExGn3VRqb@FB=Nan!p0d`}FipgQC>sR%LRQocdD9RC;UvQOMr zHT};$sLCJdezll>MH^1vhTw?VvSK=vE6nhv0ewVd3ekgL?oIeJHq92xMo+CqM2y87 z>taw`o-tw_qL(&=Y)%-N^qiTMhO{4fu?l{Kdv9yg#jlmDt!18!C^?PB76&)DU1;-h z4@bW>W}+6oCy(H1*Q`60nN*{#@V~GcR>R; zZR?k$E~Y;!@63b|M8Zbj#+v-<$VZd`X8OJ1}c==lbSq>fVjB zH)RVBOk;nc%b#otJ+g2MXXWxtp&CG|+ISek-$)yg5tDE9sNl7{tL@b#y-T|^Y%1SN zG3hKT8?c_4s7&hVwSMSzHv_RiyyGxu&VBBCUweNxtcD>T(7awwkPfgmi*PA1lLSthl|X&=qijWkeSsLrx%s#ES-iM$@a%wc#4!BqMu`R(}a^BtY=~ww9 z%I2JJnCpY9WL@Cec%^=}Ad$fzdR?G4L_{?Uj1xfPuKtBo(T)H*Cfv#IQosn$2=6CE zL!FEt*#!QlDJNK=)umgu$4QOn7?;6#^IP`S1eq#3*x4#I&~Aoomafy$IyRj_HF%&2 zwGgRl53|)&naP1drtR!LQV9_m{vm0fN9^pRvjx5GnBr`A`I9=Wzx_>Ul4^Q|{H^Yg zSbuxg(nfk63|F=-ch$U{UJaYh`x53)JHae5J+rn;{ocC$Bmtibsgm=Q~)>8zDC#A=#Gcz>bkL%NpLP{R1$ol@R6qUoJ7{UY$Vk_G=ch)ySDfG@MLZihC(&a3= z#f42`)pPg(aQW8P)<3r2YeX~;W6h?c=8aXUyswfy`+XS__Vn_n!Vq_ub%6J=El^x` z-qYpjvHY2se6g47W~gLW0|GL!h_KZH$L82C+9qP*J2jy7Q2ho+S_UL0UtWk zu9&-}rPARCNrD{?bExsIFHkCMDW>2SFS*SrHhgRJBpZ=))j29|L0i^VTe)U?cVfpB z&KPdAS4uVm*76Q=R4W&-nG{U9D8sUst^nbcvr{*&90wceYE;tv@^EED!C1s6fkT!4g9bmRDS?Sbt zj?Z0lAK^r{W==b)sMFDo=t<9v74v>(=gl|Tbu*1J-udJ4WB&+0Shn%GuVg{>7iaDQ zN#-FZXBha?XD8R{@mCV~Oi`qO`UHWt!i0%+b&J^j^uE0*yz*B_B|fehqz zn_B~=b=CKR8j%L>isf8MjDCvjro}rUNUB{Wfy7(tig2XU88Fy_MVqlmdEl&JpwYN4 z$C76b9+?YXX{PR5~I2&Z+^=niK1rrPsuS|c?F-s`z@##bJszB$&*}8nl^gLBcW#-kNFo-)vIyjS)uu_>>uQ3g z?og<_$}7-dQdbg8iRS&JhkUhCr1bYNoMrU^Yv@*gV=lSK$v?mcX_Xn@$+fUK(LL!S zS```V-_!B2!v%V9im``N$kvQiaix(wK9`+tH~ znUt%;4OVA&o}G8zYx}W3xE5bg{e^+ZSUGz#XKH|+=aYblp<=glM2WTd0=r3+ErwTJ zZu+eMwUrvDZfUq4yFes$! z56FN`iE?B(W~g>Tqhjf^Cm;&sZt+l2E6j5Hl2Oa&*IaKI+W$&Rxm8tz=i#G&IDw6f zwbU1VQy=Z5G4b)`+Sy7LNEf|x^V4JMorei&S!S{sRU8EOC9Z-d>LB{*E|-(42otr% zl&+Igq}h)=6S!b09@PO&4Vi}@?|Z7&nKc%Zu&%o)Vygr-@9Sy9*@fBLPc^tnWJk!J zsB@Nobg$!YZE&kPY ziZIb%OP^XT#=IlILz=chCi@CSb{e`7k(@+YODQ4D2bcq_d#Rjc$73arab=xSYp=|D zHqKt!M2N6Dxhp@0BQQ#X0S4T!X0X3~FgdzlxRxiMkrN%B_lY`foW$0Kqs);G6$rAc zFcIGC$_|JpLBUe}6&!nL*s~`QBN|J_yj95XY6Y4$#d>Z%lG$t*pv!$4H)Vs%T_!7&*RcA$U8GY2 z;>ch(3MD$;7K!^J6-=;FTFV^pVun2VCK`OUpg#e)m(BbMx@d><3%0}^$5?DcVmxpy)ENkx$mPQ}QIi{}=cjAnF=Y5J zuass7hUVk)0ivg52G!UXZX$}K$)RxsGz2x6GhKHB)yN)9;aMKJX{oo2DeF28%(C|| z+Sh*3=e6e)e`>%Tq-ZjL2y_^<-HOM?7kzBh7FTi}&Pyrd;|wERI;e%LAh4=*#2TjL zqkU!-uHtVhM6F(4IFR_XKh9PJ`V8;>9@$K~k>SY0mRZSIP} z$Iw~b)=eLgtv>{&F0lXV-QvvzL7@nbiwjZnPAW7qB#w~!Mo)`TpyIBUxHUVpbX+_d@>xuN3%P&KDl+!WQo3ajFh;2AfUA^H(3jd995(fLKf}pY z#uqz?Oo>Y5o0FNmGfGd6jm&7JKt?S%L{&ft9j)bF1}tvUup0-GR+F~o-`&FLN|s3xV$3^w&j;nUU12^VRY9(AS-gzA6d4T6arf=4s^w8HJb?oVk-T-Q~z2f=in9ny6WLvQD$ zgnAn3N?T_sl}+Q~63VoMNlRzpIIgzF@BAIG!Z$1jPsbu;({ZXMg>j@%l^b zGCg!sLwfOiKkI&;)D#TbRSWr?E8_Wx72u>)U~= zIlAhW>el%30>nag<|9C(s-dpLynjo-_F@J@*&N3bCo64rh?gh=Q4Lpb-3+uWxy zQ{p-MgFwX0AJP~jut)6RT@rVeR=v=-B`?#f8^S-O>e<3^p&Ew}78=E!IH#1s&r46N z1A@rm+srGc9T=}mXJj}?riTliTm906@=#m*JKi?8o5x9oUa*Fbv6p9TBR<~?Zp0X; z5j!bZNd(SEN?-alfFT(q9+oGmTE-z>nQtXxuNzlTKyela4(~^$grs3fyp`e;GMQtY zK9AwM$3p+WjK{4p94(% zD)9c;s-^r*8;@m8;z!~U!-q?_j zbVGEMfJV%RYtE)Jb$z;U|k2kMeL;Z_ddXhi?y<``bay5SM zn`S{Fz7aBBa3EIKAd^w)rZHuf{BtY;?8z&WU^ahkIoNvg7)Fc_`QH6>2tAp@oiDSg zx-Exz4q=&yQiXKRLUQOc65s09v; zXMYt-eBXLt#_D)JzIcnvI{o7eZF+fMaO+tA@Qiy_2 zq$vz#%nwYaLBbolY|K%EzN5iSFb7W=jO33<#zoCPk+1aQk<-#AK&2+_Fwy;6S{vto z@GJsZ#wP$sUg((GC=*)%BP@^K-uNOg5SqvNd9=)Bynx=umcI#JN@s05+v3*pMh&xD zrZL=iP<6ZO%oD@Ty*bLk^+!pAqA{}e@N#IJHsQ?8b{>t}(Gyx> zQk@p$SL9Se92oE!v;y&f@l4Gku2+N%SF@ldThJZ5-jAsTnldATuVy@MC23I%^xK(h z^`Wm}EUT5a<<*oD2jYoh0zO+tW>%V_9UZx4y-A|>|-+CxSu3vcZ*782HJ$1Z+F1gvXf49tLJPWs5oSK7> z4`zrYjqp_lueFgh(6HrO>MaeI;G`GQo0bG-$#*E?UN7HQx3_R=HcWzwgR(TM6f5Ls z$ezFKZSCR~sw>u@b^cCs4wum;o6|xN)!_ClmGZi|YO!oTo7^WsDE)b1aOK;5_BR%9 zu{+!cjOmGyTPs0QdT)WJfsGt{YN}}%FV>lrS-_@8L_F}@!Bpjf9B*mhhv1hFD*nvE zD#I7qjKZCGQ)m5#VzC&;W16~xz81vWHavNWGYF`G1km@Se-nhRS z?>tAx+E)CS&xxo~G@Ym=R)i>uC4UsS>XFn!t+;g@J@RgD&<5sNG3UIVG^HFQha^Cj zCBLy&3iJ^8a;ZUlpYi{_022@pw|Fcv?KI^UYp_<#0H#LMl6B>R5>9G-Ix3^iQod=C zL>d+j#ZevgFNeGHpK84#(+iBX%RHjbfyGU&l|zT|sJBZ%YmdW7FlW{Zk*}HH)@9;t zcU(Uhh>N1n;%kkM%SYeb&^6jj*3W;OhH;jYn9*^d&*~|3w%28Y7&HMRx*o;{X%XjS zTg`}fPCZ(b2m4MpMSFZcEVI*M3yGWiejTJn_;js>Sben1tNeL1l(I-{kvy$bxiTzC zypO40+r=0%xglA#4a7<^$^?-F$5yBw{MnhSfoa~}kj23U^ozbkPQ~tA!I)ijQxmjsK8k~;SRC>47)r4K68EGn z*JZAzXJ%-tXzQKc^!&QwULCf#crEJC1%eeABBA`=%II2mq?Ra(R7Mi|JryZo_X)dI zmKV(H`dL|Kl@2`d1EC;SM;YQMvQgad_iXpDc|4Z(h1^S##l6_jHIY34H z+n}0;iV5aiu+mw!+(bK$9x+&AoO*jSP2=ff@9c{-Gnd^H$c6JoCP(3xwf;B(B0?c%BFpH^Uo$QHwsyWpzF<#uEifwCd%x{hv-(wk zN#KE0`%64SODc)>>L2^E;v(f)b|4vd!O@~lyJ4ti9~@-JzdaNn8RxdYx|7*i6dFwpp`qodbw=#t3AfG?W}V2X7C;S7HzF zF~b`vVZf1dEkoV1XI``6N_=or^}qyxJ8i2H3+#Lgy;rhqHi_*n*{5H+IWB`LG2w+O zL@E75(22NuU$U}-kD&W5AHS@S)m1dl6O4sXmIi+=$)MHgxHp-UEEZUD#L2Dk4mM?x zHWt8W(#A|I<_649|Ff03K1mb5qf+lTu4-WtCvT)MXR!aO&B5`%kk zT&b7$@?qKEJ~psHko89oZ&2y720cB6L#uRiD|}rxuMnTn{}7Y%W7~NOiqIY} zS1eN#`<@l3`4E}RYa$LD$4WA{Zhkw`fu{_w{(B5X}Os_Qo6;6C#W zO0I4xH4wQX{nB6`7f?dpYxsrgJ^kHwd1r9*jnC!ndOT8gnmejgO-#hh;GTuaF-omF z+88%&T8xiu99YsvcB(}-Em^E2kilx!imK7Z@lcvjBU&k>hoZF9kcX+?XB)#MGJJ(cxE~MtGUEc&+|M#`b4c! z*q3|vBBFLDb`aAKdU%kz%jZ&I&wR<#aLplK zQKfj-yNzTx+K|cN4Qo-d%`(G3y66tV$WvHcI;?J)GO?-X|Axmp%f~%?bjaMC*gt#b z%s&}z{sSi@o8;A(jqAlzUV3eOg*x02M^}w@Ul#UKhh+XSY`GmTPWJ&dg~nDA9#nIo z=Jo4!^TH-Shp&4e;@R4TsiRweptBE;M?Xy4IdHz${@9TS$ZA%#2WaaG&y8Ii9l2_w zJm|_kGLC8s0LUnXX%8{BGuc=&t8oiq6&Y+m?3Kq_YL|H*E7mtWfPe`3PZY;jJay)n z>hH-73wy42#pgnMKm7YV*{N00Z?fe}qRq!u)OVy5YY*6$8#N`y>PfT#MK22F-`0h_ zcLiEK7y5x9vT)}&%HpcSt#;s<6rVHgUwF2)vhV{!h^uVHDY}gMi+xwt>ghNjagt;* zkLMVdvo}78QGE4#Y;k0yk9j~--g-g54j00blEt-^Ynyuc4+s)y?rA#Kv>Ll z!Zw?_2ql@2puS%Vxz!^75HX;6;MO+#1~~P!%2c@~flt0xNNB`sLs;Y;EL9Z0nn3ba zht5a6f(d}3n%w(?zPAkVBK}{xV12gTwQRH9A_>*fJIXyYr77<3zF8T48CIw?Q+AL= z5w#xJ=GyI^Bd+{RN)?|R?&zK4hF7K9;c{ra*ERd;i6(FLRJlrny9Tn`-G}Q;onGea z1p+3xB`=Rkz)DwI%EX4Af-)RJh9($k$nU!O+-gV$LA&^!{kb|G$}(F>Xkada4Rz8{ zm3!SspPVRJkvR4J)JmGws%z5`yjtFKYae%RV4oG@xs83jg-$NT8X5VhR5|lhJNS(T zwu!-~6z~Tko+}5xO>_0uw|~~k28W@!cGiU#ei$idzI5L@44o^K$!9Efz?sO~f;hFk z^|T?CW1Q^y_ttRX>6?%dWk(47SO4DU5I7{&T}LV5@9B+&^M6M!!HqxHGR6FlTN&a% zUv#!FeUc)=x?XCgs`n7UndoJ89?!DH68J|X0u52kLcML+L7OjE$2$*6$Itx_UZkvE#-p`#4#&L%h zAVxS-Kgkww@3)^%o*3v5brPCsO>6ZhDzfwleDP-Yxbv0XcdO7hk3uL`RqxNe5uJOe z<4rW})pNLhfgvrU+Jf7~L9-@%!j^&Wr!@ue{Zqlp-daMGr?<8RWGm=V z+ys><4a~Su-Tp~GWs^TFeQ#}V#(od}5KDp*RYgIOZI-zRP>SBb{zhu#Xi^V7lBN^r z3_U9Vi*i5z1p!zpjpuV6xNv^uOBj;Mdez`JCoA<|K(QRIzF`Y za868=j>j&OOLLBfTLDA7VSAn$2AOHL{29XPhUHx?tLUf~a19l%ncV!)@UHV8*n{qZ zuH9Th+==@4xo_1B;S3|6#TIiTccg&my6GPy`+dY*LMjNBf^HorR>qZe^7=n~>#P>F z1UXhi&xPfd;ZCoiQsw}(fD3Ek*nJ?<97n54N77oEcTBgc7oii}YbcaeP<%WU4j6F~ zVq|E850{qEBJh_EjU$G@%a-01psKTUuzGg68AudYT88BDWg83_UqX=&+kM|6t1^ z)L^vTLX{acVLKu*BOTF(+&WFYNaQ7uI2WgKGXskbIzw-ED+ssRaci_!y|bj3_(T-W zck!JvQqPl6D$c%itfX)ao_sm`@2h-vx$!dYaXMOG16~c(CsbtEynn)YPJ25k5%$K~ zrXe&xrc}*-S1ZJnqDcKpQ{QUx?53r0b)XKHQvn_JG$|dxQ)2F!#v?7Iy+E%Uo?t%!ea6FzZqCl0B zb+#FZ_#6#9y$F?Dn&|4?lSy|x6^n%xVUMFdopYQ#zyV~0$MGo?r41bM7iH0(;uAI` zfy7zn;{XO`Elt>P%zrE%bQzAH;L3TUlr#u60!(7(jA-xgr(W@tyD|w~6{kR3Wxk

xI*g#aViK_W$4xFd*y zL2-mQT3jn$uGUtcQ~uy_@wT|N4>EN!aatE_fRDu0uJt~L$wPbHj$H$eAmEHNmyv13 z1#_qXpgUu!0?f2LzcS4D@afUL^}Jt5*9u-Ph#)ZN{Li|`^y>7^Idz1Y{^W$dbb)F9 zDT&UPEZGXcwPPJh5 zSRPydelZY`Kzv`g$)WDIR<1LxssP}94fCn@Z?Zu@wG8X`zElV}^GGpNtpjG#s6EO| z48axw0NW916(Cg+Y~VZ0H;E<;QN%;(t-~_gwtYREL!IQ8*J>mnX4SB03E^B@CG)QT zkA|Oz^E!1`0~6v)ELHesV98yXdQJGZklHU?zX$`b07ha@?UL(3H4D|uR6x#l)U91~|z>=uG^1UF5D`{RXnT>1i-Aj^~>6#FP zb@g6y{?>(*E0LjPRsPys1N`Isnb~S%NW>cEmUIJ_OG!1tAazs6jcC#g%B7* z0l!nBf$vlp`pq{2-xH=0>Ht&6v(g8@@6tO2;T_g+I%T93+~X02`O*U% zQ&wKDAz4`uLp_$OkNfrA`o2fuA{>nD1Tn%nA`1g3H-%uAgii0waYV$?aadttf$Tft zuXn=X))^+{Nr6Hb7*DF87)#8-3`!U=1n#!TE(4+qXO~FD>{UH({4txjVtHrFbWesMC z1}RCH{f_nY%>)NVn(objw*r8wRocfC@e$g7)}3Z|2HQkJPffo^uYJ}wbBRDE`VRnd z3Phn~{MDMIK-3w{(wOTFi1mHSu?exWxxh&mgwG=cKzlT_LV)VCn~X!3lpH@G-+OH1 zA^^|{;4D4>bni8TXgZ<8p3<-9tR?M)X*7HGf6gO(0j?pIR=a-p2-=68wav;( z_%EI~22-4HJcVgG0#}G9W>96>9u$875!5<2YW`m>0Me#6SmFSLAHSQWNB~@+i@Wv6 z_-`|3?4ks;PYQo`hk+q%u^yYBg2P~n$5;Y5FOQjX#ybdL)UL~@+SK`ef3z(PHLYCT z{jXJx=9{douI0>pNgcM>PI8y!4>W{6iCpo};CrZ@VhVrps#rb9A=@6#iQ;f8U&nhoAY9CWvpX$t-6C)pLmPCAfyFsXFStLUPrE}v;79q* zPCo{p4Nu!cZou|2!uXF}f`G%v>8|1_>d!RZY+<3fg=NV2jO&xqw_VpRU0`7hp66qJ zbRE7R2!H^VVc59C^ZJ0DphxsI>0uuk>0d;+uCYF(Vzu$%A|6^0qZul8tH+YM{=H)e zI1x(F$o%iI)?7kE!eRk~)Un;r#W&6T5C>`O7BGf!)GSYPy~%FZZ2bY8!u5ohR_%MU zpZx4e@V3D~fkX4A;AG}C>-mlILo`AoUm^nHtli={wCe!~=KdX;n)U)`e{D*I?7Z1IUo=0k7=CxQ*X&$8 zY4%|LpR)AhTgtc73jwqQFqq40;{9ED=J9*`K}-e9zkrZGX0U7i@QVKnI>} z;qY%~zv*^`Zx7cv_Cm7tp@NlrtKB-|&xXLYT~}n_Sn0o>OU6yKYaD|xe8gv%g6qEb zd51I+U$vrg3|~cr=~sUH+RXb*Z}^b1S_dn`(U3H*t3c57nkJsmtXi}FYK}hqhVOW7 zoz=j)M*I1H5PwDhfO&ER01P1nqnjt<6Lu0oxVR4os^P!B|F`=k0OFCm4q61I?EIoT z4UP~u9Kinn+PuQ`?J2lof}n5*Trq9%*9uR#gL6F?MVW8$uFJ53hYL=;**X9d!4muq z{ukCTmr1idbUKU?|`dpgm$J zBLG1AKG~Ty8wbxZ5&-r%2aHzUZosETc<&d!pA6dy3%}QQQx7AU|1r)Tr~BmnElc%K zDzucf!x3}4eTc7$mpF&~64+=U=d)i`u=>}<2MB~8`ZC)! zJ|zf-Pkr}O^1GFHL}#lW?qbM+xgJ`u?@5Sw9L9%Mk1wRWPK**W5)|$COrR1LkVY4* zGn^kc^I!kHXA%1u{(O!zKC~@e2eARw(&?3$J)66oXYlgC zF_SG80y-3e*=%*L80x@Ty-*4rF0t}Hgm3{K=`sh=GAUh=n&{I^S2LmZUxLMJ!|?w5 zX7>y;e%!80EuDlrMC63+x;9Qun*EbS^VjT3@Pu6+9-WVx9fTB*S*iO|_XtaXtz5ea zU=7*ajjdj?^D(Yze(H!qky&e>LRfyG6;3%n)nB_Lgbp&(4y z);>J^==%KOL!fq)dbCD42N6UY&avJTIT&YUyky?0%&<(dYj3j#nP&_ctKfk6=@^XR z^re2p_{?qgtuW`MIQd;N^fL8CL#-EU^@9_<4rAXRWrV~PrbP$wsT3*h-29V@UF3l&8n!{KZ7_z z{~!tgo+BjuxyKZz;PrFy1bFulv^&QltJ?uD>=MPnu@>s_@lCg7{hs;MbKA$cC0slO z*H6hgeUJ9(&VOh9{|*3kK#ITf)vrzKE-vv6;P!yj@&X)>+<3gN<{XW66#&o`?TzC& z#S;?u8&XZp`!#V_gH7|e>tUfO&YP_ta7??a)?4d3{2*xUfWzJS;Xl(YnR`1p{%G=P zA9hbD7Ig~XsF%W%1jb#?`|HfHoGUO;NRTShOrh)>#P^9Srz7;-Ml zY)7PNiaGfWTIClqg04^)qSC;*%y~?Uh`Leu%KXR(N%%2$bP%gL0c_9l0Iw>< zBLtJ{#@(YhYvC}9i#$h~kar$L5VZ}_TYnw8Sj87YfW;y4h&n>^whl_{g;SGds)17qhWCg080}dvjpJDVmpqz_Nj}O z04@P2Wcv{Hcs>N+wVB>)qC~z{015%z2JjdHP65CP`zxJ6IL$Y(#*mO!^P_Vw;T{W% zt8l*8YOFKAX$aJ=JM7NpVRx3&zQjO-)PfXbgh31+zA{`?nN&_=cI>r*uNGjx6*iI0X#=^(yNiv2NNvw)$((#)<1p#&LIMz z2c#of%=lZq0z=rgItS7MK+6d|HMbBDY9SzViz+|@fwhEFh!F(<3RR?VBse^}C{vA2 z(tG%)4QvOWBQAsQ^wDSD2-l^(@la`>w5tT86)eXwN7piLu{^;oyLPG*KqwA1cG5PM z=5;Qw&#uX3Ws*wM>fEbt16a2Ba!bIu&b{dGE%5Jb!$fLodnjm0Z68KGR|eo;LP07H z^JvI5Kbp@wc0?8)MF=v>G8|Wz0f!Eyut?7zTfTIEfmlwq7z)k_c;-yx`c)n6^xLW&QJYL7?`gFS6E*+6No1YnZEPSFayzW#25g z*yy_W=9BA`JA!~rXCgD2Z6o0dqnn7vw9|}TQ!~BIB3VW^4tuY_;q zQ(4F7#AWe^J$ZP3M^#HUcDEWhm+sAkEzRrPF1!SxE)<2zH<9cFKu8A{9ZS- z+j_B^c5{w~j8&tFClK_fa3p8Mg*yNUf7>Q)LHoqYqPEkWR$!gk=RiQh{f$7H$rg+FBX?APVn+EF3>9kt*r^^BK=DV|p=Dn3`+)SQYA- z_Qtq3^M34mIt(c<-yVi#nt2Xx)VkF2dn?aU7Mb>F1FeJafz+t)$TXRF>n?7vULIT1 zV6G~1%sbu(ZzRoUgn@WO{DI>+zBLj?;u4&uZgYQwM4 zrb~w)2$1P*?Qb>#%MiOUeeI0C*D@}Z(5Q?6x95C8-?d+-PxDU3fK}pK!@O$6mvm1L zPaky-j{u)Jeeit?XaE2}07*naR7yUqwI3lI?|{9E_4dN0eF77P946bW(i{#ClkHrC zkgRIn_2~WK`QZ6W>3)l%WqE{4BsPHu{nhOr&3G*H@A#f$`fov!IfZa}M}{sGH3j}+(IynVMcMKaRQKLju2z&{6i6k`$v>)jcC>x1%wRA>_^-8ecacMuP-xQ+W zepiCmYG-KD5ce8yBHuwEfc%3tZEe>Of3(f=$OCUBAnKRb$CZP?kjb}jAsX%P_WQ~N z^nD{^!GTYDp6%~TJXgk{z7xXP@d2X|%ARNPZQfA;Ad~EPTINURk_o0ub*z0ai-W-t zmB}ybaBD&u3*G zxYyUS3I?!orYNM#RJj=2?|60F2gcdF6SDVRxANZbZ)Y}c)7!aKJ8GNoLZaa`y3V82N3sMo$IQYwA7PwT2>ie zs_FK-(T0y1m$V<7HBt|)6}g!s!Vc2YKkcK5Rmix7KGX4S}@)V5OVq-Gv(t!g~JhH`aG=4FV!fiBBgyozkKGEd(tS283((^lwp( zu*J;YAE20y3(-4;@ZC6U&VK(tn(5&YlOJ2tupjZ5r2%@v9sLp35&Cz`Hh7tA`oi1R z%W&ypnR@#t&MRv6G4G$hLQDJ-Z7^&8r5V}<{to7Q&H3q%&Bdhm5|0=EX1oW(i1vTu zj}Qeva*b9WZA%ERY$eBawojDU2ac5}Q+Og#CX6LuoPKi7bM={FjWdDW0AT!t^XBqX z)KA91t-20=X_}*#v}M_@YjV11whv~_v)N|z1H{#L{c2q;0N4+Jt75o2EavK*%jV0D z6jT4I+cWhL0o4oQzwNfoKVmxh5}y@^5Ju-u(DFSUHwXJW?83O0odB9`+OoEXCbpix z2HxsacU_Xp5D0VZ*j4q$(as>jZ@P?lOwwfzxVHbx^vmRHt{zii(tJ(=SuI+&v4in7 z&F_sN?!jx*%~u@3aWEYr`pHN;s1f(Q9)%H5PzbY#+3*5CA@d8Ig^Ek%8r0ajM)?sQ z-1om>rI6M_;)-xKoYUuWEe>|jS_h&`hGx80EcLVeTw4d%-`DzEe(Pg>&(Q?>OavU1 zPX?)di87V+j(W?yGY%~C2xexy!F|tV8UjEW3hHgtem@M9uQ9re*0~p+OkkWRa6eC3 zF7^lqq8ld&4$rrnNBBV4XNlAw*jeN$mSnqF73uk3Ok(YdO;HgGaCs*|&HoHo{KB3f z9=$%JJr8N$KX1*Ne}BBw{QUH9a1hFNp<6Kic>F*A_Q&S<*>}wx2f3{{!Zs8~S6q?v zC6c|}dSq^pF{LjFMfa<>y*BYd!`5)!lfR+uY5!e((cp`r!(m!5{`%Mx-QKdo#DQ5anwx5{~ZwUfYyq0 ztne1!FwCjY>?h{;@A|BPSp;y5H;1G1bAlD`W77D(-Q6_(!Z@~m`mexLD+4SYS^wYS zO@;}yIXlG(;K?CRLJuhfqYq7XSc`vl*lf@2kX*PL{gEzj^Q=ye!{?IGv zP+o_o`3)dcO!qM0VHdnEK8(_TnWd}5jJJ0KV@CPVD(DW+~0*MYWJMfJNELPH%Iizzpw??zte=j(@ckGViu3l8|{yqlZ!;*lY9o}f0^2qvkMIaF7m)7?vLoAVK9}n>elPclpwsa8dVerG~n@)#6 zVTTh5do^U$VVF+E6p+b4%Xq_7k6;FklgBR*X5xs9{)EkMhO^s$>69x(y(&P*IE?RN zMt?ee(kx#6z&9BCGAL>i* zFYDk~&T}F&qV<6(X$~3Refi0Za$%ki+dCeyO&put@iKXuHRab)9NxwCMJlszmydRp zqPdNn1ahVZU}_D?C{YlrnVVwjKV>P+cX(z0mU{27|NInN`h6UU>Ok~67_&$5D}sL! zGS#BUP*{KFf+1eao!j}b^u^iV96$d@EC)IVGI;+-WqJrK{tWnkeY(^9`qOsv0_(L4 z1OOdg)EAGxZO$J*4UXt!{$-qkqQ%|TrPSwkN`2+4rEyAPX_RsflV|^Tp6+nE*ldBp zcM;fw*cUs0W?Mi!+MmBdQH&)3LhtyU|Qe+{h2hDXwVOv5rPne9HTj7Z~lrj#)HcPlpt7H>*!ovIx^35oyd=CA!^7R z?mg0e_*=fg7!r4YD>@V)Esh6gfBp}w9ucC?z!{i7ssNena8K?3;*e_vYv2Z!4(RV! z{mNAHed(W?k6F~Rm^QpIcqZvq4>4Mi(5SmBfRb*JTIa+|x-@HO6+h%R z{iMhH4wi%RW!t}F96jOjzgQ6>%77qmw;r?i^Y@%XRH^NcH-C=1X#a&pOf7+jp-w`v zprCS@h)lPl_4-Psy;q;}8#f)yZV2m88Z?Fsh1yRwoiGf#bQnXhPjI5NjpkqnVrmyk zNpIaU{t5xA0q;#0@#el)7=8)-YTT<3psefdnj;vS1I(^p!q6N@|6!HVLHua)+ioD> zQg|a_p8()OP+V!Rn=9=4OE(SyI=T#S*7Nk|YWrpG)88SCyCLJA-)j+z<4MC$k3HBk@j?)h33>T82xFs+l-IV48F7sTJ+;LtE6?ik<)hm3~|zf6aWe99-XBF!lCKcfx`HxztWH=mUOIEE>C zg-)Q>H39(2J%V9DS1=kO;LsvKW|y0A-ZJ=VA8TT+%iV|ai_|M&S*?#KxB&VhLc0GKQIk)r z#HTd=r{#2KZ`HwjXBnssj$L`hWR`1r&XszmSBDPO)|RhjNn0leDpx*)9FMv(2uW3_d`L;8S4sMZFVZu^-eK z*bw_+jP2t@3CPM6%k*n1pJf0F#5ni9Ti6-TB$`Q=sm6?2CVOCOIWDF}yeDUEp7}Oqvft4^xlzg*Eq~vWEqeqSyk|Kw zZijWU4wO;kl_dc@m2pQabefHG887vudrTXexT?YO_roLW|NC;f0;P*KopDGz#`jRh zKlPXKk0jrRc)3>6^L)&Y^dIfNm%|XACS+a!ruG5GbiRd9E8jz?*lA|(IMyMd&-2qN zBtp>AT?kv~3HlbT5FXaCmIrGwKBXH`#w^o8Ad+bVUTPT<}WtP3IS?2%Y+^?>*Cx=8Zfhh^EW z$$D7GYiO7<{ zoCuu+>qMxAK_nb1(F#du;AvRLcy56wAqr{o!U(h0H_MbugPeGdzudG)l{t-TE=m# z0AMUOh*$uO5CBNotBo6NFhW?HTPRD(aC)I>Q?-KXm%)ja$@TSUYSA}?V<->Xh(-v< zD5FDC4f0oT(1BZI=zPaCtgR&C!{k?@H%ty?jPW1OgzD!wralwkFeO@7HGb418p;uM z!>QjGZKdf!<76F60JEex(N;Pf)VQWz2>(3qakkkDzG&PiqIgu4H|A#p!g~v$!8QWK z>>z@KP2VAE{;LSlQFR%Q+}=177gUCyY=aZ3!@pzN^$3`qlIo5i$JG58oS^6b1r{3Z z78YO#0$wl65J0wZAN}BchO6^T=4cu&%g~sg920iXG?3S9#=|I(jj&Fh>8WqJg;CyfQ7Lnzc^ZiKA30~ z$oSHVCQ1^G3dX&-#pOmk8)1d3 zOty{Z3cMox63BhDLe@zfois0uF4ZbROtEwi${yVH86LasP&2L#ZPtcbgnBHgpYm%C zZwocIx81Mle&a)*t?%6V(P?QN8a&#p!x{p&2>}tVGnE8J&;mm*gsNtdg;B7XsmO9;3ot4lD{K`LWk&+Xq5 zf(joa0N}V30zeEy_>OQCHq!YWy&?>;=IO8)VL`n| z+%L|rNT%pK9Hu_Zzw*o;-9-REy~b$5#|QwtpQy&s_JFxaF{oofEnJIchzbg|9CF*x zVKn_R({KK_8_MW+Ign@m(VSe(n3v9pS_7TJJmU5Q0RZ9=;yLx5*Cj!5+)CwjoTkaN z?Gb`Kz`NbTfAZHUo8`2;;yRfp+Jc@-n-LMncnwfb-f@P_}^9V)3b+Oa}w|Q;ZZPSYTZ429ENtb!g z3Q$ks;AtX&NnL%vW^&)hW#MWe`{R4dg^Aia*u}r*K+lgn{=s#ItT|)?_9$UeufOKT zT*EUr`d$y zMdF+Z3a!J&BN$6P4?E%6gKs-Hrx<(UHIp@*VT(QZ;tZ|u*)EoHyUa0YN!%Z9=NWXw zkNEQXA6ftTw>aziiMa%czC@Lb<2JDH_`x&uZCCJ`?`QIa2^cU-V|H^MB#mi>* zm*1PM-+!fjj+#9*|4-+e%}?h~*ahH+c%ro}M5>;N&@JZ1%xp1Q$7uHUDxG&^YZ zAFEmCdp;XZi2It$&W~9O&o{&A`VI`V&Q152r#94x^NQMh`v}~$%yYqGCJ<%*XLEd! zoi$rOy?{4pKHMp=WEA|xI^;ezh(JU97ay=c4e_+c1#IyLJoWbf0*j9S{n?D8&i}v-F#a<%{>P8DoB#YP9RB_EM;zl} z^(FIfblcZG)`3R|Y#mlGREE^`>Yn#YUAhHM>5jpS&%bTDqsPeT87~O7#t5|9@9k3v zfS=O8>CfZZr>$Pve1+<1ck6jS`(1~?y2aUDi{F~|j4^dK#xF5#v%ts31kd-2XN)zL z?oGAaL(nFpE`wNwIbjT`e=EL^RM7?|J1rKD@n!PMzu=+s|HHW{dQSbGR7Zw8%-@^r`jBx6plm1G z=gAMu@A_J)G@I>(kQVEn@#AeCgZ`w>h{O`bymwmLzU_p4975VB>6;_^REd<=Ht;#) z^@XcSUwg<`8yuOd9^T%BpI>rO!GjB>KTEWfXb<|=TRl(@?^C}rar_4@Ğ`!w`JQd1prmb9J4c-#vW1M zK^;CSi&U_0qX+gUj zt9NDpsb>FoH?8$iHO<4euR?%q=>-vX92Z|j1aL$foiO2F>>;dr1hb`sO15Is8+(|4 z9kR*6Nzh3kuEYI9zy_@Zq4Pnm>BCivcUP);x65GxqUYBC}0K3Jpdq3GisI%6tT4y+AB;0rx5Y4$jw}V*dP$eM9zPG`3;;6&}j|dlZkD#a#pi06O|R zKp=RU)&2`K|BL2;a{orV|KsC%^BcQ298m8WLXO22J^*n3cZ87e;wihn>>%Wo`4`8_ zU?>1zWgKBcT2AqqjTb>ZEi^+LevUKSbMW7bM|g>csX9aW#m)~pvYhPC7)JCB=494z z@NQ|H^l2{Z^^reQ z5HlaKI{+0JyNn2WXv)@x8{mN8B$}jH+mM+8H^#WfT8vtRX!n;Feetm7XsP<<_u>!) z04g{*&ROQScm*wX{AWyEv;+VaJHTfjL6Lo0A-D<+EhZ9@Ti@>edCluqkJQ!n)t8A4 z?72AJ9Zg>RC%7E}z^lK|cd_KsQp+~kVVrI$m~;N7{PBN5JG+cZpDuB<$~~-l;;EG- zSL1#0kT#A`H{#LY%v-J4^&bzi*9l|#8*++zFR6?4W%h^rs5)Du@#8A-S{5FtvRdIA(3^p3$%;=PC%u^$K?aCFM@2wiWF(nxh583~_TdYj#f0n>~oZ4YZVdY|*t35wZ(0vjvl) z$8I%uh4fGiV5IshTUB*_MF1e%uO&bs`rYCShh8vf3q3Ql7jm-;F@Ux&?U{YpY424P zMZUe^d&>_=M<|uqTAER!AVzZ-<9Kteszv`K7P)>AqmdbN%?J%Zb#oBAalF zz!V*;02%0Z=BUCNfqNr_Z4pXRE!V1KjWG9Pj6hZqn9^01FBlCu6qK5xlvPQkj43bA zTW^J|!Mm0}k%RRT57%uA_*lN@Pd~tyC@nW?hW(N9!!xE_oezp%WLjYU$HYyT2$_Dh z|GNTu#-l|9Nsy1tMOkT1aWr_ z`dt{sX#H(Vo(~NpfIcGRo&Nc}%8#(tD#T?L6)$NC0BpOnQ>*~6z(F`Uns3t_Cp^aT zAANo(=mR0NuGgpE`RNH=O~JHo1eRTlI=VdZQc3H@ux(7U%@8Jxx4~(UEb+etZW(C_ zaDt%W0N)?(1aLwI?hc@E2xfD+WGan6{HS%UnR$K(!R&+UIgws5SkAcuE0otpxzvQ7G>g{uv7^?F!ehrR(Z**dHta7z%# ztVCCH(yNq#$V$mKRCMu>&qT;%Jd&YCn>GSJW!)hYo}O^^(kng=aVtN{}>B@|balXz)CJdUfk{N8nq{Y-~_NZCr_MBYihoo@oCO0%$6F0X=liGeD-08eLOt!o}Vl28lhq%)77%HR~q+1Up z12NT?d9V&pM53(tDj+T8PLPS}8 z*Z<46F^?E&!$1GFVWz2 zJx{_t|J3qbIx4)Nj+w))Co$S=+s*;e$Kd%|pO0+Et8MPLEQ3o6JQ3D<+*d1&_PL#? zQAZGAIT+j-vn{>>ur6#F%feb=Vq^z1da9_Zr-_0qgt@WS)AOrgkd|&q))5#Y$Vyv! z%{vPG#;(!9I$;Ek>=5{5?sNB$ST0bQ+V+EQ-do!Tp-^y-0?0C2R{gu2Bj|N^7L^*& z_yc46xn*jE)Cs>5LKHvCc!Z~msm`!1ryDU1)tiqpJ*FTJ96 zTaUx|W);>cD**u-DQ%XYa_)qeD8&iG%w;H5z0Qu5%Dc)+i6%EdylRc2ZEzB-2yfW= z`cL0&b(v}IN6tea^nKu_3%35= zhe4nceLn5E4Vtz6QpWaS670L0gra2|sa@-^0?1ZhnD(RRO`K@rPSpE-T>_x*5%K1&?Ap589WrPa>4<*6nBVfIP4tbKZzf6qw^v(Nj{2C}X_*QWbzW8UHD z_spb*;dxD~N6TJAe;&bvLJ8}F_PE9|ctjyU9EqaNRQq2906bH_aSKP`>Jp&9m+y-Q z9RD+Z&oH&n3c&MImH_DV?+j^*Rzb7u41$n=B|=VY2V5*B*lJ)_Lg>K+f^BCtA%c93nRr=zwNC5gBgcaP2E@d8ltK53EfwQ0%+6ftKoY^TjuhXGeGfh&Sy88QD zpI|2(hSIf$DPQop)7>ft8)4bLw^+bhe<-5&g}yi*(nUO}7kAxfGWC=}KyRnZ_wjvo zSl?ec2#BG=P%-I=xw3}Kb0%dFa6At?5pqvF=R}t|$S!xa+YPVnn(Oe15a@wxd*JQA zF#b-WOq%Whz^Qw4>z2!Hx{O6*SM~l65BR0V9c2FN{k_8kKuygc5L=kHPE$|`L!%l5 z3Ajr$@h5_N{o1EPz&n9{?PC;J+&)bA+~F=a{SO?(LWdBt-ixix;hM& zU61l;_8&r2dR96W1nF8}s~RTT^1`&M&G-4N%jVs5Sp^hC6<;Ct`)`MT?d!12-!hQq z!T32L<&x>g$=LXuubm@QIp-XQY!eun2|@sO0+8{q+JBzz|2`+@>)tIaf3f;`EdtQ@ zKdY^q6PTW3`iG7|wE#G!@JAH+g!Z4q42Kb*-3!weU~^sp<&lS%0P|#dab00nBQ0gN z+yPj3|rqig{~}9!A>b2*Opy|1scv!kDM* zu0KK`>7P#f7H3!lNf0S7AYJ?Gw=HhR=>vnM8~Y`T?}rgtkx4;>9HN-6NXVA z=c_n3M$JK0XcK8699PFWOwXqR4PkLNMPQtBGq{`ZIwxUHo{8l=O9Oy?c}CoMZKyn- zJ!KePe|nhu`RBLw-Ono7)yjX?$8Pauf%len{NP-N4N%WT1BPpT09+lvYX55tVy8%U zwowMX_sYla;@9q7qlmAbdt8SH0D&MZx}Ou?mQ*$gPQ*BrlhN#2c36JNb~r8G*#l+d>4AYLbOi3}%4L%vr|@9cNk)%wgGFqh(>Ts~r0zEdt&^4Bstn01EZ8tF*R z(K=!RIKiB58@~+uEOmH{HiBh?%`U>4eb?>c2vFi(F~G1vO4Ta>R-wjL(DHcnmp;W` zA@Ymo?_*d1eE}Ts*b#m70xe$)5$rZi&87sJgd#+M{r4)O%vaYxw+?~I>=#PDG^gCJ z*JqgXvqMF+{!;$YQh`Ts_&1sV2MjVAo(KRSYGGtX_#N4J%6*90EOn9irD?~k^PcJ$ z9IM=D%W3*T<1+8bgv&@*X2&iSZ9DyHI0Q`p=)gA%YYc#D@mB=cpC*PK`YzflTU z#=X0otL<0EUxWaf{h!b`ejB}N{$unU9KgOH0QL;P9--xb34?aN`CT)|)W6%Lli(ku z*#sZRw5h!fkcZ_J;13`Kk6CWYYg-GZFr?ILi$Spaj5N|^P;rjgY#nfkxMare5Uika zZMuCZ^RfrO=h(RKKs_8MZOrAl@SJ|v>girHd+WA?IXLrKv&lerCxk85f!DR+w&$|{ z37^jmSHHovu#(|dxE$wt-;{ax0@$-0poQKUvqUK#`r9Y;RB)C|E4_AvKa=hdA0?*< z=wWKJV-f-yHmP7WBJG64UV)}nD7cGnImXG(Y{UH1c9GSXF7BZHldi9atr>C=wjC8_ z_6NM-cl7l|BYwqUb3E%)lt>SOmE%AQB8!&}@wxE&nD;6F5>M1~kAuLa@R;m?`yV3^ zrhaks#}=qsgS69MsVH`T^lK%g6MRFAjXH=trGEHjXz+=lg;wXTFm`@vC52*l7*Z=5 zu<&2tNMK!gu`4ycu2eX?NpQp(Y^@rG=QZtPk2mp+kInO=pQkr}m7z9HMbC9hh)cjI z5A_|4?jL5KV@F35@t1*Cx?26f8+w_bkPC`s--y*Tyfrx(wGm4-fQt!Ue zv!2zC;q`3JvP$0b;rwtk&2uS(n${n4sA=4O zXRv6AgEFG=A046D{|nmwelc+^+2ga)%-iwpGVJMoc$>Zcm>n{e@_0T`ES#IYknKQiY34q?LBAr zj~NW&Z%_Zw%=Yk(?`|NK`PVyoJcla?fV7NxNME1;^__*g-{!_7`UVftmjpZ?f1j}dsNoY49~D~M(I z&_S?#;qplxNcNE$6hy?o40&xMh+rp)aNr2vHMQ?>OgcaLhvKAE$98PfIRf|1&Ym}; zKmXi}J+hUlQou158ph3Ue`%&WI5Y*HMKC}Wv}T&@Ayj)xArSVZZ8(i^Q>K`E=?XOa z1VzhagSK`jro~G@!>o=4W;^*7Vfb_A&0YBa9fT4r2N(mhlpkcd2Q2-F0&*>4?lJ_n zeTKvHAkZKr>WpOsLv;J6=gs#2@UodaMi@#nBNm}wu(apJKV~O}#ep~${XbII4PKZ+ z2Q;Vuz&K#n2%JT>3PONq_Y5xN5ldEG3dC+8%RqLw7i=`!O2(hQ(;q!IEr|TxnKLma z)B@jXY2RIx`@1_Bf%jL4&&=6|yVTXWzS@|TBrvOb&tt7W6#lz|1VbU1&1x9m{oZZd zEtR!2m!nm?3W(dtfBnrHf`F5R#D?0`sIusiUaQK&b0K9i_#b8WX?^h&&vqx#oWd zOO3s58}I)t10X5@*v_H=wRN;l;;=#$0K>HVIv4P-8$eB*+B%z`_j`DdD|>pailEKi_uj-JzhA(*iu zYS8eEHqrPz`VIaT0vavv7*)EsWsEboDO;MkzxjBR@6fCcX^*C5O~2Q*sdEkiX7d|r z`iGw9rT6>9D`QuigudoVv&UUoFA^= z&<{vVyemc<%M82FjU^)|XFaLUVJsvE4%Wsbt9Y>A<6#VkSM( zIUSmG+ZADfdLg@Km~5%e0_yv%ECWL8gkr5;j#&c0_{kDO_j@0!@ke4IZg(q0g&ncx zsO@+g?Kk*lV9vF4L$ve2*?}xzHL*un&>@%?-bmsBHq5@umuwFl+>O~Hkj~3|&1iAC zk6jX>Wy`=X{2^^4&ag=^c0$7DzS&9X`q#INs+d!5^*v)`g_w8ZX%FABY_by8z zWpS55iL?_9d6ww;>+6_J`ix;&@N&8ST_Fgh+wdcSA@O8miGdB6S9M5SyE$>jJ@)4v zW5(9%d?jXlyu-YhD4OzH_T+VY1B9Ch0+Q&2o@D^cf*eQ0@kKE$+-9=dfk@v4@UMLV zXeM_vr20+N;={kegJFqz%Z#2;e0eF2lgG3)=){zG)jw@uN0 zWxYJ~ocN?RYn`{b-}`dDc0jN$9qnjKdlu_Z=&-&6mbLc4;JOZZm-Qd? zJ@>T_{Q!Ch%0K|n>h*t0-B36*9h{&{f3@ha-b(nc!sMpPfAzb$w(k(_TL$M~t(!nl z1*Viw$937o4IvEuwYm76OK}}U5q0a>I<(nh2b*JhcZ&#E3C5(zJqkGP@@@ShI@)9}hQu-;GasYN-9d zdQl67Ra$+Gu`110uLuBI%B+w`S~EMWSdHwwf{SAW0QQ6K>{Sty4=XUjzv%G32B|%k z#XN5dg}Jsv70sTXw1WzCW7Co-%7tHw=9KW0*Ew%!sG#G zVb7gqxu-N-Y&;BiEjSzI{l0UHYI);1mwLnsfJvS$|8#^ifhZ~7x+T`3RUpybu&b{A z_wyA@@5|~w?x%Y66xaP5Wc(Mjj_dmaY6?@IC54R5RFk`gdJFLVz(b8Z(yw5T`n_Vi}QU zu`H4;M`kiLUl7JcTSlYSnbG#OnQJ@Os{pQu{{++iZU-!k^O>>Y{ zwAY_Uqexo3{m0h}G=wI$oNx3@|5z(8{-iCWH%fgzwpM27J01;%adEWk;Lj`Xl$}0s z_=j29sS#_R2mrI*AMP5D2U@r=p$&v=)|B@o^ob}^qe6T2}Nd1&WEGJmv6k3H~2xzN_6JWnriBm zBNHZ0fyV9xKz&4>W#4W+cB9F&4f?+uEX)mlsFn{izF>erl_w*^pjs#YA2 z(IFLUWJeuqUt#=58;nI5JGb^5W6C9_(D(~ z&9oE*!0eA%dp(iiM^iY4S&`w_>7P*tqLumY)eFle`Md&Io@(Kvi@!4RW%e)F z1=}vq0MIORYH&`equOqYvq0#fvFj$|HPlhSA8oT>egD{PL+!pu0%U@t$=1_7Sp{^! zX(3u=sZM(a{P5usl13U!Ay57Qt~&!LN#MH?3IyPs2X9|#m~?=?eQxqVkxCyEPW^`i zGp}h&1z5JJeK-S}a^-&iUVY7B$|E{>&F(M2rgmTH%TNvgp+(@_N{iC3TIQlGF`>R! zYI~D4eDhnWLZP@QasOA&KA<2>j0yIDuQt%s4>s7>YFEFm65fAbf2{An#R91E{P z$Z#kSDl*D-{Y1HSSHBYw&V<3~G1~>@nl(CiRe*IqHwXdymHo`_DxzirllkApDUXDH zr13Zh#9M32#Ma`$d*S*~CDfRt$AOJob?rFW**$Nt7w{>I73NP#xs+gv$FNcRvQ zcZX=UpmtcpTJ}ZWqUZ=&7vNbPmEqmG1mCM;iSv~SR;mw9;KE(g=@a~eYDSGo^+=+D zs%#Q>nE3V}`XD{B1VBN6>vkpKor+d9Sj)ojV+JmS;wD%~E0Z7eAvI`vqd|71sy=VD=OSOmL1heM~=gt-l(7ggr}wk7g|d zF+j5m*KS;o4<43xQ~?K>sxweXw1=F_6HnOkPjCM_v#nDgl#!^aH6M<{@qhY{|K5fJN~x5Z&> zJJWd`4etbMy^X-|R>?-2yfk|O7@BSSo*w@fhvR0BTaXqX6dkjbTj?!W@83P4UQ_Gl z5&$Lvmvd}JLP(iyxO;50(AwlLVshSTDVOJ#OFAjmd0IJ9Zgv9@FLrLvNL=jl+y*-} z^a23Q-WSj)lXLq20eBMnWhCRyXc(cvA0sFo^Pbn@T$z34Sr@N_8_cdk04ymKD#Ykz zhv&AHrtpwu0hi((kO;t+LIA&SunxBg$Nu}$R+iuVVzmNX?6dLRLmzgz2T7P5f%kbX z4iXiBST^Co<9qy21xYq7Stj%$$N}aQ#``I7<^M}gQQC1r3aJ#38^2(Q4w3ekU+I%*^Dx!Yba%4f zdmaXnLq8Tme)-YQJSjtnN7dl9+h$m!|piKfx9MPCMW^4tf`eplFt&6YRM1=sW7{FX1{B`<;e((Qh?@gQQNU}7&xEpqG&8@1d zddzxedTc)G2k2ku7t8c{Br~Z;qv`4Ct~HC9Op*Yx12;m?^LqGY00aq;1jq{}9Pk^v zugCqYemqe|;59`5F4iSKZH$^fKiO>lu-!I4t!yI%0O8{SdyY5gqeoAgGrWGcdi~Zj zbh?cnwF%buOLyZkHu%SuNqDS5Vp4`fVbngtsI2Gb9*(b?W4!k7{;3(g{AYFx`HAtS z+5Z7uGRFh4iD@sG{FeEZkt#nx_fh;*}<{v$B>22b}-kDCqs-=W=a!A&hp|D3sS_kaEq3?)Kd ziT@FRgM++o`!`Lu#(NLHPrlL4iqFEl!A*q8@cMf7D2aUGUk8K2jjgAtV`c6-EN|wo zpaXF}*FJw9L0ogPht?DZa|2=9I=hU`5Xwy$k8VZh6iL+5US2T_*G)G=g*$PXT@N6% zXsuiPOq{-)Hb;NlY)+p~=syaA=eKT^9RQwu$1VWi>8&47IM8q6Prz7Z+ z5kmdZ{xbxl-0x#{5O6--{~PxdvdaB4f)oTG#3@TUXi({YwBsED)b!gMK~Hm*D1W5zQShcpAk0iBRFE-YSwUlyuF5k z-~?ZY->_RF{Uh8h@E2tn6z7s!f7C6rFj`kIG&5|eCB#B5fTWpV}E*a z*RbQgDUo5vb2W(rEujI3DYijt7~7O?=-nBdGF_IIKFizFepU zvILfq%BW%0ygCksFsatr6YD*vr%%`kU=(eg-v710QCs&$|GzYqI@g@FhB5}#3P2b- zMf-6|#~srx$Fm8WPOLNsSd<)~9q7>fcdM)H0)Y7_aM*DSfml;^GP)19+X51mn*S>Z zP`j!XfKL7*1lVP3x#uBh-IIC*Q|B7a3FB|V(xK_Pp8XLNqwyJ|y;WvC-tgLKX29&z zjd7-AcV6t$i`TbX+pi~e>FF^4j5xZ^scNzOI zPOkH3nMn5tIC+AASx@2O7t)%uja;^k#Nw-LS<8HY=G0uoS2D(dQ{mNh(asMtB@3p& z65XL-)5~0_6}K*~@lH$7J~~6}5Ds9?(VWl*N106-SIm{{=pfVR+VMDwvGEdZi(9V$ zBCnFCz6hiZS_Dw@{V9D&pGBJv9dSa$!CR-rp;ivoRVGTBLyh)Q%zpSh8ML zlDA(4|rCqBJ^S{*2!g?rTlOVa&bJYud&> z#=7GJ=B$58l8CAC+$wld9K!I{lLyJJ?slq-`tv zFed*B;IN)Zq`dl2pzSISu*+>?Lkt?55D6km_i& zv{6ao3;bH~VdbwZLgo3WMMCW;FNWvk>AQbF-faVARz~Sn&IfNEGl-XxV0O~&oM2-?$ zSsU6@3U;CJu*6+?OAzw;k`19t1FPMF&??ISJPMbfts}HgM`#=O(ab~ufVB|J+Ze&y z#OQ4ncT7I%F4l2RSSl2!e?c5|K=*z5`D*sn=9J-3r$eVkr$D-lLB{;SoPiI3 zHFkK}VD0!ibNPm*|I8j*5EVzF)f2#=Z!*xXYO*>I>(Td%7(ix7t-q|lTl~2U;I#q( zthaWid(Er0A_O>GMF7Cs{}BSf)$MV!`WS%(Cc&-=7O#xZd^*pMTD042xyGbH9=!nI z1i^2%oTS3y0%10sg^fYXL@}(BFVQhfHf>jA27ZaDbp1eYUX zU85u4EbGgA;CO^^BNT0DZ4N4=p`}ZT@TY(>R0e>zr$v z&7{VAPz_9Ew(A_h$DB0Ifblc&Qa`?H4gJn=@w(jo#9tF7G8-kKYU&>_^=I%b1*nBN zpKTQYhy`otQ?8d^|IrckH3vJihT(a=SL+Wob#1=&L`wl{bpWVNnwD7@prs zmiLK%mKI>Pa>8;VtI}=PYDKaPvc_3Y2NE+%WOZm+3h#}npLCa=eue5f>6x4pe7zpl z;j(+f=NHe1?|W{#l}>QG9GMIW4vshkAWta|5ibbBsODe9qA&w(BsYk|M7jLjA;sXQ z5~yB-z(-t95U7la*}99WXf?;~LQ&|*>Z|oX@3s32*X5dRN6$bL79Ri#0C4pMd4!gb zzL`T5$n1ABh(zJ8uK5oTT{DCG*FLTVggvQu2};L?*Pd&MqBklmYP75=W~*qj(C4}r z_ILu*q1F~6bd1%8>-+WauXT{X8ZXaoS0Slm3^nJGcsD?ng5IHE*V%V8e`KO`jnkm# z?%pzD0kIDM%65M^1dI@|+7U_CUbj;Ub5F`?9IrfcEW4ebOuw;e{^RMNogh3a064kJL?psMY~lV@=&*ieli#kIcX8?K9439g6lcoH3?x7`^lhiQMXgT8>#SxmaFA0ol~)4=LnIVx}Z4?4>=?4uRt*VPArvoK7QVJ{|)9BEW(8i9C*!$Fo%WIes<#fF}A z%-7CUuyDluEJ5bEWvpeArV9-9^@y;A?|h!R3>qnFci-#Z9Xz_;sreG4P_o`c@wv+t zRP!^KV;usVIzKH!pJj422_K{_NDAEXR!sdCUw`?N6qsVr74K=f%JbPF7lU8cFg&mK zzMA7@mA~tiyR5^8_v*RFT7SfV9}#LwAMxp@ej1-V{W7!wJ?f2)m{D#(ysx4mn9}xD-(N`fO17s}KB^?2@1wFA*unw;;^qtlKL_UALMi5< z5-Jk)bz7(qBRsQu_u-aWfcDmOS|1dFN#PPgQ~`k6{S&nP#fum3>2#BbUy$({X8urc zBRn(3%wGq8jKv9N+tR>s@&`Q}I$s9vKHPo_FpqRh&JxykVSBPTwP5(Y@e-ZMrw1+zfW1RZ2_V-{_kN-!_F`DYb6^<*s zy@3E=gZWy15Y7JtZU2PhVy(Kvz90ADQ-Gm~O9Zei3GM+_JC>Pr2%$R7tTBi0$j`0k zqGgQmN#>)L^{!1Kls64v`TMfVxT!&vp>nOfT2T9eT~lz-#2G?VY^3dbnWrePdA+0E zvSp%4-DEI5BW)g`lWouR5vO%QZO-Qi04%GHdbKXpmkUk+!yr~>(|V?^^>~woyy3L^ zu1LM@7n#%qABe}Or^<$0_PEO(8?3Xw1hnv*Y5_neMO)7C3@4T{?%qrKrpdJ${xHE@ zukh_EevMW+YJCuj#zRRfx1`d(v>AMPNai z5mY4QcmG(-l=s3bNyomYEcQP>KVmg8H5X|vH*j{$$LJ&=||=XLNQVx89mXBG53;PdFQ5c zzEAHnw16{~leS1fufrk?OnEz9va)rQ%yc{d4uJg)!fCwk7((`dDvtd=yRQ+iXV%*3Q>r5vXf~! z02wNEc6%O?P(_BdF@+O|RbOEUGzk+}&RDAy|QV8|B zjK?wUpsdzB2aN9L&2BXRuJzZ`{{j9Wp0DpTf8GA2d4bciW1JBjXzq{muf1;%oAz6r zxiZveE6iallmeKUY;n$X9g|?@2FHGUM<8IDJ_J_Lh$=8>6-;A=(ji>vM!OiR;51e9 z>#R2h@G6rT6LYQ=GTyn+&+I)dn8Bnb+3n{Zd_%+0Q26EO*iNyV?SqqlW+-FTu}lAJ zDM7Wx!7jyd_YHBRDc)%4VQ#K30(S_ai#nEQ%#Vqh`r`<$+ortucxh(P7L>i)gyFS+ z!kEfzQmRDz=*CNUqtz{m_5G5IzP!>-GS6B$NTf)6IKKkxWiq6m4w-2Bx#!VsRF9wF z>=DLZI$$6G5MySUqY@RfFx?plGL92_=a3Ez6Lrqs{i$hQk%re!22Q-8Qu)P@=)2l$W34|U`~9H+S^tgzM-1G(|Fc_pDx*JU2Y?AP zd_40qP$e9^Rw!^E?s5wNRU!xxgUDHg5`+YSb%ys=9Qd5!ZCEEaxL!ptjTR7wV2*F+ zruh*oVZ0C{<&EPnrM0ZzoIWb>Q3$y=ZKE{zTA_b!2wE8r6jMTG!dlVUw~PmHi$4Ea zUYz4uzMUYPfEXMdvt*%R&1f_ZAV9UsO3q^rcdZiK&P!FxnzjBA0BLK8+M@%u6FzL7 z?$4X=**ag(1c>5fo?Vp_fhydV!Ae{OU!i;;Pedxs#XwiK<{_ilP z)H?NoKe}nU&6s}xo?uL7y}yjVeMO81@&d9o_xs~bwgBC#=3j?-XFFKiyk^`X2$*RB z@CwcU!AkSsbhCNfZa3Qq0dxT<>%S3KfNunf?<$hRt&HUkR$o28B7ickj~LM}m}~!a z@?!*i3i(di1>$h+xOwsDb@R9HpEs`_GVam*AFneLd>Jlb9V@b zI>Ms~zGcD;$b_hDAoD5o#>#i#8K#BI_cEHSJDZblhv;Fx^Cx%)gjkxPxSiZOOqDn- z8dK7##FWPhl<%tSGTg6a97@h`*cbu5%>T*1D_UR2FLP=)!cR~0Q#0RV#~uVeGLK>Y zX-k>^F~afjnhkn$K~$#2NsFVlvpt~Wh$!iRlh{swL^y>11OCR$O(Pux(ryzhlq%kUoB`($fg@+8jkQ%QBUhNIR+@F318;7w zvKau|nIagNM0i2w6=p2Uxq=T1d^6{k-9PipUp-!(d_}%?o+V9b2cKQM9z6PbP95=I zV;FYmup@`(*4xepc93-`^?Fx`6px1&Qx(wP^Vz$S`;_~R?Gn}agGh`4dZf%0ro>Ol z;r`n%+5*B;K6+i;5(rrX=4*I^Xc>Si>@3pkblQ%v1732qJ{K3oET zNv6cc1am*>Fdc(UWcZ!-Di8^~o_|c}(+Hu+_HomP5RHr`ltJthOR|_UpW!@jbcA3+ zvpcsj6xl&^HX9IxB0Z(@Upk1`m5i%-l{f(Tk8%7r#iHUNnv@^dGHDy3%Q^yp4cc;@ zDdRD1y@54`P5_Gwz}kpGMPIr`@62DOL9L-C!ZHf4aR#OU0H{F#FvB!>tvLai&o|xD z3!u>fpjwD%h#({+OztfJ-r2q%^k9K+dITcTDI7{L?xR7CgFnYO+W(d@e)b3UkpE`{ z0e?i(kL3^M+)*IGOsqVC8H3q({KeUyM4OHP>9WH7Q?fedE#y7(|3O{#p)ZFSvpd;3 zD^AD}0LYZtz1^M`MJsUtxZQ3v4`BNh04Ts;gQ%9szRoNn)Hs$Mzls190%+Bv_Fuu? zpPHYW9j0`IMV@7exjEowO;_Lu$w#R(``e)`+1k`F8ojZi>O*N~&$Q;6d zLdJj@_1DXMi1kxHRxPKE2fyM_DSNRbJ zOy}i~P4nk}!V-XaoGk~l3_wefEtvlY-Y6mXG~@_rsLAFZgVow753%a zrlOki87ng!m|`WkiXtROtpIQwys!ZHk}#9z7_z~m;)@~7M>v^M|*W==) zujS;zh`&?SvQw_t+vlq_?97UaeB)2V-=BYVd9SSaWpQ~+d|$Hbw*Wm`k(e`bg;<$Y zCv^96)w`|Cn0BU2)*b5iRugc^1YyW* zj^YFm3Na?jyd=^K6-+5_x-1`4pV}r1Brl>bal|p2E~MdW5NvB6iTDZ5Qq~C-RpVd( zO7=F$GF0s9#&E5$Ohbuui|6T2I}@}ZoYm-cD1ocfy?^5qTR?(RL6n4Ad;vg^YCj%p zA3XfKy(Yr6(Fnl+pf-WvivJBvvGEU@aVQN|&oe&l*BU>uc=w-Qvjv<6oaUH+6ETT* zOF+$O^(CegK$j3{`hVW{|25O+HM4M@E&6}Qv&PEo=s}E=zg{44#`@)Bobw&&0B}ZJ zMQngK(=(j^MQ9|i;SwR;@NWXJv63VjhjH2FUbKA;gwD{y>YaXv}Y8 z+rZKAZ^Yjd7oonCiIIVlg7{M(I5HSuUe;TSk8kay=2o@+YX1Ez*QF$%uQaz-&0llE z70{fxhe3n@;_jxJo*_}z{@$*JiffVRD%o${57+lVAc7|jpQ9BR%SUi6PaZtaY%Rks z4#;)V8D`d>r!4O{Cyfw^jG!Zbq2*2SjDS31&dz; z3sKW2vmn8GCkt9@ZN|3 z-jsCMU~leznX}rd9t{wK;5wQ86P$n@z#!-#Y@dE)XDHSMV;z9mV5?IjwGLS;Dxt`A zG%EJbGS#ot>dyT-Fdd^I9yuC>J-1L}nUBkQP$4Ep+mFU(OdO4fEUOt|xiOky1%R`$ zvFo*2s-a17{Cv<=ypUm}_TTeGG@tu$b1hJZ)i6cwsatZM9kV0L1Ro;JA)UZ-fC)>8 z^d~Yy>o$u8(G*P@8Z<-z&Ls3;{_L`0a5i=1`e*RkF)UNRhtHS7^cSn1ef+NMPWGGE zctIA;WUyKGg}% z(3zba0aNFg`M$#e<%oH7jF4g6u@nHNNOy!`s+i|BuXby;MQ|Q5K^TaFL@v~N>E{{B zYuO_JKp3x(lrfz>(eb9(DWu2ptvex7f2-Qj)*XIivNd22BN>}E%CP#w^F@R8Cj|t~ z-}N3b9^KuSoi*Jp@TP9Sr5T;V2owa}WD}f^_P>F4knwk3*Fr-&W9i%be3h?tb&-C` zM;B-`Ws9{$yq~}MLX*T*lI#vL{ zeQ@iD@juG8gy2+0eWF4lwgQcF*Ae5xb(B66e$KEC!09uRx{^On(og9x(yZ6z?CoFs z)OYRYx>aHir^1^%NofJV3_!Y2G&YUZ;dPBg(+u2;T#va-4S|1J0)*)YsAGL>J~h5w ziW|Sc!|JO^)x#+?QD?Pg{g!Q4mQtw>6uJ3*F(F~G_IS@s{3z+q~f9~!3 z@b$Goh$cW*Ce5HkKh{hj3<(cRN+rB9c>@D2re!UAwzlk1?9CC{2$RSR5A2l5)O1X& zgaKIBTkkmbA7O0}K|rvE#qqjmghnh9m5E7#^vJ6=6Uw9$Nh)!VDIUpZwx(bq2;Y(2 zZQOR8D8ZK@3sNs-3Ng#GDYkLht_zmGZr3HD9wc)c<+nx#0r-8j{Ok>?`WIQFv3sFU)zZ<`8FpZueKl3+FIz zBN)1oegKfI zDYolqXZQ`7vW#eoW_&`d?7p)}6(ugx$w^`P3&USD{iGh|Uje`oT0Fh`pKx?pj{*S& z0Ebf+1K^SW42|>|=KpH@=j(hS(~bi_oqJZtepw>oy!|2Y;_JeiaA)1A??||G8$g^3 zj*vEw!ldxbc^&w5-tQD}C71xwchpPnF5k}#w_`}1<=>fZ(2CC!pv>&^pADK!=W06P+d35DE`H5bQRQ)V+x zTYq5YR~PRNzR~yRqU5#-jmsDk#!KLy@M;iQ=E63tooO1}ma{Sn796uhvO6O&7Fk5^ zWWY1^;H9zSF~Hb^wTV ziWVwF1d*);yW&#!6{ z3iOA*Q1X7i>L7^Tr2shADf8OJ_L~~(NA=oKD-b|!HGioO>oI`Dn_5qe7;t`+r24@p z0G>~}yph*FxR~Xu>-;Kym_P+i`(-R5f+?eS!nM!t!&lM*!8ZR*!qUH!q2!!e6;1_U}8jqLYG%}q&MkDeR{+~7GhkQ`H z6qOueqQ*NiG$Peu-QQJ)PrdKJiL@RhtMi@{+7k2C@gdCC@oBShJZ~N#oqr69++>_lyvW9R;4VQfrLj5!K%coX+nZ93Wj`~7H^A72&sfpWu0YeILuAmyDekbi&T4*|B@D5P;q{;{L!yH~*G7xeqCFh| zt(geCp92rPUDK=Yq%Ej}+EqQfyN27b?z(&XY5Xl4A$-p*NXxSav{8!%2tA08kM@Xu z0LMfKXgbu<>Ly-v?si#8%EV6Fmw8>1FO~%)Ip1GtPIp+>y<5Ehv*Z{)xFsA<1( zy}xV0X>-@?Ik)SaZqfFaW%et%C!7V=(jk4NZQuUdbvrh+p}t!c2VUFvEGuvajnM|< zYKwb*!eIpCKiF}&LtWsa^?qk>PG+| z4HvI`RbZxLUVSKK`G(~ihQYPvQsCqG+Mv%>8i8xNx%sRDBM+OC{fDevK?tFCA1UPs zrhks0Zn^;-q_6@-jsgG`N3LwpuS6S*h(&9Z%x#*!d4{FAjq}r)tDP(m7@n2G`QMVD zY_-6|ksF>z>XbV&0h;gCcg}x*(^sVwjBA+vF-*TGQ+};nD*(u_$nmE0zEAHnw?H`T zK2PukGdU3e)blVNSYwI?g6Lo#y5mR9**-+p(GyI~VE%CkIO6_z{~1I9FaiPTHevcc zk?Eg+69kg!1K^fq#XSKU=TDNBu@{!!8+?};#Ppnl<>xJ4wjhLQIotUg+Ad7s*blco z#nH^@DUZL0*?t&P#7?5=gpXoMNv7E%hk`@^ab@oBE!wpninLv?s^|56ob?=Gdae2Y z;VBN+VEVC|cnYEZEmHDrC|%9}U9Yo$8IdjQGh~Ye^YMdQ0XS{|` z|7r5N`NQ-j8pGpe2V&$DO~mf%lV+E`JZ2lfR?q(%J)vF+4?Fp4s7PM-KeRx)fFB9P zz7GO#YIF_}I6ePUIZA-33%{6_D@BKH^%wjlsO)zZi@N#Yi?8hGhz)M+Ct7ehBqL1gt;L zcAEcd^Iw`>1VgW3BEsmST|9n>!@s|O4bzWh08Upsh1uzpCVdtHMVIlfkU;2kN7=?wm+s zPQCG*URFoY1d6@<`+UKQI%eR!!uSKvy#SyH1ZYQsB^owKZn|Ao34D}SKBVC9dbi%M z$3BbYKG*gJx!#^z;_N9e#ld_y~A`mJEqEx-UfErCz2bQuAeFL|cRWZtGNyY#1`y z?2vVPNWVu%NbAw2tSSUxjqVoaactm2XtCab+3ic`K7F2AL(wO}pV8WUH z!Zj7%MPvA!wZeOt4DYao&m4x}fW3ha*#hj0_5ZC}1GPgTbO8_v4TOqDRd7f_u4E) z_dJ@$1_99=5B;YBC456q`4qtsCAbdk^f0FNNkE(G z#;ZMWI)OWwu=HR`Su)=vRd7k#T*hJkhY4 zdC>P(H+k@eu-0p1wLEY=ddm(Ir~7No=^mPYcCS$Y)0}SM{hz4cpj9J+7t1bP8|^;@ zxK_sRE!EfY@UnIg{xW}GsAAgC4y5hvz|dz1)fA{{m1X}B+){7C+&z1I+^l@d`4+Z= z&~QNo_y;*-XAt`?P9qtvomLxA9CL()BZP*k7rht1JSs`FI?-oLgij@p%YP|&%EbFF z{V_x95j+kJINxH`8J2#p8ILGC%x8oZ(FngHU3QPsBA^UEN*H~UNo3rU%$Evwhovff z7gzLIM=aWZOUg6;-W+}ZT&TPrlguJmqhYOv=e{(2e(~8Nk-^Dz-Wk09Wlnn(@MSW; z86lEJ29SMKykMB4XfC^l}991^FzFZS6!1)G}>UDkZrj8?#WjL@t=X2NQ z;{E&Z)wF=f+7QZ(c}qemlQ}aqYfarEP$xf#o`DM~3TXo-bhrOG<{E;d>7wgF?+g6V6&G9OTip5C!Qgx zaVdc2{|AXh*LckRGb*jKss=$oh{Fg!1sFTm4*w7U`P9;X1>dLf`H4`A`V8Ss#^3G! zA^^Zt*ma579|27&i7d3mk7lZn9t0+83GQt<0}HR2u7IGuXhxXK6d()%LRk`?m8PuY*5H1W+hZ zp)C<1?wGANCkWui2neDKF&UWeF#@zVAOI6?nmU4Q88dF7Y!G0~Q|3RNULl}7zWkST z9IV;(fN%ZIB>=($LN=WMHq1?|0i=p*{DC0_NeoNJ;~3$y7DubE!-L;b02v1jl8A^Z6?t>u?B;{{ z;4x`bnSaf(ae|{+>x3N(^kJZW&WZBkc3oC|*~58cEh?ALz}r6r$FUKn{}`gB<@}U> zYdKe%9=NK+q5ZI!@Rq&COIAMNt40Tt%#H(0FI_IG)G?YK(pfUoOo&tb0B8-M^FK5( zHoF40V)l>bXoaW+05n@dKmHcAz6(IPDC}2sQl~DCuBROnCprPt^M5Y{SYa0N5B5KQ z`Vc99VsF4Aqq7jUUa9@p2Ec9nP7u_cV7U`#e+W&FiANK5^1y-EzH!DBwhl>SuP$cIs{9`$Y3NC7J&dj{& z0PO_;RTZ3Z4^s|ogz2}+e44LCk;Xw%HOWhlzSmDB`G&NDYSG+w;4RmACpuB+);;U| z1cDmvG|S%~FU{osW?JAP?n}D~fPMeh=Q8KPo!nQrrd3NKuObvs2%sZZEd-Rq2i$8ufn)!U`+c{gvI z`}w86lJ~pNfO%5yT|5pGsn3S@-gW*V@4hRITe%NZ+{s{rmY#o8{P#8T`<_(+01JT6 zhw~o^>JD)3iqstF7J+|>>hkXJi;KlOpY|tRCEE;11divAZ?(!NWpw}X^0$D%04$2w zXH4kX?nO9Mvm$U}yngxwx(jJC+Y+gT=`aTq>CBHI)b?FA01WY|jC-_;N`fV11#yWR zLD_7WbQhW*@4XA${Z2XqGf^eo69f+89B~kCuo*?H5k12^_dgaXO50Qw#SFfDiZlsw!OicmF>E8`&S%v71F&} z0K7qepIoR~nj1gLO2|UUGFR5dze< z|MZ5x@wzR2f|co4TjLTFElj-UISv3vr!3Jy!{6ZiNez$dFDEenQ`S$9VcyidOk(O^ z#!(cC5|KUHS#-(rg5T12(I*$ssf6iEXKd2r+3($M)*PGT6aniRg!OtH{c(gLTtnaB zJi=QUn`-tAQV`YApJO&cIubc!B7TX9|4TId`x6%fu-zYC{`ZM{>&&CuEbM`aSSXy) z@<#^DR3AFuc@&s&-p<@DynG7G)NcpVXwvgO`6!&yDW&(|X#(>4dKqJ_Fd1W|fU|@S zVIz(bctLF=mTOGA+3rluv5vvA>QAxy7zxmYb>PV{~(oH4U=EsxlOXS3_T z6pIUexX9qubC-14zFBHvTlVpjfT0%fS9nbO33EM6I=2g#5wOtKI$C7RHjLBIGSF7( zSOr`BXV~{+$ZVVB>CwK31Vay3i~gru&^vWRn*k8vLx!lupyRribY-J%ey&2ANX0eHoWGh>x=#~hUyGqKEorxlz;tuf)Ot*$hy zYxp_A_raKV3QxqVpD8RD{#vi(%NVdL&fR;fKsZ%MsJ!1>FL0ypoy#6w`s{u0Uz*4= z+^l5wGL+?G%TOC$2)`KWvwGj_i}x5Y32zAi3V=yEJ2;hs^`B;j)(Ia#&tQrp3P8>w zn_x*?n{`=<${Qd3>lBZH4gyA`{4uenbeNP)nG7Z%R-fHMwjW*I`wwra1u~(NHq2Zm zbBT=&)>w)Z!gRp+>m2Y92YhILx})zQ$S}i%Qs~eewd~h?^y(Sw1z|qWCS`X3gaQ-x zhhF&(CIkmkZUZx#f~^E7m=FC0>3^VReQC{j*CKQvG#w1;{7;_)arlq+bB;+{ck-8} z+r{}!$8G?chf3(-oTxkd9SD%&xWYXw8WzY^0fA<97UaE|Us|GaQ>-B76#+Yr9iFt) z6o!9gZ>L#(^>Z`X#Ww*C0Uw-nc%b zm74Zj{lPLE5@jk5+$M}QetW>f{(}d^-{krbr$nw1J$r=bY6yZ39{>@`gln+0ecRu5 z!M~>TrOI`3x&IQUmk7Jm^kkih%DJ4o>yY@BI0gOMpo;I`B^w%y<{|?uiZ%!XJ z+bs_NAl_FX&Y$EA9~;!yQOTYgoN3tKHor7G%`QGuj$!iE{+~d6pE6$m{OEb}Vsn>q z%Sh(>1gDTE?Ao!jx!)Z9hV{A->{EQXu%;mPjANI0KVp8u0zeCN$&&B{z)@&Ge`4X z9sx7VBi$J^6UvGf9}nFLyDGVa%yJ0(3V9IZ2dJ`Cw69hAnn7T>9SiXtz{$fOn&t;4 zuLEF1D>NNbAhl~J-?0>M2WvoRL*^!jmqLIEbiwxKgXSUd{eb+|R@e~SD3MUXe-*S% zVL%F@QVMYnvbY$_q&TV|YSaj|ct#dn&)8OPegMJx(_ipW2;#!~ZOaY;ZVT0I|Bf;s zZC-0S$_Dh<5uQhrc5kLEk`FftvWhr)^>NA?O*V|&bDmhgVzWE z*s=>k_2K?zvwij$0)D004*9MvfC7NB7~tL0&W9K8roRAvK!U%}DoHlth`xLcwdwgj zLc?8%&esS4_7DIZemiXr(Mla|K$Jrywokr?#*lz1mH@HHNWtjTVA69vebYt0`{`AJ z#F_|a!tovgfSqS$n@N|K#M?gt05+Xjo%{>hQUm~)|Lc5dOkYg5PMX#4(3ZMhlzv(; zZ;T_INkyw`Hw?RCcz*X=@$S@sDJ22`G_mv75cx-pI?h*7{EZa=9IQ9rF@HQk(1{oz zv&IIDuAcvyjH2LJ;_U{;>(CJhGz_aF;Z+4o!tphex;ce#W zIk0lNg%6M4;r)LN&;AMkBCrKCNPfaJ>Xxd)OJGG90i4{b)#FWuObw)K7So5!`3M5a z-r>+kSa{9xaWUC@jdIv-CWsfMi2iHXXxLM zAWV%oK&C}J;20Cf$?$}cwLT&!Dq01WL#m(GZ#@k2vn(=&Zq+Lumg&}YI$QI0Y|(pm z^smk6HP%po&QYVvYQ9v zq?OM=^WW0H?Gbd{Yw$F?f4F2U0w?=fp_9Tg#(ij~T42lSk^~@R5u~l2{2gfk8~ygj zX50ajX9%aqr!OOz*3?9hZu#DFK6*NB9s{F~$zv6Z%~dP~9&BSJsTBYM0OzyY4%Vb( z!+4<{#wfyQ%=iEZO`NyNd;RI4T$R_O(H6miUsm|b?$wXp_pH9N)W^Fh0I<>D?$XlC zKD*c{!|UOB?U*VBV%S|4%*ufZkU7vDv78s{0FD;LXL-(%AcL+6-)#j;lx_dg43voh zFag<=d$*PAeY#880>L1{A7HEyAZxjR32jn=i7pahUR-OpofE7yxvTjX0N0JkXN5NVEne%-8N{=bgt|2j(~)>yB(hK~Y0cDsJp+%@5KWEtu-fGD=-v@d)6TeW%}3AE?`O0R^s{`r?8xLUB>n=W$Iz= z7g;cXW@W~9V4KgOA%9`4Apme`3`2Obf#!cp#sJN!yM5T~MnHcoVNs%dBFXL2mn?g{;>`rnFh0@ru&}xOdeTJrOvxd zqa+Ul0-$hSr_gjt4@Wt_=^xY9!hmD87<7tt2^wuPhGAi{r*RZOb2!El07qlZ5rR~N zz}*fEG57R@9 z%m{T!S+!uGGr+}VT{TC99d6I3%a7C#+^7X-`=G#4(A@jVN?lxXGFRxdUt+5jfb9*^ zZV{Y!YvB4Z!V?_=Yh5P|z}y~TfDEF5vS_6DWp@AU(iRAO`9nK~+3ep^LaUk9ROb9C zV-z^R3ZP>dKqqrdrz`ks@eLxo;P@;;IxJ_{7BJTwM$llRBk;h^KH$SQWEDOGLE;F- zPRH&5&G8G;CIL15Ea!{%-=kJ$S^^D&#N4pI&DVPh3>-IFj7l#`9}26lDdUK7$Bq>$ zky^%?OA~ZNy9$2VWUhg9XjY&jR*7pYA)Hc<&$$FZ{wvj@Dp~@hefUkyX|Reahs`iJ zue@I6{RWRp68((}4Vh;b@4f5W;r*pOcQ&{y!G;%-KQ{RNu=DCQBi8Z2sv8%m71Zjj zH$g~~c{msPqEsk6_w4pB1obL!^Ss8i(5JN0?HBz%hZ}DJI$Vq*u^~bbRNY=r%G5Pu zY{?f%HKzYT5Uv|^k^k8$$c8!4T>^Cc!mSB=L(kEG`>I~!O{{f7HCd$qN&E@`>yew< zrucF48Un?w^;}Zm&H%1mjNrk&p-od{qjbDFgi?c=?>Jsb6_LbygXK1Gj1b_>aWuya z6HTpKSWRiC>B%upyIAv2ou@o=1w`@IUA6!;6&e46aJ*XHKrcrSAfsUfwM&1q?w<&( z%#q|PFKSoB<`Cj&hg|<3?Sb>!7n<9aw?#joWEIXN$Rx1h>`%o5=Fpgfj@dIkPBC%f zUb1xn06+jqL_t*aH`de=qHSU6Ous}1rZ%t+wTs6OD9Zh-x6=Z(i!(jRtU9l{41g|o zdY!=7&HAN7GXBmRb@@;oo8s*19Wum2eI_aYwm=Y8Kh^E~qUO|cI=~{tybt2dFzbrf9s36MbTO~o6{uuzFGYFYd z%b|u?BrZVQ&+XT0=Br=o`?|hp``Yhu$N^j7pk$eDX>;0Nsa-mWQ~S`*>2qa93&)%! zAsi^=8M`!-7m8Ic_cMb)vngeiRzjJAG|dM*;=@=s3PhIx(h!%Mp+Sop@sl{;F{H(s z0)QhdMb5Y{p`gzW3u!r6B06K~(F}N9F)}WviHu|5>Pyf>P8XL3+V&mcR9>%tChvE# z!7g6EBboQ!epjj9`_Y$pNYCHtU_-yVtKaTiD?98Q&zYH%hUfne@qZz{9fkwwtsLLF z!S^O-yzJTA$zS_UpIlAVV`2VFPW9Yu>pP}xN$$f}+5+ilJ6!D12NAvIX>7}sb(PMP zZvPU>6zT&8M5iwuds1hz$0Tu#@Sw#5zQO=^3~&pw3Pd4V*fAh`J`aJ(Y{e&*A?4_g z-1ENpFmxK$g&03st0P7s@>`<2?RdGyu1)*aOrrK7AkNK6FhRq02*opQ?C|0 zPHV+c>{>H&`!oH;$UG}tu|B4ku|z{xdMwPW_j$pw7Urg}v<;j_Sd_>cw;RmLGAW4H zq(=#|bx_iZCcZ=H(E<-6@1ensqeKM)wf;7daaiQkqraCX^nG!$ODt$nW2{Of=gG4! znTQib=XUNZ1PG@|!o#%r;y!$23se}ap9dEEevjn^w3YOi=JyI>G|kZ}hCWn=m2Rkg z%V)9N@pGQJqle4FiU5J-n7kYZj|z}s{6{eU?yk|fyN2Hi|Bej>WHR+GKS?lebLz)L z%FMM#8UMPxQe0Jq2rRql@DY`C6#%eouygDZwE~?|wyDe2Jg081{f|Yo*?fjjnv7rm z%~!h2dDS}AqqJph+6%>!$1`}FLBWLkCe%;r9j`CmtIz83s^|5+r93)g+~r{7U+CXO zb!x|W9G?4v*G{E1CBd{^A7Ni=?uT=kS{wIv1>m(P3?6 zyr)HgbAhYDjJ0!XWrr2Mq2k;pv#c!;*raey{#CUoAUIrP_;eVfS>P7tg6GB&#rn4pFp(yhFd+$-(<^@+m+`>cBS+5N z`fm)PoI!xCL3pl1q|JyMXlXXsHc6v@QOo7Q`|o;o`4^w-uFYRHj4}O(xsb_F|Lg(` z3_M~1pu@!u6TX-bDgcm3Ty)~+D(zR0&qAnFT0ZcvHb#a7v*%H(`STtX)v3}z^RM@I zhGKkX*z{SmP3JhSmJ_tTg3kJgD%h=r{;;@^W{xsi67rA^L#{&?Bi{iVA2Dk(XU>^l z&Ui^Pf4g*y0QMBdcfTi^z329RCvbwhtm!?(BIF2<`6p=qPF7gD1H<2LlhFqF9gTk& zeTJ&ORXkTvw15}k#$ci~=Ei6EF+anwk#dh8%9U*bDYt^;2!4H4{%DJKg7VS=M&U_^ ze}fJ!<7gEev;r=Wfks%(nlWC&`Ps>HKBvJ?(+J!L>A26m_$*u%nMH_6J|WV;Au>7_ zaYaQ+DfCVMm^bB62oM!N*E0X{Q$RWK0@01YXK4!RO`8QZDJWseP_ut7@Lmn_bvpZN zv)v!>3WLU^X}U6RSaU@PKpS~X8`%aGKx%6D#~W<{Vah&_Nj|`>B7>fZ`9CIIEwC`x z;!)vE7<``bjRpe~lnq>z;&>2@8RPB_&@%2N$ApT|VvL0`J8I;^Y@uvktlvMS-__m= zP~soUBTwS^uw3?k;ND^ZG=>Pwc;8FkF-QyO8^AI#cCw|jR!0aUCyd7l%hd|wFY`|l zi@B^Xe@W#=eyy`X{>I?1xg;lkXu-%-s9EmWg!NfH@@N?3@eEXQ5v+a9YIq!;FJ8WI zQs237`)*tUR$pbXQ_}x~+6_CZp4X$|IRya!Jb3?|r+!pEG>am2k}dboP!sidu@HIT zCVpZX^rjTq4iKhHrIC@jBhjoJ$HBWC%NI9MfcrF-zXgOo5dgC^PVI88c-hHa&%hfv z22#`RIU33ir&HbfKBTHl3yx=ariNyWDSR7KFz!!qASm;XG&uMK0(8upurM+Lo-=U| zWa6O=fVxgj8U(~Qh6b8$@eP((#VHj|tyUrGTpNANmNyVVxQ-?=M~kRrOv6lxZ7xEv zb-W^kK_eZhCy}ygDcHa?dxGYF1;T3+E7SmtXXxA@T!{y2vm=sQ> z;syRt^uihAhb{ibH~?dzGqDH&#)@Gy`$ypB*wM?sf-(JOLT$M!`s*%D=8?V$ zoQ9ZA8vUEF9$TXhcUn#4x;rh;|c_fuh;?N zHQPWQU>)KP0Iv6s!@q~X6|!1)Q<aso8%~2WP9U&BvLW173zMOr7`@ ze5BLF?$mjt4=H24ASsroWg9^pDYpH3as>jc$|foR(CnWWt1jxk5CAyA^ku8{f0OL} z*-f;7Fed!j_HMD~d=YqLc_q6sw9pj#e-OV463+K_1-gbJyW&wMiM}ifgvaYx`RL=p zu|ax)6@<#;`K$7-LN9jJ=-5t^EkaPzFixcDuo?=?EBs;{ML-ro7#Sxx8wn456G4G6 z=QYp6{F9;ek!Fe&DHftEKbjx}nCdLrBQ%6NH&3X~C^(DHZz&9Eu5#`#<)w^c#=1_~ z6Z?Bw2Gkl}DANDeU(+ZFzGkS$i|2WG;d#Ax=Z}KmuO-wDzIYV!D=_@?bsA#q_?wiXC7VuF;pivWP0mq{^f$@t?;#-mR6VlsyIA1|<{><-Wz z{P$+Gj~82a2GHCrp37fC%lwFG{D0#b#sw*~2uep~({EVo`V>U9#dr{(h+{ww)q!BN zR1{^3<$%trMre5E-!nl&+sTVd^qjta*0@nY_ooAj#;yQJvm=;z{M)Ac;opOlKyX?t zG#m{%cym_oeCgwx5|uIUrbEYZD)v8{A6Zv?80P-~Li*Xt zqvqB2j{PLRl6;p4w{L`V|E}HFU+b@Z~GUL?wmbU`@A+=e1dE`ex@69i zakN!;3qWzMOC2k&v_0#P~Ld{r~D(NC>;XAQLJk?&tvK$Z?>pc zzN$a}(w|UqTQ#AkeDT;n{(28Uz?}=}=d~k;uMO`F&wU3jDdCU(@x6zdfvmVW zMcO1#_Vy?7e#^CE$zgSqA?f)uNZiX215r8fl%u|*Ryb^F2R+6L-yG*5te13<3oTtvh3D7;xGM*lW?= zXS*l1Fw)nJrkpx6avoNwY>0MWpzEc>k$6)E6%=a!W&RZ|w`_~kVu3K;foVEqhk(OF zh#>M85g|z*;Yq!Vq@Y4`lIOzczBBFUXTAF09NTh zVM5JC2xBOa`|trRKx<3r3tx$z181(&#QcAZ_J7yZ&doyE& z!!2u5KA>XvuhtfDK-Cy?U9M$hCCZsjx;>cnYUsiIILE5!ObY-A=@TqLFzSyL&K{N@ zFQ>cB-&XPJzlvCnb^deUAeJ8pgGS$wD9nILZ#DhGMfZp!bLLp>KSI>N39#bSzL;Z$ z9pkcvz%(-_^vHtQ?x*qa!Tu(IF^msqfh3c7AFyv|H%R{yIW)%*a~=3hjIwK5dgD z%L`xtHLdGL?Bo&?J0=!2xz6jBM?ex_mJ&!P*4Ge1Yti1~RRJ1BM-dJ~nV-^6ta)h< zfN7QoNt}1?^a6;w1V$2UL97ch_C4c0f?)&&f{;#>BP=_H9%DI-3dga_2|D1tW4mX4 zXSh>9w(}!VnSB#h7GvD?sWHp+I?qU&~^AEBvv)LnoaJ z!-5ab>r39d?0$Xj@v7&;cbDS)E(ic@)CyUb_UND`>$~0>c1ArP9zE~T&O!k2Y>?Kw zPy5n%2=D=z0Zs>!14uY^4f8DqhCSK9h>^49@Z8AIT|_(A3Ocu3)o{FWAHKF0NT>57 z5iksuKyi=aAPJzv312NH$CxOp?gF92aUjH3H{XZ(N8*gBs{()!CIFUn6f|rhg!v?N z6f12C&9EZu_UVZXI_yu1glz$><&Ve}UVQjp!AL zE(6d6*@(F@*JlvIb6}uT2%v)~H389(0Vg2@tn1yX?-yv|H(3gY3-|&?E1WTgw4jkg zl+Z6r0JxXtg?OX=$LzYHB~8YLDf&$OaUYhd1?*ymPhzGZ&*|z!=RLOWQV@Wg4N%}* zFmRdy794{*;zZYScckV-K?=tooQ}PH?f34jWn1(**zT5gm zC{Tq%z=@!epPYCx2$$U(JpL@FwG19Z83jG*@#xt#^cDh zvAp188R3y@|J9(<-b`d9V1v_8W31V*8i>ig%MDD_46_3c=Q984xV``$ZZkNKTKEJi z>l}-8ymL8%`!>ds%{uWK73~lLbXq$o@Bp3?tOm)X-TI^o3gkPsrR}gz>)2*8N11-p z6>v2BH^%WFZB-M?#M58iA8x({9Gd}Z`nqb`)o_4yA#mt3obS@Vk~uCLau8$-NA6Yl zPocQ9yB+@~SN(})EHIyp-7*%1j?{lZntQ%8a%s#df+d%G>U&}eAX$!#0nVL}jKT2& zmYMM5bse0!$8`$S9}obHT<1SSVZwl&0LxkgX!?&R3Sorb`{C^c$BDsOmm}vkAs5Mc zko^@!d6oo<($~ZWvrnG9$*O;mL%rvn;rW|4&Y#tH>hb*3CAtDi?rgB*gwz^r>;V|$ zcI|+A^qXPuzL8lo0oCW#;d~}c*gY7QWB)x+=wBJ3SEu>mZ&++|80OA7Svn6n?bpWf zXgptTZrq1oM+;n>5vx`p1OkxZOd3qWIoy0S2uPSieFnxvG!hy_H5sAUxaT@@iL`hl zmU!V@K+CA&nX`){u8unH2L}0(uniT+`y+&9aWn%`$rgd6KLSy8A~D6|i`@apK*rrf zDpi!aneY|RojOtwx3@_oFOFlhO;hq;q2Mcw8X5l;MvLb~_iuJqDw%Su;fnm~YhU1K z^DAI6ouSDCRQ?0GPLX&4r*9%a~!a56`bzg8SEQu>~AZhBC0qd`1^XYnSPggNBW@d@72|)_x94;KOzQ#YY6s>r`ZU zmNC2ocF#>KeS2Cr{U9tFjMG>OFh99#0Fqg>rW~1;bTrmU*dR47l$8x(geAa~eq>~A zba-wA)@A&86n{AONXKBNGCWDk^eph8(B}%8FFyWfk(TL`r*mwUjLM)R2vB>gU;-zQ ztO22%yhj`g08%tQT@+Ct017@3SnCyDzX%;>MDdRx^Izxk%G3o<)+!9@S#RARZ?*;O zbLlGuKAvX)Yo@Mwx{SGk8~b_&FAjzl2An(k=sc2OSM{Iwck+%tlpt6DC7E*Qq*w%@ zs31*umC16=j0N&AQJrhJ!%~*0F&2b-2b}QXjvJOUQYOcT&j@)(pevy`d{)!mYukA~ zCZ?+V1fTJ0|8@QBhK~KX9i|>yb&#QD@X`WZ9V(AU!`Kjs!><^S2{q$-9KLh$Uj1hH z&Yd`?_m?`@(AVnK_tfHIXVvR^^izSspr5R3h4S&6qE$BB(y9S42&Zq}xK^^)ercGl z=OtBLEPgA+^@~ zt?%e7K)bgN_O&}hgL-1V6e#87sL8sCWc}9wwtYUVml-Rxh)Rw$G5>E)L53{W9pM|m z}U-e6!2WcpgUC_i#wo;zYKa z;x~Y?R+dRH&zm$_(e4<3Hd+o;6X-BKyvLHYWS&O$Z3?kyc&~3TSU>A#hg%NU;~T(t z9aan&RD+&0?Wb-%-InsC?0>0m=RR#wtoR8mwtnn9szGi?a&9>CPfnocA ze&bN^tIRfijx#`oDs12C`DRO+#Qck#O3|B&NN zr12s7ebBq2pRXa<$ff7c*XCV~@BQJkx*mklalH_543w3Dv4mgKh9e7r}&mHCkha8}XazvZJGiBz*llkS1bY+J3FMORXAfe!T)&MC-?J*@z zbY$agz0Sxiqxp|y`sk3`zvo%me|D@lYvPP(;3Z$aVcVqn0$s|<@q{@)b;C1#jT5> zj!D%<6$?n5%lvB!$NITA1H@c(gqi91m^={#tU|f3A*onr#H>XKpdg^w09eFfk(197 z{n)aV>9<&r!xFI#6`ULLwv=1bQO($EYscX))> zX4a#dokqC@^RIOcYyTm>4{?a4l{?B)4P)#V}5ucBp?=~LLS;XNwc{8uLB?Tehn+oD0)0RosL%a@c z!?1H7xWJVfu*7qh0K`0;jKgf%JiNodQHHNYf*Wf*{Tqy^gS+_1RGMC#{!-Wa!A+I_ zKAmf{fc<2oAMI;{+I5{>xKqXK0ZjWh0Hp6=wEE!|D`(SPzBB#4eq8AJb zx&}cqNh>VWp(gKS`%Gw;)+NW#GTnsTGlUT*CAS_l4=gFW186Dy5OkUsDTq)I1%B!T zC>1HO95DlN6gH43Rn+(!Tv3CuXO3g&3eEnZ9&+?taTJelEtDxjZl~vbC}Wmc^}@l7 zkG=#pzd@3(o|ij|UuSPa<@r1}3*%+sL+@Xf#?syc3ciX^JEu+7hr&4 zN156EjhjEz2bUiUl*JhZBXZ2(=^y~31mLHWfnl_I4=^OwtS?XPW9}-rGbCls9iZaO zRS@Djh(ps~5s1d8zH{WIAKZug77!9DHW6?FL^O-{zy-|%oGD45^cwR{Gs-hOEuSD5 z*yn|KBEsAZ$1iSa)}HM&XD@Ny$2#Yc3;S^xGlBS>u$9wv9Z%?JXxO&~`6mfZ3k+Ahx>;ixw;eajK4qwOeathvEXK-wv&G7g?Z61JB)ZsON<{zdQKp>aIJ(cfvaM?d_sI&c2E);2F-N{(r=Q@n;Buv^34IwHa~v;%8Q zeF{;;mReHSjuEDCeIKrFfe4qF=OwrXI{}Q)!WhRef?E4dTtkV5Z-nqA&XhJdr>QIa z-%rk0H}#i#Lo{w|W%l=BIGHchKI6BI2#)3cDR3ZN-@@#lAjp(~-`RfMtiZ7D;W%q; z74Pi|1vXBay@yOXIQ)YrV4lL1Tg1(jHG2w!`+zx7el_z~8J6dSMPJ*nWZqd2>P}|j z2M_SHPDdf3XnU^}zNmd{4`2Y8(mSom=!h1R=eBtco}evRcjkI}&CXf`*JlUMo9@*w zxgX>v^S_EE+r#g{ACP%#Fwk1OiI^0C>p0N0mM4_J)k1y$(+&Q z7*vz+_Uz~8Y)8f(b}E%7Q|ij(0qI1^1J|pRe}y=Mwlhwl zFX96LSX2-&;aM?nbI{yQusLh+d`w#x9;g=zVs^O0$8fRpYDY67@(yUF`9FyN8}W)D;sOXA?C1(R z5L4L(P=_vft<_8IrNy}-*()B`3MzH0fs!yN%i!GN{sYcs&ZdkI=LbrOZz2awZ_->_ zp(b#D{B^ZJfQX;UG}qcoKtziGwG|2rKygOJi?wUWT1+Y1ga5>}47EZ5n4BZbD|i0V zj9&f;5B@K?cfy#!ODztrR`6!6Mt?j*FraxF674Yz=*km>W+1mXwvt~*`#)JfX=V>u zm){-~EgJ;3T8=Xu0-iu{pFIQ0@p$aLXl>Rg|Hq>$)9mW!b zYX6TR3z7Bb`T%jj9s+=u5EDPH&zpaF&^A9~3E&Efmi9k;IBkx$*p_Gm!HSL`-EF}t z*7ozboK;?qhQC;fz!yZlPRN9_sDyC|j|Nh!mI+MZ6iv_w21SjH!msf**D@OS?R>E{ zm+#tX5DnY>07id@BOdA_0Kk}Nj`#ml@3V}^B{yu%9<`$U5SZysULa7~XwF_dYmnA9 zBc_nikz^>r>R*5Z+oj!HYvxa=)1!Zf02ll>)5AN!q`-Ug3G=xO9XRmZ$0m3mZnXt6 zi0OmiQ31FQ(phKU!mzXaN5#f50zj4^Vv7f+{wuXdu93vc`Kjg_I#z z5N1~fErT;61fYu(92*KFQE;>eFPoKpP5t2x^c8`C;B0TDIsSRAIeCU4-~c`a2b!JR zFaa;^-+`l!SsbWvf-NLR&`?@lik4R49j4R5FQ`!5Ag)7U%J{PBkuAda;fAV+rB>BIWR5G$@WymIy>F-@UdixEN)xUJ% z-Sc8G6>`_NFzcXI5%pEy8sOC{VIcPQPg{-`ZRF_ zBKCo8V!L~8(+3}L1Jh}j0+i`L6CCH5G3$VaE%OTQfKxJP_8&nVI3U}0l87CKm0IwG zY2S3P+~Qm3T5*@#>|&LbopxeDiY^u51$rAS)A|DNdQfz}?F%HFxlF)`JQiD|qwqUs z-PAjCxs!_@-*hGJ)4Ns+q|+SKeTYCnrG)*Yut~smpmRW>p|fL2CSgx5BHgX9unM~J zX8&WiGB%P$e@jrvHqY*$;TY)0M~5@anCz3Tl4{L@PkITMG8p7Uu9r{XY7Y1IfiYEVl-b<$y4oK$}V*~QRI%|Z7 z+YB0qkjy{p_D5svSFpDonZMfAMBYDR@8na|a7KslkeP+KCqe#+dj02{andVkHYY4M zzzgp5l*rocDFomIF|(T5DgY>U0H#v@NO0+b(+fR7?fok@0CU8iQB1(LWjDqIpibCi(~j`e*}*Gl%p9mAu7>0(k| z-rC)lY}f)0HoEv+^qzB-S~}=^cl=Tw>K@(L{wjllF(8g_5hU~t+Yky+!BgC4Yv=9^YXrxITM;VN1O~^fwHbrI zCg8F$g_)3cS@RDLlSU)`MP$r)ep|tmEt$Xm#lgDu;;%d@Pv5+km*4gCU;76P^2IFv zuEM|T{xI#!-ns1F@SCMNXSTSL!A34U|6#?KDywxCmDkSlr~tt5hjO^;w*X*3F(Z&s zYjO^TAP%0_)UQhFhMrp@&2nZ8Qknl5(IP$a~VOw3}U4& z8(7Euxo$1UDC=ej2I83+$kdxZ@Tg{5M>npgb%2EVcP-}$PlANF&wEK8XMMkQi}|=c`EB zp&J<=3INplzln~gf@nBd+Ta+6*`Q_h0#J{z9l`0X-u~&6PU4t;Do+2nwyiR6Ep5f_ zPQe1o{0Phu03dMc1pwKX+;;AXmS{GWdiBHT?o{%=r0KINVV8Pv2r>Oh%e%Cx8X=9K zBy?5c*6i_hqSHs;^ZhXVeg8Yb+=owV0o%~AC7z&txhQisIAx5NfBc}KboCkYpNtQ_ zW;z_xb|V=7R&!~|J}m*jA03X`PT>t)5+JS{4$?Ybeo~+Dv2#JB-lQ+n7NDTuVGzkz zX9ttAB+F?f!S@LvD}5FR2?`BR?F8rfy~xsN9(n!#XK7l%J|V`*G82I~LfTwmkLExM z0LEK%TUkCFj85mbI47PTL#rGD$68jJj9p9;l3xK&uEWZ5?JcueSe!u$l_h6!~WV>=b}yijW9mU??~b@*fd%0&wRXY(3pn2!p#Q~8f7%Jn}2M83LU zM;Ln){Z{>IN7eW0QA}X?TRFVvSBU2;QOyET1YvM9lX?Nxeq@x=yeGMvc;tX|Ee=x( z4m-ML4Ix0Mw2r?OFoyyG-zlLC*_+7sK8>%v1%#Cz&V_NU1AwdCbBH0iZZ=qhxCKF# zwQex_V|EJwp>+^o-Ap0{LQBHcH5*Bmg-VeYL2>uvb(i7V7 zjCH4T)`ZSi&>XGOZk%^35V~=EWxp(F-5kojXe-qIB7-aVYT-xt?Op4#RiX} zwM|I<{ONm+iP1>^cq@8ze>_W;tk?tm2>AA=Mf{9*#!W2($R8)UN-7~O6 zBg>Yp2KD^k;UlP-VemYMhB|S4tdpK`rJ0^=W9W$sWGn@tu5c5N4c1?O`(n9InM}1FmPqomA8}EqXOrmAA9ez;6za0zwG&) zy(jqGrC=w#56&(=A9kAOhT*+>?NOjGyefzH{MM8*nFD}MzJ`csK`=<4%Ps&EwZ2>4 zxUt`h$=WDt`Zrj2_yFf$Qx^J)505C5Yk}9ecBs6s@oube_X&MnE#T}f(o)lJkZ`FC zj|ffX8_%)XV$b`yoK&(rZ+^@11$Y8YJ*I6V81->`*qq^&dED;gdgSJ`AiT-S5sq&T zP=288?~$EIa5TmIf3_0`f~_95kWk0FEz;?;(^nV(Jiv=CL{Zj6Qa&(Vx5kbE8^58v z2qw_1Ob!m3mA%)^gXcdtPkwpbtnKbMv%RBci}Zhs^!wYRmR$hG%_gRm>zKf?C?Mmc zE(HM1q}t2&;~XIKulv6}+WZ6&fIvWoUPDLGXD?1DT07l zYZOGfsGEI#A3mT3=mp>?J|%Pl2+@{vdISjS6Q@qo!2&=b zfW&x&LH9`cgF3aR_scg7J%^9h@HsMf$+zoCKaSC0cH)F{6@fH;)t-qvjVx1u+FaGLX>^Q2q%=^f2U_go>aS^Uhad>=tIN0-$Z z6neW=?i%=N<3DgioCPz;D+U>xWEtS$2G$83-sHRW-%+NgMBaBhKqr`#6~Kx$K%YQT zx&Qg1Eg-z;0Mgxx?9BKs0#N6`<*{4!O~Bi9AInl2U~`0Tx)E?X-}x)_4bA~aJ3K`Q zAPxc6C)-%~K7pYJr$?Y@S34Fs>S$R$#PbfH67x6>G=s+^4kow9hDjD zppbUd{$Rw!IYv-1R``{%c`PjCJ$s`D&+GN@SkH&=)$_}a7vI0^ou#?g&q7O6 zp34eigTAYW-}h{omhaV$sps|D_dKsafjaRzfq|3}M-w`t47~urDLbd{EOvSQQ+|iT z&U0x={RwU3%;N;j(<(Ua7)|N{Qbx^z*FkbF4;Yt%eM;8%-~Q@a0KifJAiS&PuOla# zPY{`2m4nozh=F|^_H}cF07rP*KL&Z7X>JK+jQ88o5!WyNm0bgV0tUEKU=(j5J5wK;u(R(lt%|Nqb4oAk!E zY>9b0TPB-x?z!E2ugVf60R?#EpW&b2sUT?Nfkz(uFL-WP9(ZcVtx6NSAR89!fdO|= z0fJ>gF4TL{>+ij%VVm9d_pR6~b2FJdB<~@4GI@89kVQ~STP5j`cF>Jt2e**f096VBj17PI?AlMc`!50DLv;?~f5kQd0s!OuJ^l55Jmks0SJm|E!)kUsfE$1v zghZU9Hy|!xEN(`#Uw7@(_N6`&!@O6FROjk~4csL#t%Tasf_d|8f%N)qozSb@BYEJ1wK2 z-LpoTR+3Emgj2v}TYkR^5I z=V}3A$bLJb?>#UP7*)Ptalu-A3Kzf%Nf6A3bko1sY#9ZRF zqA~QL1NJO~aVK$-7k6C zlreyCzya(^!_jedd~#Bq@I>$t+%O~dM?B`l^T_k+)#yA306b_4uEBaH7r+xM=gBzn zhhkbz{tE%1r^dJAY3c#uaQJ_`;UpxhX$6iD@{rXWyJfO%Su*8w!*x9qx&Q~R#EJ3V)A3j9-0j`!M3 zKLin*vYG0!pc2#*Awv&%hG#rqpt<{xhW3u!E@S|J#09&kRVP<-R+X_G)}8%v@=|;E zzkUB7-ia9h3pO81sO2FuA=pj9N;Ws4JNtF}QZaf!LO>A2fI-KB_bg@Q6h>9Tvm0}@ z;FUT8yPv&i0sAca5Ys_tSK^LCDCe2zoMk9*8t{6qpn*h5m-eO(>}RYaoX`dWh6h}fLD(~i*VG)}(di`* z96wH3sZ~YELSj+~Vr4B1RtD-Jdv*c|(et^p@RN1KrzFCZn4l&Pb*N~J#@-n_(*i-5 zp*HaX0F#5tu3}AA2xQfhr=LCy%w2F(NFOl4Q-1X&5#2rsdPMOSWWa4MF~SJ`1_yXK z7g+=zvD{!TMb;ZIR*+vzV|_Ud*zLsY6O142z)=q&fCKhbp`jW$Y!nLEcb`Nig%RIl zM*uHtw-_)^PykEiplKHt=jN`>OE3Zz!^~c=`+x9l(9i-a&AtR1NrA^8hG3QPF5=yC1BGR19~+JUP$$4 z;o1JR*g3r^_smEV*tvJA`A08d@$|W**u=3M$<-2M0#`+!&RKjQ&r=8r z(DdX?0P*ibT_16m?tuEh4Obm;CFYQ{FqSb!Qu2SI|Lx6G4)h=0YEPE1Ok9Nvz?1(g z7zsnuNLRG;jLqR9ga9(N#pyr&;5|gOo6gv9Z1(4qRrh6PTson^vhXKCN|sy0LZYQ(Itjx@z2;-V8gj zmeNh^`-48`aKz6S19~9%J!H}}D+j}rwPMLhE3DT+A&7Czcs8K~y*xhs}1Q9(Sn%e+?kwaJdmEB?1VRqB_s1%5dPspHVHPZotB)7>^vV&smqQte(W_~ai%fFlSIuQ>OA1%f<5AHfGO=1)RdjN7QJ6;9Q*r{Cu?olLAxPAa1QKL59< z&X535u^{P`YAfLg`cLo1m9Yhy46q-XCF1P?N?WazCdJ6<63-BrXuBCxrP`Z$F%}zU57-jYUC-cH~>VjV%m+L zYh`_sBY3f?m~-+03tGTa0+~5e_cj4QmVaJysSwr{h@-6ker%`quLbODkMHgKcpU({ z@?_#l2)p$YF8h0kq3~YzNlS#uDlcg{xaROrun;x^ zM1b1{PB`4>papP-6DGD~Eexm!HDJWXX$T|!;~0Rk30rG+HqFgU{;zu9fc_#8HzeBv z?>-Z_oSs+n)9i2zug5!T4&(tANAm_3Whj29~;SctPL|$UhI>RA0ho_X;Aw z0d|RHWXo@k*XA2`Xyjzg>_aE48JpEhe*Xa7@(0KOr=b5AG|mN&k^ca~`GJk@{P;EP z&8AU;Oq?{ycGzqn+x=#yoqAXcIJZm866uF{Rh{yP%oQ>y2Cx$&M68D}%sz-j+=`JF zMxO|~N)!)M5L0(*cU!>zalR2jwC|kT9EjO>bY#-|SAGVs!f|x!d0T+CxA_C<#|XR2 zhkjfk8}ULzg&?#((vsnF=HwJkN&0r_-U&V`Pgv_IYnAh*gE!VNX57c#%LzEn%ZEyc zr-EElE6<2pQ5E%!iK4i|K4$I?A^;Og2>*+(Y9e&T?zVt^*{YoYH>MBSgT!PJS51I1 zVL&0uybe&E{G9C(YYO|M9(;W@uvzm^+4ACdJa5d}qMV~1VLfCV4c|iF_iBqoXMmcr z`pi`dBkecB0iDN$_kj6xCb26t%NOVYLF~66KpY|@;|ul?Z#YOffI#6@Nd+dKu+LEX zzxyMnKXp;>y*`RoBD548E0GAUi;Ca zd#CISAudfnplwgLer^ABr)fMpJb^)fFqBaFTtwr%ZX~#udnp1WSqO*nsX!^N1yVfJ zX8Ih;`_gKubW-jdH?A9V>NBQ3as@;jEAw2HdX5k8%J}>(u!%&vDG2~%qY|5^W?uDu zW7(tKz$nSsdzRk)pPeJg|Dc+G7Zy6l002M$Nkl%&?Ef*7BM{tAbNrRh?-~hlLeY88@_q?t7Sf$Y`A_o$)MEoy4l$QX85Cnkl zo~)V@U*!N0adbl#@QdB1@0$OyI^s$5iFwEVlM9J4b!`o`E8Bh9?$fsYNo&|;exn6! zdk#NBmW+Y8afM933==RRB*TR=dIF;FJ!Re5fv6bLAbn{oh>;ypcseT{{z z$4T`i{%35wK;}K2@%gmn70V8%HlZ{MpoiR~w(zaN1(NVVw3Z*Z^A8KQQl4Gh`Uue( zvZ)%?UqapHsX?B366yEu|D=%yP>_E!j>?y^cJkNRr_4ZB&np0IS)tWm#WjFaY!U#j zppcw%GBAVPwa(}NH0>8R9ZH|RhPCYE$L@ZmL<)p6xd7ty4nmdBInfI|J3$9Yj4f9H z=$0T{MYAWU?fw^bHEdcSrnF?ob_h08QfoM_{j$|EPP#kuSzDk?aqCWSpC$n(5F_Z& zv14LcViJw3Vxl#1pIRhbM9fasE^-zfZ3d61MEcEAgkAvCaf8sXu78wlJc;bCqbnec zknU%nT0r28NkxFPFB>H`F2RZ5+9w_*E(?ELFRQP3A~2Q}xXsuXLFp&V!wdHPa5jp6 z2t^@7iQsq|5Gnrw#&VrmOat1U#l(T7AZO9QomT+7`#%EN_qjib0b}YoX5bVq;^)O9 ztXC2CCtl?TiTq0p@GJ3SK8`q!nT=uMC$&`Kbcy4|C%3}WeVb|23~MF3X1y!?TI5}D z>>~kSv)yd;k9B=^N}8G88C@u9`^S<1!1)y5UlaDXGV)EcBy%|AkkF^NGj==c^m|H^ zQziy#Xlk-HZJ_6_%Ts=5m-k+@KrC+Unz|6VVBr_19SlJyZZ*#^)huAujKy%uL@&}0 zEPF~*agrZtS|A*2r*}C?;vG&$vTI}y$++Hs>#=|pQa54oO2GjOq!e=Awq=R)^j`vi zzuQm#+x6aEyG^1b0ObHE^v~A-WE9js2k~_6uOPITQ%jSt&z<%3QZNIjCGhXNZJT0)TPn_~nGbIM`m?5fPtS4BDuvx~e zSdwE}tzFexe~QN={YK%edCCacTFBts?bm$wmlC$Ufy4+$=6RWD|I?^aY{{GP(nth5H0= z{Q|a&r5qyWi(-u&F(T+6+%&Fd&#i8Nx$SoEO8iQku8AEuUSrQM&#=reKQPVo-!$(E z-;BR=?tLKu*wFXs?z`gI(F}_i0`1PzU+sk)+eFguKSBR}^bKW2MDz=LihwA34K>P` zp7yxO4p;GO7i5&DQV#GU{ofbCVf(>DmK|AxR%~!jRd|HYYBrfvmj}@AxnEj`P$8y05&u=&=Nz@G-@7mMqAvpZ7vTp+h`$qzrWjiCU|0N(x*PmG7>C3|pY4kmA466A^`LW4)_A4Ws=Pwck_5UBcW zsLC$M9G+OkP~(Soh%41G4%yRThR%<%8ZkC+t&g~zO59Eyj~!yn02rbC7-s}kn#FbV z_r4!~-*`7mct#%^WM7mG8X&Pz;oJP%(Tua%A?erdaQ(a^@(%q^(SIL(Lq$dcTmYR_ z0zk3X*A|cxzFFvv%pS!c!9 z$3;#SNQDHRe8qyq$|dWY&-qObVsAFTba4Zznn3`Fr~VkW2oJ15xca{9j306X(Tq5V z03!c2$KMKa4&)yKzz8h?;GiJ_3>Y191IPp55@YRlRXLA{_#*>2Ox;t)xB3di@{(5+ zE_fUIoRfpgF)#MgZdVWhX5%q}t%hqNK(ssU9dp;Ne(jFdD*?pDPrFrha~9WI*jI2* zGwu&_e=@EGNC2S6N&*s@F7>rc@b6UD0$mF{eG51o(LtM&K9|}hB~D*O{KcLcGYO|p zUbFV3Vqxjd`D3#J8NTV?x%a*WR_nAdD6pdA>K^+fuTLI90Px^MznVjBIRcP5Q_tN5 zK_HM2z%tKi2L~kVZDf_#Em#MfLli(jaLB?Sj)IiqWeJ25_9kC&z48cA6L3vJ02o3% z7;v?65Cm*-o#$)aRascXaN;^Z+fG$hac-~HKW&2Y{(r_4_j7P zx21b_zkMPA+|@YkMsM3qmu^iv-C>|g{{#fxkj{bt@Xw5}O^GUSMF7YHafpS2jBxjm zz;Bj3D1*T$iQJ!Ov{;Hr{@6D{u?<<(2ArJEIrTgM!SYVe^VDQpi*7?~iqhAB~9AxypwP$Q3X`P*vohZCUM#SK9?N^0i)ztPe62(y1z4GuVU z^@RY02TBB}{s_Fk1+o7?z62f3537^uVfA`?Tz#=PK@i|8gaE!Kzj7VGHvl9Al-qMr zqaFJZ^{<1ypBCXy4j<(KFA(%MtKPAI|N5I()o+j*{Qd9BxV93d^6HlQb0e#_;0+CoofF&4Gy@Y47&xG3Jpm3mWkSzJB zW6VCqcqLDfGpB>C^TD<+xk}y^{f!Qa)@v`tWrZ*f8@HDcAmkT%ymLo1j z{`_avurwEO_=G4dL}w5N%8sB~+ly$RZ1<0TOQvKQ+?Yy{m4y1Ep06-VEev`^q=F%HT;gL23Tpvb<&01+&wjuD$r z1pyj||4wx+@OfGwH&D*mD{dL90t6pGcjHOFKuqHq9Hrj!_U-u}tN8~OrguCGh{RhF ztKLBNYB&N;kcfMD3MCu3_U&8P{(A_;>4EqU&Oqod*|fnQe=uhen~kf<=E2(&p8cEjs_$Xj zyE0E%jbz|li4Awro$nkujFuqG*t++ ztgd(o076x~#Tw6C67IwsdleFvJqv!TOg_)IbftDJ@Kb96$1b`C<5$Mt(znpXp%{uD z-EhvyxMW)#f@MHBB$`SDSP@L0s==s0Hy=Dzf4L>S1`u3l ztS!E#1m{^j{hC_<-xlJtoM?iS!0z5(d^a}#4uG-%$z3Ui;HzcETtaN{s=(kiqLEM7 zGffbZjC(8r09MKo*8ut)CdMiJv$m*Z7VW{20szZXfPSFga;N%L6C()#nZU+KbsJ7- zc*aXJ)9k&u?*srl?KTLovkV7HLSsZnW+!Hc>sB+8oc&h>03P4GMP&{K2LO6L7Y^JM z2Y_Z23r~AQdE%cG0$4NX`>bjb1@tSFzb7ud%f4%Y`?NqaW>!%hb>452wM}X2YWXtZ z1gN2MFJa25r!08BSqqZiXQAq|7%f;J`>|B7@-@uwnV3%qXmRP*6jp2*BRZe zb^*$3^5d;dcY z83x1|G|2z65df%S8LHwh)GfxOJGJJ|dZUb^%4RCAYrpxdy959iV|B^8MBBs#i*JdO zanoSd*K#}_EFjBrT5phw?h*KHtohrI7xc~z-9*r2LQk}XYl-y$nYlLR2C#a zN;S6FQm}|WHdd1WSnTaWZ|3rtK9=l20Rh7FZvdQ^8kMl?F#nikcX@R!@W2*uGG8f% zvefMn>}|oHDOH8BNt+5BA>tedg3 zbuI9mE#R)Nt#fQTN4lOQQWR!4Sf8_Ny0V%UxVB#7mu|TN#L!d4%QGzess(F|@@M9( zKkOF@k&8W32)b~c!aKm3pP_P=*jMHLz%3D{{k;*-C=WsU)y)<{xniFFua%jY+0&{( z_4)3C)reP72Xq~6QO2clKB6wb#iWL)I7JF&#kc7uc_7cXe-9 z*bey^6l8~`nQ7CVrv8kGzz*aH_{ZqKhrX^>u#ZJRbU?a*05^3TI1LKlb>*@kvv^Ep zepbadJO{7_J7j!DZAg9e8)_#`jPX{%LT%Qm<=t7k7I@wk5O@QTZx)#VW*`>!^&%XQ z*8#Loxm)c5*FWTh`#r<}?!Sp()l*=brGT+G0^vWLBkg|R5uuU;KyC^NDsB{P z%T7H_3k00f?!IC%=3b^RS-2q^b47)|u-|HkS<4yy0tZWv4O(;uCo46qoxOPa>uIXi z<=VAC*8(?NAn0`r(O~^&DbcK1d+HdIA{WR3h-y%QVJbJS+JD<{jAu={&uSRvwpH-Jxgwb%p2=Ntmm zu=y@+YWId7Y09ywo&8&UcZr6_Huc{(o@O8cK)g<6W26p`<|i9zTiCXEZNI&4tW6Fg`Dr9?Fs zC@Itv5Ub-a3ISloUAG>{6+)Wo;k#-Hzdx~wkICpAc;e5={~?IK8ksfK$?~W=h5&GY z5S<|}0Q6Z5i@-k#0QvV>zy8j`onIFGDFa|d0FWTS7@x9e7XkpWkcUu>X}2H%fRx&X z&$(*f`6YWCp*>HgUEX1l1SBR0p-KXP+$#uA0^k5+uCO3+%xjvJuT?PVMt6|D&+|;p zK4y;_rK@_^0(;T|j#)Lsvu4w?oTHTi!1>^kD`jr}6apCAL*)R7OeF!pJzY1C(l(vi z%@%0(PC)>$hPY#m64=pRcUd7LtUJQ8?Ei9J3fm9>;&r7U0N{-|;9z0cm=XkZi({yp z%q{3?RZ~>l`)4eA_dn`No%IV9--(S++M<#G;0pl8h+*Eu%MZyM4EvbMcpr;n*nQ*O zmCuuh?-K#wV~t^hZ}0wfD&w@ZA=y!z{&&0tP$*B1n;2IBWef@inj7^VB;|qZ%K+>G z%5twI@GS1+tn2h>Ht+iT5eIBIrPeJeb3_Ga*pC;(>ImNGV-N^01uUHqP?ExC#Czr; z9c6bvT??#Qz{SXomJ1S3(-g`Sp$m{I7bpn;Ctu?Riwen25CInF)%^TV5rF#}SpL7m ze_9=acpc1_)$6Ni^*7HitFPbBsxce9S3HaJfKB^P?~ z-BZY_#?NXg$p5lBt1heWst=eKkOAh^1<3zf=9%w6Hm7fXRxMt0-~WhtM*@J{5)-De zLkK4dw2IB^T~p+X5cyqR3RLip0Re+T%b&9BZt{1H$IE9G+VuMo(* zsOIkw%!=6q(Fhr1fVKjcRtJlj-+s1ASL?0?cD@B-lgHMlW=&Y0BUJS*`UkjkuiXM?SU2CQss?g4f*ebwq%j@8=g^!OgW?&Pfq|_fGQc$BBP~%jPL$ z0KY$|Tx%K}C1E<`C~@C^Jie$7NAv0!LCYry5Fbeh09%-VTX?t_GQ~3ntl!GG z>&GhqBdmpB5kdi7dnE`E$14H(SsRu5zZ*A$d8N!ck^N{H+?(bq@+}tQ@4ebL0)UNv zOFu_nw8J+$sO{FC?zAUBXvzVg`eiY0`(*P!{ChF&LE=mWi4L z-5C?kbgZX*&=IXTi_VTJam_h)n4te_T zC z0C3+GD}gIb=A&1qx)$hK;OSbxv4)NVQHcPT%&O-N0f2Rdn`49_NR4LzYmt8EP7x5t zcOVU^aMyu;IGXFYRr&aa0-Bwx=H$MJTTU+^z&ZQ>>JO z$*NpGRlgQx758Z@(6FO)PxU?Rm-WBg-|^-Q;~U*f5vxYB#?M*Dr}^?O*S&867cmG{ zYb7BKKi|Ujm4KjZ6Uvi*fkh2pgJ7NNK^R;CKIkm>4c7n;xQBfR!ZpD>st)2$#D7Ts z<;1^T&bq{1wB@A4!-$;wdksK20CP;({~6IU7U+=n@2S6c(PclEb3*OL_1g5fi(k0s zb&}X?Tl+@y9BzPE1L!pbR3cFc0sylzpxKuajFvkK%52!XzS;A>@2bCFE#PG8_Mf%E z<-)5uFpq)oqq#a(d-cp6l8BV2sgC79uJj{F-KnkxcC7_s%>hQ^;Bi~!1pEyZu-pP@ zP6U0WMxn}O+vR~`Vf`;R@5L>iZwQpKn))#w<51Ia$+wE%xRcW!G5owH>c&@o-?-%f zFjiX|ly2=R-KuT=8CGJf%$G<2$WF)(Y&q70ZhN=F&z>rDRgC+ituB@Z50hKgE*GASOc5dK2HU^Qo0tnPYYZdPb6>?=4w=q zO-l~C0ry%dw!9EfaTZQQycz-kgo5$%vN}K_duSN`5&y@Z=l)*TA^nZjqCHKNVs`1* z+Q|hV0btIbR{*?LJ{S3CjMubNEfN}neOhLmTy-P;N&7PHC9;$Tt1v`>03|St08=pw zW?qpCE0J9h$Oi7+2D>M1wl4Fo1wK~`1TER+LP9`84A2Y$bRZcF-Uityr>dW;rd_#R z3*55>Vx#W@^CMLQ_hyp_zXSmBhazxxpHEMYCnY@sPx zPa%L;y*U>E)U)c6fqlh=@+;W&mT?L#v4kmoCA`W_?CyW<;{(Ps<`^3h+F1@2S%u}m zh<;;sb>ihwnI*4KEa&(GpFOaQxOxSR#%C*)2N3(Jh+DcVy3B6d?7B_2*>|dIfqiI! zoXVb~uD6xNQW1zh9Ad%mFT#(Y*w_dmCkZyH2zQ@W#&Bk&*{m}T${4U)J|v@W33^no zkInehls?S_5NObAKsw}|klJwz;8HW#>p`4ZKeNan0f7`V%B?+$`0C`0o$FH zc1=6a?U(j+o7QUpZ_)n)`kn-UHE{OWg!d3O*5}S~yusOIFOpKgC#yj2kEN)!1IWRf zA0y%q6KXZVJV6dX5A9%b?Nffb<{47aGyY>$rOT&lfyZfq9L8yqYXB=h?&cg%@^K;{ zups}O{u6WvPv1bKeo1%&s# z3uFOIs|!Bk3_)@q1_#xAgqR)>(0c3@01#1$03xKC-Nx_H`)HjZa4DCC_k|BxGTf-} z;sg=^fxJuR*EiK-`UXLj2n6KiiXL|=l>;z<|9E%`=gOkEU4f#Tyn{({Ch>Cc*aG{2 z`z*NapMIU$wZJ~KfKywlHXOJ8+xCq6P?J1jC)8}uW%)0s9-JCZhr#+U`+r;kfN)pO zrOGj127!RMK?uNfjqzzud9Jiyn@^()n;N z3oRgo#EW3Scz_M=18@ZI`;S?*h8!v=Pi(+}L*W8YvYEWa#J{!>J?7U?D-SZ7vA+`Z z7lI8fRrrM@;TlUVf)GIE3qfFOJ;dEq;&OhnGl99MPB&gzs@7}v@VLbCal zJSJC78N(m?SJiiev+DOfUIOS{RTu16FStv73etZy86gO8Qq{hgAOS$6G_M1=V1CN1 zxnu3KQ`NC;CA9eB!Yihc0SpZ>tFKY;8yL@vwpqUs+Y zuL408ecZAI#7zPuImamneH$xL_8aC$Haa`iBwb}*NDCzFZTp;$O`q+s#@_a7rnQo* zNcOeBrm$Q56rZs*{$?GU^wNl9V`DK~yID-t?2@iH^tglwZ~`Kln3AeA_Gb!<_Q!lAAd!# zUzEUt2su3b1{`GcAq4b*?|2Fjm@beETod`0wJ~uwaXDuKvu#&C-J09N@qVys=l|fu z&z)f32ml{z9~)knNON1<&CapYRr;qr-2#p3H^sQ$uZXl%tUi)ttD!3inX{twScz&R zLB-~t4PrTazh9pBiB$#zrH5txnGygFdB)=lD0zRvqv#ieBcD1>|4$Kn>ob6V;LD|a zbgFBCoos;s>H^^ni%Y4d8?xCYeDEM!n0+>OqglT?<|OCqG|)Z9(}90l?qlo-sPFxXSkZ;Jo_P=xz1u{#!T!-~!+s`Psp;x|~d^OI`q& z@qAT%@`jZiE&$ui&7e;!#-_Dtzg_#}eXo!5C=~v8!V3Tga2ax?OXXkIL z#W|amQ-l!nazzE}hKI z3$njF=XvI{qiTKzn)87}8t+oo%$q}qcvsAwGcqGhNba<3UzceQyj58iX2$KUqX|%3 zD_Vk@ORMmp~YA)tw$YXO{|8PAYT{WM!ZaB(StU$8m^ znIEEczXDf~OZXU0!^6Q*cFPq|W|TFHToAz}0077Rc&-qRY6R-~ z9ALoqssg5o)GMEs<=2fp1pw-Fu&N!rsx*u1raS%HaW~VnQK~!Wc)4;12gt77&X?OwdxZm~=xC;wca8Wt)|6B0P%G&f9Z+ zIRZ58XqJXp59bWz8pL0>%>RY0$KuRIkwD@^gHQ9f;_X)jV_tWSK zv&aQtEIa-}Ht5k{&|JLvv5nh20#Rzs?cs-iUQw_; zocmMVR-X*-%%5Bf2pwW4>g)D`H`g^Jg8YlK ziMy$i0FVPUKP26b7S*PIhPT5aVk>UCx5a6P?WA42aG#YOBy6VH{+7+o%&_!Nx1FzF z`lnm*;=osrhXCq-g#F(`|43yO)fQ6Ba6Hpb3~m;$5n74iGffBszEZ^vh0jo1Xr4AU5)m~3iRteV`>4DK|zTKa6>hDcr?apD2ZxFH4K- z;SgBL9e_We7vMXGSTF+tVG=G+j{(c(g;27Fo>i!|f@-71Nwi*5H$1L|c83$Eh z$CaEOLjQV8O_6_en8cTW=beAYugZ0%Si+uGYZ6FNasaG8C}OPRHqI~t!D)NkWp90# zQ6oL2#$wkXLlK3an2Q>}0gbTWJK`Y9S`r?2Jn=Vvq{*_cInuK;Uw8}H>q5&W0U%@p z05NM}fCc^o)}IJeV#o$)`a>a%CH)-l+6!#s@BjVA(4ULDnFZPx0Gtifs>l^H-Qn5z zx9u5Eb5m{e+l;gG?w3LU$cD~NvD39{Zc}!=aBrNp)<4~b!?#&|K>s=VK?HyhV8P@o zEiDF4RHd1m!=6HVyCEANVh1;b>Wq4zzJIuD<%HxGt92B3T?n?i$ z@Q;OU)all!2HX~SoBu}McR6ol(=HSHjqtlN+zj8`IvbvuZZX5FohCf^(F}Vr1D3G{ zLZAM)1Ilq5zTUFnYWxhzv=QC3Xo+b-0MO3bFgRy5I3HGXWB@FY6*B6Y+L*x5#%a6LzcXKS3kXFb`d$$h%7qAD3GK`|C7l-rnoCzGAZ5&T`j@b6>g!fj}j-L_klP=@# zoVo7=fQK|_yYt$1^JoKw?gR?u07wA%zx2Gn5=a}sbs}~lFvnp3zc&EizqpUYv^0@? zC3%jx-?N}TBTh$U>G{E??5IEY=f+0M5Aa4{vqh0FVq&xBzzj3PAZ%5&t^a{eAXNV!(`X>nZ<~)8ZNT&8Ooj z?p`$=F^;)+K1VM(fsQKx&4#bcKg~S!{GImGDlsNd=lhs#G3iM+)o#ScApX7%plkpL zHx;iqR0wnAkqY{Z*8$=WH!$6YaMhbmxtolz!0Ei|kJ+;%T?cs&eUl^fF^X|ZgC&aA z9_!5uZ*~WWD$PxM1aAK+=Si)wkL5vFJ2+CcJ=*qGmNye+KCJ|4-L`EsEW#5?)N>8>gt^$8SmFU`b^@#&ZaH&xZUY0C?Yj{*IIXvvD=N8ddWdf&dq!Lv~EX z+EJY$$n!l?k`|*7Dx2Af%!^{LR9N*xts1ilZ;Wg4R|z9U4A+&HS+pHD>`j`LKRL(1 z*Q11`d(IjW*TF=h2&$QbYVJ@=C=Qc#RKGHD5W)4rJR-l6*Q%J#@*-QHfR4z%693sR zF;GMVQwU%X0q_%V5F!dXUYcS%On-VaStsGJT$$DsCV@@m00fLaxQzd!Ns+SLa)@cF z+cR+bnWSyktp8Tvf~v1Ry_+* z0HEw-X6W;Paq%;2alc&e9cwdN#}P{$!ajTjU|L;KmkBjFhX}xt63?ZH7CF%GYSMdG zp^MnHz~i-mh`+3uDO`=5dsi3L@bbKR_3mAD^vCb2gWvrDBEWg|C3mgAogY?TBjo8d zPp_SDvU&`C+ij#!&XzCCU4?a#6p?>WKrXLcA%oXj|GF2|djxpCN6_E9ufDF{A!+{I za9&-GIlVf3T`gXJ&C7Gga0GxM4m{yuj)~#SPpqun*nT{K+?JE=%zWzHp2z?K{el4S zC9eQ@>h{GcFgzm|1jFY6>$la^XJTuF0oD+(=DZGo?oZ!Uqtm};^L0)a&Vq?Rd9r=z z2*X!E@)6K$_o|gCV>!GW;EEMpO*K;CyH?j6Yww-6wHLI;z9Ohw`3zr$wfx#2m+{iC z=_l`kulmfS#zV6=UVFFFX7{ejHNW(1#anrA_{D~R_*qWm)5Os)$~Cbn(_*gTmyp$O z9cEU6k2sYdaGlHki9bw<0YljI`|MqcpA{(i4A{qb?W=%!Nh1bqe&(ZH z`Aap3evRb+#dmN{eb1{YXCTOM0>txwa|m$tcUA8L2(lbIaPF*zjrCsTt{sJ+;qIT} zyTX$nJtKZ&Pk;R~!wk=`kC+XaVI6}!OdeS@`7J@#Tstnf(>Vi(ye_uHT(BN2$K&ei z)tl;vzw>9+^n~?7A+hXHom}Jys3#nfhTNE-B(BTpY%j6}1Q~n!1o-#{nLST2-JAuvCWa&eN83q%XJ8;#v5r>ApHPGbkl!h|&S@x^KN`iJkUuYUW7>g3=2wi@F8qCTp=u1~6; zEhg31ocesR^cg@lJB&yFSWaRSseKofBhXD8qZGEI3rtaer2I2}zaOAq9ai6e`-|%P zlV$Y|VQ~@wszV++JmRf+PMPZw_snHE&->_pWMGB6__Z&nPPQ?d6^_`}ALXXSzWC;E zRMnfG(Xq1iv%Emas^?eL;_6*>^+#R~xO$HtM1che|NIm}*1xHSKY)b5-O`)k=ET20 z0U`PlrOwddYD&R887{s_@#IpZbLbZ&Vn<)ko~aj z8}JK6-+WS;zjhKAQ@imn$-nkAJJJ<@?MvSLU3kT$`8LZ{OIuyS`7U7~{YVw*BXi<} zN>hjBw3T704NJRmbo-G#GgtGc+o}n{622yYY}<( zQU`P1ae)XRC`l*~`V;y0rI++0G{PkMj@k2+IiFw4wmf8T4CeTomvx0G(0flqd=D{s z08vhY-ikH8)0R;`EzC6rLR(Ri{7uIj_Y)4EW~Ts>WTrMxcAF89@-RrmOG0QMu0J1+{=U0sMj- z2+pfta47f+3fu&EIs!+SpnWdk7{2r zg7vN3`_Ee3t7Itdp~T_ZGm>_dpOW_QX#CQCoB1?Na9e3l?7y!B06Sq58aDlOZ_}o; zQNc?^01QHidAJ1Hu=lkleq!-fyxhoBmp~)^+82|(B{}0h)?rjcXnI5y{851^g1IZ9$`9SC9 z%#GUmZ#UbfOhaz%9H(yR%Kd*fcZ^@J?<`;iUw{-YSQi)L2Fdgk#}l16)p4$I#CPi1 zTcF+U+Qk5Z?VrApi$ygD({iINHvn&s2S(x}GsXpWYY?0T(j9p%Fj$b65PFmk(BtHP z2vQV?qZo^;mzOvl4uqE#Mfm;+s4`6WaK5#z^V3UXG;LDi*kq0ODoso$>6vLXZO_~R zm}fgoe^omjcJo^KMYx{)dkWCFBaZ0>1+i`Z!!N?IVHNr3W#RzQ$gRoC`b9bEj=(6b_&3(9OPHob=; z^3VMI7Pam;{ci{owv_km`_?<+;}he;Zvpl_;a7+sZ5oI-VeuCxGd+hH<{?qQYhNqk z0O(E=ld+_)M2Es*5F7`%t!o_J&={V2Zn7Ph+{`^y=7<^P>)#4*tSz6Cu-%4DR*qhC zQ)%B+*L_M1e?t&plSX9UzY7Qe@P^^*t|?dsohfV4WoYn?&VCR z5{J{CZcQ`F%-a5Vufp1KGOppOP4{hn5qXz?_LTt8Zc{r$@Ypmnj{d3BPgB2CZF>TQ zVQ#aO-gM67`d_gK+(`f^74a7>61h^zh1@x(D z!$UnwrJAxjqicctwtyQHcdKzkRZQgo3~-OQH$8@RGYA1}dEmPVxEA>@n?M&3RoP-C zs29K8`*jEw!c1(k$=SX_0=a~My64j3W*k2{Pl15G7SMwTP|YCfOqr!g*Yk--_U=oNpCu>9 zk(~$<8zgSIkQb(ik;A0vdY7Hp;XP&dx513!?otnmo{`(8_S808+ASEnh++7(R`B@z zh?gi=BbLj`DwYs8vcZvUk2-E9@gD5aL2Zw zi5vdg$`HwK(votetZN9SGfZW)$RC*Dz55jbpvkibVW0=QyPN>4xL60kQVkKnEwgn> z7z)tD9c62(8dIcqB** z3oZeO03*hQaV$TPcT&WafddAEaZ8Fq{3RFG1mA*b%Aj2BBRF)1AR6g!JtKx~WMhO2 zBW&q1_FAn=D!!&qCGN6S*&ZKJBKDhV)5kdF&y_+Yu~-fOu6jaDTqtLx;U4R|W-=L! zE-wo)KmsJh$D&A`oJpI7G%-5kg|-0j=|P~#|CoWV0KhPTC6S(h-`imLDVl@=<4@DV zf!QJi5HpdKsMNg*|F4@^F0g(MgCJCzI@%E5wr7}rsr6H3yiK!&?&0rCA^^0T-wqOd z)6B5!INbt+?zV3GC9uGBSt&dAf5H5yiUM=c#12dcJ26*07BYc4YL#(5n%m<9vNfaz zBKn+|qB%PabHHHY1~Fm!u;@Kbaa}H53p{QM1k%sW(T$3ysJImXC;?!|2pzK-JYa)2 zVwR|WanRwSVwI$a&4#7>8BaN zO`LYMw|KRKJNqNFfNgB2sHF{I|TfH8*_iIFL(l_)i)Cw_KuAW|TZ zaZ-7O2LmBaP35EJL@)MFtn417l-(R=OZk$(R+V*a2ZkSI-x@~bkA-D0abg*~k#~u( z%3@_{61Lo?kFrGCMJ8k(TsWB>;&0tDUX=UJ-p+ z`VSckp!z`o@YG%{F~B+A@I?Mi=Ui`GQv?zbe(t;!{we_g)?&(wG9t{w4`c>JjN(gh zC`M)E(Ky2>d8WTPmHHQ-49)Nej`E7_e!tmNr3cn&*8Xij*8u-)(2_z4QxX7IT$!lHnD}t5s6RvA$drj;2!EN>Ls+ckrmF)m*JX6Jm)!ydFObE*=pk#1S{y-K zq0RRHEG+?`yRQ-X5AK`5l^C149Ze2|ZG&NZ<^I>kTii|6%si1p+n%|WfmGsdmXhu? zORVj2+hKcQ-&X>Fol$1uhc~lnvoqUvfx!7+l|Z7&Ma}Bh=)XqaLs2dN0pL1-*t19q zWOZ|?Dn;n?d@2SzC6LtAzRUiMHFt`Aw%5(tf=NiD07Xjo4>4B+v?iYkxSb3Mo4;UaQK zO4Bmib!z-qNN*E2nlJ2>WL;2eKkSy-loRFDrC%gI`%fZ(r~IDyCo*p>bm_~j z{-_%@h(FVc=t~~9u9?PA{Y~dz`#ZF!#@e{_^RMkL_Tpbsl<jM{$xd^5N+=UJ+CY8vhiS10dV^v(UJ{23zwVrC98ff1g+!{%;Im!@DaR4{-x@TmG(JAzBr5PkQKj1 z(1ubn#s~r_=ZQ~Wmq+-VE{mU13%C>Yg6b5O#&hIw%DM>b_RlY>(ZzZ7dN!!OU7l3G zsJ~`Voa_0*GKQx^MTU7lQuJ;Vx-8Be^ zN`sWd3`mzC2qN7`NJ+;Goe~0qw5T8AF)(%s$NGjn+V=bVqQuWRk~Tk$;ig7ob$ z&DH?yK;wqJhA(HMZWk8wX1u*8%BVwZ2JgqH+U&5TIF9!}-R6_zTpo5pOzYayeePGI z;OdI9e1%YF*gkG?u`!(Bbof1-w7N0dSAT-j1d^P7VczW;ObYYZ!QBsXmVm_2`3ATs z*T`UME5V2ij!v24PZZ;MyK(kZSsePL#(5>!$ahL3pQ4W2&8Zy1lY*#mH^t0_ZL@u5i61RU=)>gf5 zSD>FO2+^WR-bp)}q{9RcY_r_61+1}{$la15X*tpAcM3+wEL&WFx{<@r-X7`AS2Y(; z@;U>9_SYt^sf13eOUULlky=H5?!|95zeoudFfA8o{MP6kFVl;ZFVIcy@~ry^Hxs-VNfriI(BeHF6MhxH>+n%s z#WSN2DaSxD(jTRq5L7Al*e-!Hf^9PCrP@gd-n&(xNYnnKN53M)(rVM}5`kszAFkUGX9cdbR8yBrcbzj?u08%H^dN|Yog4KSJiXc% z6W_CkE(?}hkUgx_8rkmHP>O&v3B5Jk!8Y2ZLfEq zxuw{!?^wy9Gmrjwk<^Mr&4qqx zE?(nGbKMl4;}SM~_4KNn3ioX-(7F9FKGLxx^Q24_aBfbR-ex+m8AnnjwY^1O%@keYE0$WV3aDVoiz#K5H+!X=*8AQLh?w%H*}Eu@KI7<*7-(vF*TMx{ z@p-%t>q-_u1X5y~v5RnEaY+ydG5u*p`r#2Ut??+)_c5y1hK5o*?@?L2zAtY7ujbBYu)N59kjbEt&$YI}X$h~~S4Vx$N1f?5}nj{JP!KE0-* zvGorM>3v-SAn`Q+S?%_2Zief_u`<{$dZO}0h~q^_KFSM|Bq_VbzRjZvyey?OjCOnJ zg-mztt37OB;H~j=&sglma>m|;$42X|m7jePTK^Q98Xs-8{b%JEgZF`j9|w$T4) z0U%{O%(KYGPS;KF>lG6mtNI5=O14zXYDD?|LH&}Dj{+6A-&&bOJ{>mEySS#U&4*(A z%YS79Yn?IB=sU@7=0Qq^Lc)wbq@pA=)Or8D0$G~|2>SnehN@Gvp>JjwQS~V$N%$ArIPZ!@TSh`&~@0}*bvmU;2yK8fGLZ$ zcT<0lqK@95+J?{A?TGLl{Pa^bsr!>kXjC`%#e*rjWrwG7T)w5!D!mFBwLnW}f8Zvy z_@c4XxZ%^4W^zI4)cLnMNyz|@_YHmt{&>A5{v~u9L-9FRXc7ykJK$}!glz1Tf5&OQo@bO>(V1AI`NXnQYvQW@$^F|@h zuslm^S%p8f3Y0ZG%n)OXdj^;V@|)U`~1@mo^k1Tcs^YA+^L@pdDS;>18%Jj zt4<_W7|q(Oz6Q&C6z3hDk7b%YEO3Eic&^hMGI3F_Nia#E?)i(Pu$5gKoyk_vL6g=S znNNKXr-?&4`*Es?s#gDZ2oU94kTVx6uwWtd9ccB!j$bBA*AZ=7>{kXM_IQx~ebbp@ zLoA_~npx;G!hBrN`K4#VX~s%7&zQDyReRQ-rVKaTX&nmAt#3+mNWW_8h@ET}JfVWz zC4`HJY$#uItFLJ{OeB@33*( zC8HJXn#|QN17bV)5zQg%8$@_1R^`bMx)cS28AgJ`tm=W9Zj%;~atJQA&cYO-u9^BG zfvvAHVEg44dCx6vw(IxX&Z|Dy!JAMo8Vc=)7DK|Cr34{8g~5(ZX=y?s*Ya;x{^x>1 z)Pu*$U=GJM_sK}^28iP0VMywxiQ|46}{WB8Jh2*T#t}FaI@(Nu0 z8-{$D#xCl|Uz`p3>~Q@PLaOp|{A48i`NRDwhY=+;G_0sN{UG53vN9cRXojn|Y5lf9 zdvl8Tsr!lN@5;NngZrs(Bo$R>O)?9`x0?hrT(HM-%0TvGbWy4qWdX%W=-+shHrmN?JdY8~TmyL~a`UGajsGQSp`pcE z1Bv*ig0t$V*{4^TV{@5K#yg9Z1l(bDM9S|!w+M_n?!LnUBNj?hqP%VNzI6S8eTf<5 z98+qVNdC~ltok)S$Rr6XM`~SN3tEc(gm47o`}mjl>aIT?u+&rF?4MX*Qo4W)&GRG- z{$v7}t|uo{Q7mGG(#MM-N{9}q0|ND^}QVb#m2WDni{;~A+eb!0qHp9|`h zhtHZ=++G2?MzAc_bB=2k2@mW_!y*xD z*%0dK^lwt~EtZs6f}ip&Ua410GjYd_HxGGslCh!F#l5=z1$xJH782`iN^hAZBfZ)Boctto#{MUdVU@BF?!qw zzf{h<1e;%CePH>SfyNmXqaNwGpviMbnc5F?@^5B;K{^8|MVsmR{pRw|yIPV=?gt$+ zv;Y3qFXYZ&H&PKA@cZ}^?m`2F503pAtlQ@j%zr(#`s_qi-|=qNCbOen?PW!b+Qd+4 zlHTbP9-UPh-$}NPvBp7Y2TR91x5XHe)@t9F`BLjL1-Ww)d-!OB>FvjT$n%eqYgwX6 z4dQ>4c3J(vWy{>&DxQCrqf>wgnrD-d*$Q(9#!k|XpZ4EWWwc>jQe%iEh1(ALVL{d; z9n~l6dUmAwQ!;=OZx<{G9!SK z@h8neS(eg5D(}yJE(0-QT8pDAPCl@WuOW^cmak(PR!wYtlFzbyOs;E<8@B)|*< z{zWB5EmFA}#hVtFHAufQB!W4FIoK+cVX^Vi8)>X0UGM9*#58V|9C!3Zmv={Kha^7J zxTE_{gS#otWUPC1M}v!M_{9r5=j~QKSy{=u?GUFL=IhoM9=TL8_>|wU9$H{bgiLeR)gam+8Psd zLNqZnR>MyiM|e5jneLU`*Ba&bEu00ohe!r`IWd)_nO5c5;(=WXV;etd)(O_X3u^2s zq>HHkHqPS9r?Kr)-+aTQetl}L&QH3ItgO9o?yBFG`SD>bJa2xWKO-_*_Uf!z)%AgCaLM&k;(L{ygKI6h&c4r4 zuO!gLZUU;c-bwUU#9wn$Md9j9rdA`uZ)8inrE)u7W2I@#m|$u2XT|jklJ**L`c8o4 z&MD6T3zj7LVHni2Smi0t>#nh({H#DoZpGw6HN*>qQ(f!Eg`n)Th*lp4El;d#vf%gS` zuRd(+M9R2If_&wLS{nHXK#iwgNpXEfQR<=UBts)ZIA2b#)#V%J=L#j~J$T3#Q$ z^nJ3Rzt}$THxF=*g*}4VcL3&{bBMy&pjzdfh_1TOR!8i3lxS)sc=}~QiDVelQ@FnuP^7dl=Za1X^s>5=N>u&yC zB%QF(v*)PjX2oS98*v{a?jC{*QP_%Rjy{7kS(|!66q?-la1mZ`6xK;@~urPgehN3|ej6u^I>4gDgM%A|3WZpqLR{9Y2Z?(V$ zI5SVkpW<~4Uqk3wU7+H45d>aBCI4{m3})QF+mERlLQwcOoKFrr*mmGBuN$raEtX{i z4MgpCjXGu8vRJm}4qtTM(_T`}Y(EnjbTs@1{O?E5v#u-6hgspXev_hAdm8zsM>!`# zST0hLQ=HmXGy3LXNzU-Go`K2cO1bZoE1PdtOOcf~oCz{j#82yPWMPvWgXHENrTzVt zKM9Qr99llxOZewC>hHdoa(|$Fr`Ft<#9dez251*n+NhT{2u-R!Kj2w0q=twC=0;}w zPf3$6u`MUNffMVr7Uo3a_aOg1v1cqe}?ZQ{2W>9V)Yz zMY~F}Zr}rpaB%(#*|9Swan3PRT!9_?{OfWkLeK@O$cE=RU|sC*FGk^8?9H0<`N9e5 z`mSJ5aWes3T<|oVywfa+z_RZ4$5)D=4{ri2=eSv?;6nHHM_CQVdWV)Ty(w%w&=cA@So>f%Pvoi>LtLf(atat*YX73f=@=JUXL&A;oYCe znb*xUh}W}%(};euY;?aL`mmSU<{pDCnkJN`Z~bV3(;<9vi|ct9D#5TSgXNjCL} zz_oP*1I3YlP^!Ro3(|2y!WSp}%v*Rp@)ude!OD&31eZp03oPiQXgVl`2)Pnfe)WyY zE9*KS?@0?orEAR+PI~K#kJ3Gk_?;OhX!*KfH)U-}&k4t7;s)qEjQ@E`x^dSwYkH(V%TlSHgMfgh5FDTcg5?nfhbypc7D`soMM^Abk z{&Jp0e+(%Y5c>fD!J)=O=qhIBUJLQ~D-(6!+|NDcssI$s?H*o@YaF8seD2iqI zW~ZBzZ1NR*3dNy&Bg_qLW^xkJm}{!J^ydVoWzvPli~?o~X5M>Lzwj&z%m0881mgfL zqvhdp`b=aW2F$Ig$2r1F}^YT;Ol@Qqp zXOJH7S=1Wl&su?hR|f1$B}{ zxSwfjpxqAyF;!!@Jb)uwWnAYTHj zqamr^S}HM<8@*ZJy@c7f(^F5iZ@IPw9(4y5u@cq_i8HSTUni;Kk~2ykx6#42X3t{@ z$O0lntER;L`ubySV#c+_Fq+X!5oqO@l-(#Upv><^ZTYpwlD3#!2wA$tqR_aBEtM-B|Ur8_fyHt)Kktyk+x*P2Z?P z$9&*W&GU&g?e21K-`w{Z?l0Q1TG(mjl>YMJf=jAiy!@^G;ns@q?9K0v=)HQ0T)E-{ z)K`?xuM!VOL7Krm0U^ry$0^k#=k%!HD#%h!rd3u zl^q1vRa_Xl(^p$m2v$a5Hk9G7;t&_zk-oGzzQqT8$;b;{F~YBR9ge>VD;}S?86=a7 zo|WnLzQGtbGcQ&2gaOu`bYv(_25z&p=kEUnn6tF z8dWeAY+B+aF+g7PjDyed4VPUq#V?L%e^CTeL~Q}LJe!6jk*C>X*ILzS3uO1>z~Y(9 z-_oO=(&0J^)&hZ$s)-AWg+9dz0f~oZ-{w82N2yGL3o~BzY1y;OcnruRjD)m?zpW*h z4>yg5xtXA$zeUO7hF|ab((G<=kU`YC*U6{?;ab-FxT|H*Iyg*3MbvUxwZH*Z8Yw496f$*ILCZX3_CRUp zPA}FB8zEoGlbZF;;jJ^Dqv`uQ%ba!)hB6=Lf#erGrit*t`Qj8?eW4f1h#z5IlE^lxnjOH8Xn(4%=M0r#+vzmlE;zP3#J+01kel4263t||su zKgNb0j)s-Wk{U>H5EXA16@heRF-2-IBitN0|Ao}G?T>dDMxzc5WOn151`5)iR&yGMWw(qTq zL2UcSlw>-!y{({JXXUBq3M z;g^rzctnki>)tw@*?R`ejydF~5WrN%9$E%0)H+K1m|xIFtf^zeje`>aQOoO!S`{Kf)*1L0lB zIA?zYM11G%nbpZ&V-TF#vxk!Kjw5%4BL?&!B0Y^aQYTsb@kJgMi8isbo^Pl+P0Z)O zUk}_u95sRg=U77E!T~dgc=Qm2jNdVTzS%$`*5w`Q9V5LeaY7MSB6BKvkU~rTdEC8! zv6LH_Er!a(;$$F=Ny^mg*gti89mcY>KMT0Vkighv&7wa4I*LDoF#*c&S?f4$hiNVw zJt7qpQv^4?B7C9RiAPp}^FCz@_uJV`8-zMO+$@Xt=_}KqVvx^|vNJ8tv&3YXuNdV* z?=Q55l7DQED?H%n3>hSUj*au&LG>(d@w;_I!uTxtJ#Kq@XD43%a+yi zfbRD%$^;b9=H7&4MAznQBIYGfU;`S|g{EmL4I0uO!*}#=aDFU!) zPQ0Dh3RvFYnLNA1ZCZBaatkQNbvbG|i9^bFn^lc4?S2=&J$wAx*-q4hV169C3Yqqc z>wCd^-*1jJlQTcO*c1hz?E9?d=MU=T_N)(zj0ZB$$%8jU?P_Y81GslP$9O~cnjFBE zT%%Hg&o?~s^*9uk{aQi*_A|XCiTI%Y1NHavEUFFdmc`Uy{#i`kL?-YKc)h^|99fb$ zK5-@KZH}I;YVCN}8p^66#5x<)*s1&&GZ54}5Mnd1m@!;r5|N(e8ssfdY%G&;8%42Q znm=!#09pP~2PP%Jb57riJBVC1qw<-Z)_9V26TI6|(Jcgz2Pm}?iiFpfm$X?Ga z@k_S=;u6a!hAXuEb~ zkN|<7ZQUkU-dq94Mpc&c(MeN(=){DBI{BLDAzBb?+_OBtx0PEdkb74UKW8TahLS-k z2d-g&{FDpHg70olbi!oKZk&Gj(mmKS_}u=suN4#$vdrJ=|7l|3)U&GRx^lR1TP*=D z&Lelv#Amp+?KahdUWuDnzFX2kR@69y)r$UY$P2F<9}Tzo8X)hDN`2gY7{Nk{KUl_6 za7c$xm!E~;`_kW@rX5|-y+Wct-l%tg9)P)I?g?%k$t9%*@!G<_US7}Ghb12e8M2EH z)y@=!a6gNPo+< zR(4Ui3X0?)Z6!QMJ?=mxS?sG=nwI|aj`6I+YL>;7(txd5hENMajTd#IbIfVGSyK(d(&wbtIIhy+QY}|$zTWee3~oU!A-E&q7^e5a47H`OvethOI~Zan zIrlUt*jQKP3ipPlQ(C1ibE_H-`qO$1z3vIUoNL{AALGgZ)CCLA?XU6)IlI6-DLSYK zAPz<)`Lt?5+E^n9B#CM=+}>{=3@<;=kxdAbKK_V4jxI#4+WZTb?}Y^PQScAozk-1I zmpX;PcBF1uhnfp9W6$LT97;!GaDIO5XZ>#Ql{N!KviQJ*Y`&w~WO=C(wzh$2XkH3v zDMn4=h*=HA6~4Sh1F@tmJ(3|2XEqg1?H>n{wC`O<(e=_G@!Hr~&eeEsly2d9`)mz@MMg25iULF$R@?WW& zSOW`QM+63~BL=~6srXEg2U!{$>5N7E2;Sq|K~gnr+2AjsGiNFZvAO02Z|kxe7ooWb z!LLe~$E(AQ{|F+Sr~jR?o`IgXGb^D1Fk&A~4pd%kWL?p%pcni>*(jpO=cSF zt{9Uc&Bf#-8`^tP6>t*pq+U z76s?>6>sb>)NY-Q1lHgVn2V+1Q&yG~AFcnRx%#OPBx&tT8{69$cBdI;eft`0K|eV@ zTHyZyWTTak+6Z>W3_AL^CSZSy=?{?sv^!1O;H(dT_v@Y8=H+9Uku%zCRqO42pvt}O z2PBmysfy6Srz!U}miQqR)iY8>i!rTgp45WQotTOnm$`ej3c6R&H*+nHeBXR8@5ph1 z8sWOk3L?96r|_Q!+7liG&kKY;d8#$PMAvNJkpU63&+Iy0&AYrGV`9g5D6)He|GXlz z;&MEe?`aT41mG`{tSbBs=f0cEB7~vlVf8Ngo}e>=qE5z*>Tx_{yiP&}=)(~&i{MY3 zM;L-^pjOrAIJS6tSnpj9muNU%8)YHSp0yIjym%f`EADw_cery_335PhV?2oOpt#^v z8A4M-LD)C84|?K>Wb}8nFi7;v`MD`DbtBf2B7e@IDItV-6(^VAHFmI>hAKHoR;BXu z+73=(q^1lmpp<%)Sz+teM>rAG2mv5aNYWKr{3ow>LZrK<20|z77s-dcuM}#N;tL!p zhf~yLjt)XR9x5>uFF;^@l1CbGMS{p^?c22&dm-{c*kx&K(b`Oz&!>!-M_d@*bPuxb z(Ib0}Tj8d=BV|ZDCEOMB$AY=1o;&PMga6os1C2o|nYJcevDQMm>d^W_WR(5Uxaxb5 zr~KiD{Jl7|mAeMBq9oS{#Q?{$;hgZz_&^w*y?kp+&A$aEN_Rm^%cGf!ab zkb;67K)oIge_Hqt@FxZ7vb8@VvUjcc!TILqDWTuvhjnvnEmilB^mK=_8?h3Rpt0`0 zGS`F^D$xoD&$#MP5d#TmaT-umfl)5( z*!l%ePO$N>8;fu=38O@t0oU8TYT3a7&e)-2zJ6;VEPi>NWfXN*Ee!ZMDGCjSaE{jep&iS{>)dhO6Hr3 zBxHGbPeAE91(r9`vNB;MoTVYYVB?24zglS*`~0@solqZnCN6DtE%CwfO795gGkR=$ z_mJyhM7dA>MACpm?||Hy#!ka;(-uo=H~}}`sD-0mK{WAp)^9(`{YJ{3fO5PZa(%Kc z$`2XMzVzEE>h!%Wq#9QgTQea>SX;0O6gtZ{fLc{*U6^yoX(&Yd50d|mEsCTYsfRdH zC!CDJ(Vy2n0RdK~xi5QE6#`;PUZXT}O4t~nxm z?t%Q1^$p9?ky;?hah`J!0-TcqPd*E+tlwa^S(VZWH7f+*GTo(`Wb>#}Z`%A?;iO!7 z{&_5x%|zn?D>oCBsk^1dZllI7#9N-Jm(oleZZ7=vN;W)l*YU*a!JzQMhBSt$BA zb;8f3K5V6T z{nn%(Q>hu6vj^14?RYSTRHCmWM~{srpo+UtL&}#S$WMGjMS4!JibQemBwk3#U7NJL zNaGD&Ks#x~nO#8FE8#j!FY+s@W3Jr>)`j33%*SaMt)u_95xAQLyCx?WSqUVYUa8C^ zHO*5QTG`-!mSQ3-Bq7z$#|gIc;4kJKA;?O5$h6%w@7_h|Lu^SpJ1?s?jLn-C9zWT? zL!hpPT1L@iQwB^H**O=Y_u4fSSB?!o?73q9^eDgdCL63`Uaj&(eSd6Kx+1ckMMZ(* z8?76e{`GaIe1^KO!J1*H{i|e`j}JC^l=8Zw7DZQLw5*(oO0z>Q z<+N>hi~Z~cU6VL3z0|K{u&y>ztK68S;yh>uT1`l(XVWJd6sw_+@!veEf#uyXRB%ATW8X}b;B9ZbDce^M zLA6x=U?SUKegWHmvSDUH@@#aIqu(cXC+!zR=RI2rHjDe#uiT(n-p%)Ug-5y*zgfRO z6YQqoe54T)-Vh$%10WFh0_zb|@-E7R75uT2I(&XZ4U@ygzRTKDkTc~C>!=u(Ha)i# z?cA*pF1y&cI&9}j$xu+)us7QA3qKyMeCpZesU^s7mukt=#}mKq>?jsZ)POGuqYTlmUdLy| zAG!V{W<;0Kt$G2b-{KZQRN!Z$r9+76lW=k8=3xz}+*StDw)oXxk2;uN$hz`n9riEZ z)j-b-sqA6T^s`{LQ{OWLAwY}a&a=!raQA|q!!1|M0Y_)~Tf+c`=hd4_8bbZ$(pl8Z z0n4`o`2FB;$3Yt;y_Ip!JizZ}xA^9_lYSC$D%loACu(A8)G5H{&&0iD{lvaW%ZQEK|Q zh4C_dYB|Ryy<^jl0UL2>J3lZ!lgop>A4CSodFk+9uMpyy-NdgorIVuW3@?zBMcXX{ z2)r29wY7UF+lI(;z{5myn@=8J-p&-pbwTqetk+xcP?i%GQ>QwyTdErUPe({Ky(#XP z&qt#sX4tlGP!mNz_37xAYw2$F*}-BhNdjm&ydYuhqBMYVtdbaiMw6<$;h13yQMdr_ z*mTcviS#&IGKc;J-cs(H+8mRFW&F{z7opG$x|6jeA)Y=^>)2=9ib-5rKqFTKKCRC` zG5_wrFCaVv(@$xAnbkV`5Ge}2uxC0O&W9)#*q~Rw_$c6yi#`Em*w6D>OAKoN`e)Rg z*V!Mklxd2+Ubn&Ud&!fRF-W{mscb#zbN~(7o)O)@gA+Xw@8rXPF#&u%;cbAe2kFwB z%rL04#{S0^`n`{APLT6akpU;q7lkugMGkYLH|rEgunJ|!-##q%0WQ?QoC0?K=bU70 zHF<7m8zyYt51aKxinm2t3@8<+qGD?B=3mX=`Nq^=TG(@cVvMa-KN8#9`i12%){)=_ z0a<#}L@(9JQmPw6+WR;VsH!EHtUDIYn1GmDJ)uc8!|*^V@&){JxZfF0`|E^yo`iH{ zar;DJbB`vxr9s`NH*JPi@b?3ObJS2qXhSgTW$qKzDm@qxIUh`3xmkjsd3^0oF$ zy)mNn{Pu+FtcSCEKS*wt&ZdzOK2Hb{aTgx`mAvdiB@887pFB0i;?F&K+PZ*i@)knG zlIW>+9_eq$G1KuQliE{TD`4C|1>`GJ>%XJUz;KiY=Arqv=2;x%#p;ed_d6(!e7cwIy!*7(-ckbSaj<+g z8Pmo^d9wseWt(=LIJsRx?GA3KU#euNx0~#_0Nq(46l{A`0a4g@x&DuJweIVS0?NNc z*;nvoOk5wHMXQkvo@vqn0gYEOd}~aYM&Op__x{dC>Y~Lax6@jMTo}vQ5Fgi80R%h{ z-7`&+#$6WgS%_siSi}d+d}Hq~n`mNMZAsglyKRKZp-)JD1qZBQGU})A#*&CQWtJTV z9!+D!3OtoBZumP{l?KT=bCiGNK5KP2-siy1j0fw9B z|6vG%qR4Xg=qd04(Ec-2`Xi)p=rPF#JfuIfVUC4B9pruYeGg8HJez*ELh~`)qzkTs z(Th7mT<(q0$`i1WVH4|0sd~CmBlZj<)bMn zk{R^&Qa;;zL~#sl>%%;Ysu436h#yfDwC1Wr7FAO5pwF!`_Ii@%`93e*lxJ{~lrK#> zzWXnWe%^n@1lXDUs~_T?q@JWtMhe9Fo)7zA+=0^AfkW`IHOL1(AofbnyV=K}2S1$P8GW*=?#FPU>k zfBX|-Qe(e+6D8DWw@6cywq+c`@(iPuL}%^So(b|v-g_p-*jD^CqfWhg?>_qc-oJch zaE3cAYy_3r_E}Mz`-p+0g=efuI_?JzFhS}3tuWQlh$p&AGT&6=C7rc67KZl^V{jzd z;KeNI5pfl>2s5R$VIx_7gUB9ptt&~$fY%*mNL(ixaIwM5S}Y($BwB~)p0RFagd;9M zabRLkWHLwu37D3Km zy)!mg{EG_G^^2H9)cJ6U0lLK3bOD3pCk{E6TE?GyW^UDuKg?Wbx^$lCf6s!+VUskI ziJF(9i*n~I#l+aHYSG}<8hJE}3d`@g1SyCyi8M*GfMrEnCi;)dCHhOlQw6TQ`o58u zbU7tGK)d5p@{@@Ei9M&PnQ>I<)7xT0lYA(ra{XDJ)#F_s>{oZFUhHmKMz zI41fkJ%8+A^KaLW84^0+C+PM!K1?~Y;eAHKVY||?Te-bUuHb1sKKbD-HwQNhFh) zN&UuWKgXx+q28LX-@s@5=I+A`tQI?)1fKwyge-sx`erl78#xh|mWT`x3Kfvh-dVCN z`g(wd%-2R;d=q%f(uac{@W8#Hx?2KzmgpFTedl>A;{v`B73(3KE))KQu#(pJ`)^8= zoTv7Jbl>HRPMdn$7%AR(^8?cYnqfEa@*iHEx{c(<+tC6?A3AniE7&GM;oQ{8G?!Bt_Y<7c=mBiBr*r@0}n6> zTHKN@^^Wj;akK0rAmckftb$O77G|J#UQ?L(Ar*#9qi%4915@Y~0IGwW@76RWC(_?u z?uUpudqmJi1{}t9RRvF4FJS2HffQUxQEJ)KCj(mRH`Y|?pW=)~=lI|Ygo}Q2gr>Or zhB4_24=3y5L|-=C5Zk2HSUi8Bdq*nq^sq5wQ?F>yaa|)P@QF3{cqb2@qLU!CE z)5bBpYn$`R8W<`diA6lxDou-~;TH>G<^QzFi52l{aEHutArai(sK={@>iP-m^cg6dk*|E{i4orTxashGkuK{YMVD)olfuph{%L5?>XE( z9R+?(CePGc1Aa@{m-LH#-C7Dn=&g(!sC~7VPfdsWlEeu8Gw{G5lorI?Pk{gZ&QJ>8 zRPrQ7Np=LrD78akxc5+4I>gq0)s7hATteQB7$4}jPsb!bc2n7&P0e85AvX+Jni}~K zaAsG3Q;$;fhqRD<1!-pY#-&*BSuD~VZvKut0PM78l}bQXFti9Y^_OY;GrckvGeE2u zG;z2uG}3jmYWWzm#oRyxTnoH)4gFa;sblrb^rY_Z3wrSV{| z2?yD62N?SY2&ysg5zGlR9YIFluS6;#2(C}O{64m6 zdiKM+$!)w*;nA`!gNswi?VNc{9`u`)t%G$aal);{RPU90y^EiQCmQ4i`65S3{ccDj zkoQosv8{by6NyI$_!h4?6Z+7QHX5=_ryq4`1=bRes8O^Qdy-Or^GlIF_ADfDB(SE< z>|oq>@ehhAV_rr1{{Y%uIW|d^BL(PDo+Q=jd~sRNq2ddhw5>Taq2ik}Xh-YL#V&;k zEDP=~G!nPnPA|3Ue|;CTIZ18x58bbZRNGz7peIn-$ z!ob$&?$7kb)ic<3j47aWAB_=$DJa}*7>bIn?sg`tWlC!ZEem{8$vgCjyD6{WoUjRM z_&&LXA;1|G-VGeTq*+|+p=KCOYMGBQB1X_dr0ugx1O~-^qwx0vLXj5xM`q9u8Mf>3 zi+HcoWU?%4@R;s~_Mpc5o~p@s%OAALSZndIp;S6gbL6CJJlPZqX~~|`UwD*p$FAL) z`&v3qN;yw3|8iNgY&{PG%mwOA&1CVG0S?=j$=Pj$47rpaVE39(H9=1?x5pcjt{MyO z+P&{=Ev-w8S~Us!wQ>qx0Gba6LkV37{|&quB<-#o%Zp0cS$tD*3z{ucyrUt%YfI0k zkrjZ19JV^~?3?)-$iZeF4Wo;2M>3rsxWBUaiI#0o>WdE0^FF@^0^ib_;$pHP*aW05 z0B6jcVGXot6b$N-n2E04Jqp@GnF3E%Tku|Tmv*YXr=>IhfA2yybMKqHk}pz$8-6jE zt$4?8e6h(=8&D&v%muQnru={`9wa(OY#6dc z5{AH}d7})T@^w#ISN#NCaKhEv%hRK37FGIU)x@2nusMen9g7BUJB|`RD&DET=NJx98StrC1rm4 zU9sAo*0#Xczm_i~6H|w`##Jc@I-Mnbh?TMt$0!turdXANfK%=ki_BNqi?W#a5x4Uo z4q~ls>4v5!EjD@-{{pH|Ldm3d#-yTkO8opZV|pf`?nin094J+MNGb?oMc(BsB0In$ z$&+o0>x6ZG9fLz@wBz~%P%x)Q5XP7_n%AoZ|G z^+^F|s{`x)MkmVjZ+7+wk5Fw;;~;$uCi6S-p8LO54XJe)1m$5+@$iLwXbbTkCyO=- ze{xXH-u|I1?gd}13s?ZHPWe@xl!#@hd)_Mc8hZ7$Xv5FlySCl@L8?_!VMM8JIaq{} zn{StAcj}&ZeV9;}?^K)}9k!sd%+VUZ-$}JhQ5%l+zmIb+8E(oA7BHc(2C~z$l&|wJ zVMq7zh^brrcge(%;MrrXq^QYf+(@eyTgxwt1}}>;F>Iq=8 zEqEu<{{g%}L%$eXvtgX~-^Sg*#&v(8^?$kJznmM@Irp|>))im(z`6(89;me=@UMtV zv47VPHT}EGUn~IqC#)$4Fjo&p!{&(d)yKfdlgY3--9-F{w1>Ki?WPR1zSJc`Ck*siZc?it}GdbG30QV;5mC%wig^(x1}@4`wx-vH5GhvK4Q* zOxIs=55{HoKMLbV><+1JSbx{rA%-;$oWeAXbD+r-sQmWdKK3Q{uVX*L01&D7F{{xQ z2@>36SEr{U49;WqIj1$_dM9K*V`6$c!0ZBrS*XnxdA@1m8w3&??8rUgywDGZ#{iXn za|+`5hF#fL*f*RveNCND-L-nFOK-Y%>+%j!v5A z$Ajj#&-PJz#*XK7GZ+9roI4iXXi*5@%=Ae{u2Fwz`^5RGcL%uxz{vXCDg}cTik^4#cVs~!e&6` z9>010-(A*)ai2cVx~}UUxC=etPQSbRN$eMyuaaiZ`5$w}|4mrelPQ14z{yjXtN-s8 zgXZV^`^}5ZC(Q}r>12%7|4DQ7^jUNCB}xGIpER=x@Ks4uH=BYP0O`0muXPt%zpleo zdVtT&X5FmW18;v06KDhf7+PbS^Zq{qkN*+wE_P!u4P5{p1Ca0^kk6%Ad!2^OPzsga zQEt<5#v39$!hxdj#xphkGxpR2piTg5AsxhzzE4$0T1)c;>%&T47q%gdroU{9I4sgD zzFe|~G2At);cnW4@k_uyG}9&8yKVD>IzYk z20m_bU@wt+CkX>yD-*!$F=#1=cU1H`qnB{x!`b)gTn2V59r0|#sJF_#J|MxZ1;IH-+{>=h$@VL;EJ@I5&bQ)@y@&NYDCNdVEUAA zkCMNJ+b*~Rk&6#t0-S)Ty*_Au`%RClFGtP(0ayE}=nv_KAE533IZQFN{j2Uz1%M(- z%El-Qpx?i>S@*!Y2X3kdZgPGt@vy4BJO3(=JwYdmguj21`!bWihW!7<{F~7AuQb3B zu<&d+X#N@3`hES?ljhalChN;6cKv6gNprUQq&ePy+MI9i#}$BqQ;Jtgd<8T0o-tCZ zlh!WKKgIm_*y;ZPdUbYiw;=8}VFr8&4*wM5e~b7Dg#QqCN%(`u$EM`FWAD3kYiw2q zUE_Swwup?30LEJ=0puu3Ui-&77R)Ep+Wa~nU(1TtlJ?RRO;*Ieab16<+t5{O-ZIq@ zTOvr!=P3RgarSu& z!vE=XquD=)dkwQm@&A4Fo2%ix?liw|L{9DGct%qR0LcE71b{PtK7|?jE$qaMp&hbHytj)Ry);;imdcbwVKMDWb=m50r=KWTos^;Pq$CrD{N-9zkOZU2h><8JRY(=9aqZ*r@O z5>1PMX_b80CS0Mt`lnR?c zf0q$p+^VVPjPLp@yc)Oq{Jjo8bOylc$MItpRxLNjxno>eykRP>!VV%v?pvHD!^V3A z0GTSV`=r7RDm4_I05IkmioDGAVRr4D?|H z+-7w?(UI%q`_uyxKTfq0gO&(_s0;1?h=dQ>6;{mO9nKB%>XwFcg~_zb>3jDZUPzof zIf`>~>OXdLLa8Q;aOeQwCIFQHh9W?qv9xWhk%EY_cfYA0uVD*Q{Cv{y01^m(T&(Tw zv18HWuHqhw?&1~zjs`Rn*7&JP0U0A+1L*mG$B)*BV=R6AwRbj^>PLIn`42`|FvDO5 zox@z6rV_wS6#!xpmP8q*b3)~q>R@pe_o)X8XIJUp zhL*9Q4zCTyj7k6lXQx4{D8)^F`Br zgTNJOQxf1*KVqFzIP^0$<2%i}R%mlS8hrH*P9T%d*-qOH(%Q%N#=w^e8SK9C1v^*X zJED}x3DN>c0eD_MG*^3;phadwBH)g9R+m{JBLgXzK67A%HVdAsPy-}x602qy#1u1w`02RdpE_h-j01c+uwDmbe90VMJ7?yf|g#{dw2?!yQeaJ)n<=ZZbc-c1E( zMf}_k!lyecMB)mOJ4WQ+^ZzPvI^#^<$pCf$h@Hm(yb6#eFC^rIT+YF;SLoh*lT{$2 z5kdz8MB*PDbpzyO3%vlu%{R`Q`FKhXO8f&-Pf#Af*a)OH5L+1l!b>~K!pgKASHbVw zRoW$NJ2KGe(pT{%%&*b$Ni#S)h6!-oY@D%M!&C?h17L%;a#{ig81sSOTChJE)kw?46@dZwQEn7e#> znX5|3a=Py`X8F!~HW?jR*NUssvMlkquE}!VF4=Trw3$DB685v^kh^hTvqqc&6VD;! z&R`0>0B*j7s6QBNHHT~*of7AH|8o@noo{V77aLp6d;+{g^uJN-zYG9jW)WY$a%~<= z4>&SiN+tFs`W5}(0Cykbju;zm;<*uTKJ87LplA456925#5%#>lHW8eV1h`s-q^*9@ z*1yF6oisIhKIE?^o3BjQZ(L2*)%eO^=@otu?n7k&bU#jg&>Cun%WuBb@anUE_@d0s zTZ6150d&0%u+M<@I>5h#|97#MG*rbiF>uHF0O>gr0CNcKIbyGzkVPysCroz}>5>J1 zRyLJ_3|b(v-REp7-E+Zi)G2j2pb`R=kOUy#+N^uvN<9$g|Jm{P?DOHPbRmBFQ^wrk zlpRnM*l-QtF2v6s(@dgg8!|`@0QW%(Ab~@H2iei?{GYR1bJ~0}eBFH8J7`|?-k_CP zgzdC>IXPtK1}Oma0I-?U^tlPZwb7dZ0^)R`)Rj8=4rXrK5;$mq4&VtJS?v1r{r5mt zfTF!2{c#35&kZEAp;rR_ra3?S8fAg(bqxrQ=_sux&aUFhJqRN#6&2ELqrOik7+x$7 zDsl}b0M&x=)#nzB(a}M(_u|`T{NfvwU>-Hw=)c%I8#GT3$IX+|-R228FrF~}2QtKB z9ykl`mpsh(+4bvp-)s-m6wbFO=_Fz_3(2NaHZJs+Nn$wDmvQ<`so$=fdF#1+Cf~S( zt{LwB`jjT)mQQuV8JoGf@%b*>QND6BuZ&#VBGQ*?+akRet!V=!KC9;8lO$Y;0pUnq!#9QbrzD@r%5S9B?uPDo(#lfL~$%JM8abFJ(eB zhRM)Jfy*3@F55%kitK!WG&fukeM%6_kpW49KyI`{>-(BTHlmo;pD{ECH*-u%D`Ku1g+Amvi!2)nR zLYd$8Zu9EN9#_V0G-nX_Gl=-}tt~YAKW~oro^WHTivEZnX4>)dubR`{eWU@nQhF%y z4@`7XkqJO~09oGqp)qDX*XF+UfSYvU?As9g&qhbhSHsihIZObL0&IeR>=5<_0CD!5 ztvB65@t7q32V8C556!=Ba>5K?To2gjTxkAx8eD!jN?U1S!xdK%X(y^y5Tmg~!@6a< z;hcDxUU@5D_nC@&(5}$nF`4?n4mthZp=Y?PeNz6eTZDf%t_GK9Qe*)9%!e;ym?l|? z;Fh`jr*>?sl=pLnWB^F5`K+ohy$$1=MlQf`5c_htsndkIx%)3u;Pz^A8?9Zx zT~MU}Jom3=_fyVvD-8g#*FS^E=jy)+RADFqY)SsE62M!l=apYnGcysu42jmcDk;jz z-Oc?Y&T<|$ulk4VZZo&A7ajo^f%FN5x&E)GWvU19f15IUS8nfjc%Tb$<>$aU4IKbu zh-3JlJ;nbSBE3_NiEuq+|L_PAd3OF8GR;}L-rGqY9q}j$$3|jz-6|O$P|`2ZeUXXZ zhoK&^^G_We_xO7-!TRXD7{C;m(6-HkgOCQ;gaNQg`X)?{t&1Mo{?-1k3cx)1FX6u? z{=biJxPIrSdcfJHm3%EmfCTfB9QH7y@KA_o-b^u^vAPwXsh)Q?Hgi^*?=U`1H!a^? zDVe{UtMVFG@9O5tcS-2`28r~1x4(vx0buJYMcAIqf+cI9>gm<5rkcC*=Ua=tV7s$U z)dPl;X<`iWP;tip6+F%tlOYTMclmjO9si3h>a;s)E?^AIkOWZEzoPzgaJ1>p9!CIn zI6j5=zdQc1pa2VtIT|oBduILnFnYk1&ZSg>f5LA626(zx04k~LaR707nFP1DB0?d= zaOaJ|karx)oY%78YpqR<&C7p=qOGL0e1j7{C)Uzsp?xc^@(}%2e#2!fLsMmC=n?!r zWCnmA-g%+%!>*41Zd}*Dn%{C(%QAn(>(~Ae`w!XCzu*|a-^Bm#VLxu7M(sqPstc}| zTmKPF^_@5|Q7Fo{+@$fHlrOMQWXOBha;{}`$y&l7>fQor>&a+4q8p_a`6mb#Mx zz)ol|08S4%<{|?C9TVq@`^x|r#h$-A{>cEyy?@8%T{TY4oSx|uxfA&lot&cZ?*LBx z>;5qorUyiBTw}-CP7Z^!ax+FH-X=2I?x$bgY&5+D>_!T{Jf zK5RA*51R4e8wmb!D300Uu+=7F|HxS(`NB>~G&q?6#SC~@1LH<}e_i;s_dr6qC+=JLHo=;u@U9_ylXgK5P85c#t%w%2&`8)u1GPUcQ_MV8}lG7H{j3{+3JR^-$8 zSPYK)JI%}Cpn1WOr{hVV<6;0ykB4p3vR#P&CrCqWA`KPd{fbtzfwZ-c{uDT=p7}3A zE9$lWd9XbIK3)m{JqECW-9*n&FaYqU4ghiXoDnzP53cn=v#?@$3_z(9=!YI-S{kQx z09>&ie^c73eMVXjLj!ty}z`|;@)~4%sQ_}lJ5jsPpNSpb^xl?1ocYOW&@dwre42&*8h62DI zR&D>ii?q!-n$NlZZNxQz-iX&@E`(*;N&M7bcQoGJP7)Cn{mVc7in3}$(I0o$&%M7M zVt;Yv1eo&>QvPmX)u zcj8`pwj$cbI*_oj9Wzw-f_bOH&l!k?_>7~&y#7r|&wWeVVod(VGZAXbA-*7PxjvC5 z>y=Me3@&B6EJeJ2qLP4@Ku5&B{Sv18R}uh8(pN0)fthXIX&eElw`aO}&pYwH-5l!j zpFzji7n)9K#1sR7e2Da4AnHG7hkrhXpbra*>2Ckf^ZYG=A8?LQu-GV~K`|C|*XAMi zfO9^+a{Gzp38?_k)nUMVQc5@VbTNZu4iF#t+vjehPh3(x-mFCPoOLeG{8N(%w@|sQ z|0U}qO{I~>lGXwVh)I+aY3Vnd-~tb((leC5rfbUmm_IT;)St)10Qk^1tij@N)bD^P zzt0#JEvVeISaZb}|EQ%Gh{o z!71E)7h%PV#w=Xhh#2i*PdwvBeeIkJ>U;tsdxmQ#++58ld~NQ255xfAN8%?$pmRic z_1OUN=MkdZqZ1U<97EilptwenXRblpJcqgD6=;mUQg>GFU2n8=Rs^q$JgNi0tNzYW zZ0DK(ixG&QyZ)Oj$l!FGcYtQ4Z&r^{&W0Qc@s1FPgs`g zjK8*WX;y2o8eVNtJ!vi8es7CrGMtLBl0?7xB&ykq3SYLPT2tlSl$*V^>@(YE&otZ* zavDnXl2G>RWqrrMdR)k;{Blgni!5O~8MYeF5Pz$JW@W_swLczV&|cN4~7bvR|!RmSy^? znK9qHu`}PtpG14~f0UW;GDeAp+UL)lypQ>P4o)PoUknA)a_(k1DM`@QgS3o=&~M+j zOz}CN%)bkE{?8!(r~6Nu+0$pK)nBoGVVpWpHqnQoGSpxQ5U04meOPcW8tnL3n}^Z^ zeobv?`)8cEWVxE5?V;IZUTiQH$KV{|=}PM+BLJ6CcWb-pl zXf90?4auLy6QA%DO(l&bnW0Hgkm2%|Yr5d0!nzeUt>X1RTJz8u0DffWOxGBvG2Q{; z94b@!YjD)Fl~1<@k$EayaX%#P42yF7;A-yI;9Mioxs@O?}6 z*W{Pq2=2Z%kGcmK03rGe!3F^oi~vT)0ODtKa?G{a;3NCSLvy4gHA znIj6_55<$J{YxahAHLf~aj*9A3Tc!07x677z#%);hwNA%L&Q$^xyyNywx`yAaJc?1 zE~4*>|4Z}=3Kpj8Uqn7Y5A6&Z9Q_CAK}~%Kz!G;bkn?Xwy9ZnY2(f@R?2A*+xgKE; zpq7A*(<7LpAi{kRVRyp3`f3BQ*zG4^Ns7d>yji#ihlukc&X?N3*g%}y&aV#;uFFEZ zG*tYRy5Bi~<*Lixi8>5mV#okv{13VMZ-Rb<{rRMM*6cv|Bk~UiL}i!T^9^bhY7v9z z$XfbaW;qimy*2tAg=LZmNn*;lZi=CV?aSEZ)7?^*r7g?oKGP+kD&FTA(e0xd>u=5x z37jOVmSwxD)mxYO>xs8h@~JGVO3J+_hG<~uHZqK}3 z|J-4g=zPH~A+LJe3=$-zz39cjJ#K^81}3TwHQQjkEDYN-!KYb{irZ<&vJHOGb9Vlx z+*yBwlGEQbKkNUzRRqYlW)8%@w!|`PLOjR3oJ$liSI>8!Beu@O4<-Qd%r$v{b8w3V zk=}kBzj6}l*~a|pFH& z^uEf!jQuzRpk0h&nOAftkP{aVd?2*5i!&zBn8hF`(hP-HSwUXs8+mmw4L($Bvs}R} z%Esf~zFb3=;V3}{z%J*Ne}Fwg+vpQg4ygYTtL6bjo8o$>y0PG2Q-!Wj_jT4g)B_Se zo_R(CdYt!{3BZ6IoIv;-A2&~5A2rWj9yJ@UjyeB)+-#HgM~wC7NC51j2ymP8(4xD! zPnSq=?sMItHg>AwR1~3em*|jPJa>e&2b}po;5xelcCe41oq)`puvvW?x7KmIvl%|2 zg=qfok69F@RUbMu?(|uC0|autRYZyEx zrB@lc%Qt4dyuvKgGp&AeSJV=+9{Mt$zg5!mJy}|Y>xpz_oMNE^a@H{b0Vze;`~`&zgMWD5qypY(s#{6C{V{y{VU0{6+&X1)m_JA|}}dC3^(TDy`8h_6XhNDk1@a&sz>P-&h~ z4AZ*I-8@Puv5_fRmPAOV)%-So$w(kAv$rmDhOzthShF5{N6PJfOCJkH1o2g76txIv zMd}D=w8bdX{fv>1_ftPL{!iKUKjVzQewiWxn}l`rU&1pNj`l%em1#-=RDz{|v z1Ab*j0nls?Jh%u(0J9{B|K~6Op7yu`kXyrc!8>+f0647Fx7uL zod+!U!J0>iaxT85AG(H~AKCd;AK$QPh89*fW2go*bD@$ZtCwW%WjyD$Qt!f_lTD!0KgfH#4Fz|2S7 z+rdC;YKYq-v)(Ahg5Ap%VZX7&F*_(BFg+O2iD@_TmI`>4Mt`xYK5rug58J8i) zsyf*#lqH%YOIg09d=h(_3|DN0^Z5#y*W8v>rpjd&5c~Ff%*zak+@{q#>KWUisd)Xl z6T5svH?91-GF8U>2}Agx_|&zKasbBZ&o|~%mVH}hwXHIIlo)ye`TrUz040g6sk$Nd z=E#QhI35z$g~$*s7J&V7yLI<%`Ns75e!sZi_Kd%m{Ws0mNCAA)dmZpEBmkHPiq=md zMxxz)cdcQ+a8zf$P0RQAKHJPccDZw2@?D(IF>mwR1yRkr#epa9334s{9QO!^N z6fGrf<$~b!&t=BtAWg*uXlUbd30&qkt!yqV%V*n19+&f282~j%oD=#x5Ofi)JdOwl zi*v6#cxoUTr{BS*8w>yt`a>3t|C8{)f&GYKLM&<_FM){~KwLiwB*r3xzbaJjM+*Jy zr0j@%L)Wh+(J{cpvql0OFk3d)SkUpFQ^zsDXn^g>;eV?;Kf5aH2k&bSI0nKpID!el z)L@`^9$Fm$V+f$FQ;w9t1lYiCg3@j>eH3kTe@g_{ow^)<`Fpp!!ZDwOjpCs0h=mjY zb7aaKIp^Ge=m6Lx6-Iyz09J5ZmSr{gxYI0jxeraf&JR)T#Vv0Y?_O>nhERXPnBmC8 ztk3vywL%JNj$}X|Ns;D=adiZde}dnge2$X1i`Z-<9;^NduLvweId=Jr@Fz{=-z_(G zBhbo+#`H`T1Ws!^n-%E z*&o^J+o*lLqgtV>xVzFFr|d!=z{L0s#Q(4RFF6_rV~2RIMQWxf!JIPBLe$+OJK_!_ zm}2NgneQ;aWB_o?rx*ZDU1L{7eIQA^Ox&oe(7E{d%zia-1v{V~i41l7w3Jm44lc2mCSEW_M%Y9$`YFg!a z(5~3VLpOfdk3q_Ade?8ibi*~soP)+|YakZxq1)9``MZSwC+wAs6Cz&FPN1F(0GiT+ zYeq>-Ar@R-#j5m)$#bRmek`*csP$-o%mA%ti|J_Q(g)gt*pgn}>#&H;tQM`A3_C=}6e zxC%rWhItT-03Na|i3xWfWh%t(p@m^0%}SXkBK+z2D<5%=d5HY5G6CW^4D};!4rAhi zdBMR3G^Rtw$s}UF@J6bA(Y#?72NnkeEYG(C#HuU8sjFGKiYI4W#Y?QXFsX|rx~)yG zXDqc$#p!y$tiqmVTnQMU|e)q6#e(SJmte*_UeA=E&8M;=cj?itJY^A;6j=yd9PjUaWXK%SO05tZ2 zdGE5ZFQb1Me0}EDAndY@NdRPvgGnc&PNrNO!GZ8sbiKsa#dl)&pLtk>dNsa?;R@>( z5#LQ)%vH(?20&zV68QlCZQ1s53+j|%|EJO`-@SFkIUc(4BNn8s z584f{`YVt9qF?Kv0;0bau6#A%$~FEc*gwSn@7PZoX(boWK=8!g!f#mQMQ%TzNd(o` zlUX#Pr>JWi{^Sd;A%nH@EYS!%2}I5v+8zkYj1!C0P(;>xMK@i;3)e;5;~sFFG97C7 zGc=$xHV}axOsCBRie-B~<}lYr?EHHIS_NozzBQ+s&9A9>x4Xg#FRCkIujsBPcy*81 z4f9H@Qi$&%oFeobsl|b$ZYkVfse723_ynpDwPyyhvN(*tPC+II=lyKw4Dd{gc zt2rE@JPlYbp-L^AH@thwIZiac1Y*~|fO7Lau{^Z%Lcgm){^5_XPq0FO7%q3X9ieH= z>#;K3Weh%^T@sn3`aVqNLL$NTt{52uWy+_!R6bbs%W}?PbQIC+b6M|Xn&rDQ#*{>;xo~NqX}SNOQbw6OyViGJ zugM;fO_Ij82_sxDr?ID>OaQ}Y0WVYn_$>-9RRkyuQA%OLNI06q9^km0`91S%Us>w1 zx30J5A1kd|<(v~_pyuG8HL(X02n%}bhp1$v`UH*t@(<7hr)X4Zrx5_iF(##t>^qu*-c!&9n z@0L?VMx+U8y3a&RCw(CS(8ewDuD;WB>|6QknM}%;t$!bT4;1n5+OUO)zmmAyz~CMH zhBw*uPsM=3hlD@vNTTZsLSJ7m0$Lfmydi8mSBX+@nP>li>D zey`2)W1qwpomH;M6|bw+nBEN=S83&T(~#PSR2}5mwv0jBmo)hbN*|9!WS3Qxrbn5 z7X(DeU67c8zV7CY+(n7}EffIm4?$4bfjNUIF~2}h!3Cn0sPIl@BQ&IK%gxtn{f0Z) z1Md901M0bFm7jSwn_bVr(P1-23;Hfv-Jf1;HT#Ho?|{;ZIzwWdOWkH~J7!*O{XK;JAZbS_ahZPe7Oce=05+dUw@ z0Q8k%qH!}{o@dXi6F2psO&_{pc7{yS8DLpt1K2blp)+8N#2}i7JwuBJa6}%?+RvuI zt24PTF!XfTR=jkb}RjOzQ-E|v_U+O z7iL!@X+L@LHV+ThvEeYAZKslS#2 z<3GxkAQEvBy^C(qEkDtijF0BAU=>-NX^|dz+A@~W@s5xrh;l2TE!%fQJvxaiaSNqp zWXUtpnb-Qb9B4hpQT~kaR|$qCDZ5DbIo7vgGPvGFe*#bDFJCwF7bsRde?=zrL$rT+ z=09%_5rXUhPb8banC}r%>c}G&sYFl7BXiy)oXNKMt4T(OjKSAHh?fxi?)rONC>Vw) z@cQQ{(9^z@0RZFB_H1%f#82m6Heb&6g9%`qYaDT<&bL+k9|SUt3;>B8 z7XL6lZMdxAvc~BzQ+W(mo=SVv?qgv9_|a=l)CaEtV!Q*SR*7!j8Z7l}4J7mG*Ek^c zD_L3btY&O!LjGWX7yCbAKVm4p-e9hFG3X%%H((d4H$?L_lWeXyHCXU$#x4juAs6fl z#5vYQRX*~H@0jH7zM@9k02-J4ZI}^L#b_b^r--#~vb#1!i@Rva+C1_eaGO@~=TkMH zgQU9y%6J_doHpYlu0Mll`)ans6=-90praTNr1mM~{~idtyIxMBuvKAoS}Nf%$nG zm!PznzCq~znCGF@6SeSUrGz{?lRdPPqoE(lBoLU;yzP!9*K##O;$xSR_b9F$cXG=Z zkZ>U`BmgM%<=0K`<)1dagKuGkAprp66#Bn;!_Ob09CEw~dqQ0YB2mJ7^c##fz4ZkI z%3YLL3#gyOQ0%JY>cT~JH%r0xg^-L%li#W^3awO&# z8q-ZPzFnV!!BRw&aT?o>e?fHV&o>d*<{{f6&S!{Tt{TfcAq8N%Mv?zh7&`|NpL8HM zE6k6+CjJQMfv7)Bn{A{yHn9@P5~VT~Wr8>_Emhd!T>z%3YeA-qrQM`iw#(r=2O*e- zw)|h9DDNQT0H$%qUs&-^2VXaT*#A1112O=ViQ4A+zdtwo3DQK*fibcRtUq(YE}{OG z-+jkTwxwIPb*T3)7y$I?7B^e$BhTg0r&HE}DdYMGPUk7t*)@B+p~-&E{q{-#G++Ey zGk=DCioj$r0FVrb&%sX+|F#lSaSMOFx%=(#cZ2bu&l#uyPdES?|;vSrvU*y3x>zxMqk!!ToAgFLRb2nc%UVlBO zTh>98YjMWa05n~W)j!4l9`=%^vk)*jEJO{OAqpo^WfNFb0;T%&Ghex2)fdq85%?OLS(+zI6_bk9Kd5q}<_1Wir< zTZoBnGnRKi8vWaBj{r#ii(D?J>+M$k^WG*olOosd=BdET>i{J@PT~jvgepe>=ImYv zJt+e~#edS7`tjQ0wdwSL9Rh(HP%!8KA{bWSHw-P{42aKs0!d}q;l`MnBWpZkto2W1 zmJ)7Rv%=9p#)*@G00`qa0CAubeQ3)00XZ0=kzZmT5^~;Cl?x24p2r5jKZ?kAS6^7{ z)kfYjAOWn#aup65ACdvY$pCQdD*;nS0AK*PlPw|0DS+k`JL0i9LIYxVgdP6gh}~3f zJ?IUH0242dBX6uMelk0829vyUYHl?(_!Rj83fxQk##ADD-9x*^=k8V@Ic_n|f| zGG(|$?988pJs!Ue?@h)7;R5{b@J4;;1B2@ zd*z`!|8J;SFbRPX>ikzS;3d9SYlj=trVv$e7vG53_8tho3mF=!|PRookqQ zfs-E3;?uOAl`$0gKl-yMAahmleZ=_(%c+Onli`C&B)l)}eQ{B&2_H;+&x_YlkFEz8 z9zfT?!MA{QJ4o4hE0+v_4g3@F^1#7?lMCo`lfASYuc_cqWJb8}dIg-tDvKaSC-jXp ztHWbU=<(6|{a%~8D*i7>wUL@??E64&=6L(J!13F$**BAW2V%#TsUQ;|EC@VfrjH#kYeql{YbH^Wl&~eV;wvy%EVx8~& ztLzi|tP4^Afr7;u#I{88oZWLlj#2>Lk`{LzGvtCX&^FMaDB>i29)!P8TMc3moVmPkME`gx}G0LV0GB?6KGz$28Z z;6c&Ny*@FnEbQX+M!ZL*hKPFRj(VF0b6^p+Q|yR%PCs?1!YC&E?~JK@p~4Yq3@^P= zwh_h^;jZhk1K$;C?Zd7`Wh34^672MWQV@XzT977PX|6O2Pa9lRXpvrdmka=(L7eoI zvSFt6KzdVbLwyMYKBc6mFobk^S6JfwbI%;vfhgBCGa-z={ELJe`^ooa@sjHj?s@Bh zOaO^~ZRr4z(AOUpzcsW~wn65B!`2eJrQTT8KT&Y^3tCUVpna10YuIHmrZunj~nf_yU!y;V$^>`hEV<8KCi_HZ=eokq(r?M2xRds(&>skzdc? zT?{%fwkX50xQmL7%|tE#0`C8cy_BgJ*94N2ruJiTK9PtJf$U5&D|Z{FFMt8?$Ym5M z6!#oL+-TKCnpcqsoU%qi15&YM72HM**YCI!JrKkZO-Nb{fvbkfv5(45+BFvf!-3B zKH4XKpn^svG|W#yNopwta1`)X2o?+gcjQAcAcTuz1TqH#`SI95;TbNed|1w=BeTxy zkEqKrmO0Re5fJ%EqNu3^G;SCsH&&`Kbc1c1*vcq%OhmQlnR z-#Srt1Txx$Akr((B8>+Y*O0Z(M;iXx(T``^G~2y+w`FI2JVp@fRn;%*V=cO68g32I z`GG2;T`!565Pd6fC!tKEx97J{ZHD4 zOG8OZv7ko7q_JwT#T$O1qKiQnI_h5y6BWkiHLH0t_7VL8bsvrKV;4$M1Ea#-PUz}a7QqR-B& z_q%%)VC)t#j${B7Vt&O%qWjic^V`~(i|sgfSI0Gpp64m*8lU#f9D`c=t*fRSxJzEj^Fb#7tkF;-Pw;`97- zi~#rqJ@2Os>45YGbn}}E))m}V5}_I6j=@7ljA!){Na657=iETxIeGttgs~h1bAU0= z5s)54U+h?etmQJ1&fJP<98ggkktoWQ$oIUzyQ2;miD~2F>NMPFq=U#bo-sWTFk7T; zoz}aIFrG-C)76C2`X$05&TysU);lsWpMC4y-SY4klj5DSqJU-Diy+Uu*R*voO$Ipi z2ut1lli0ML!VY1G=ld0#*GlkjhkuNOfGhxEOc%}+3t-XG_txOkk$${RJ^7gRr{n?T ze2gGR(HZdJj4>cX@N@*h&$u{ce4Hub&v=;)97i&*+Ael@IRqUhE~dUF#tQEDZkBD% zuaUo5Nz-hE4&OEyHZpEXAsAyj&b~0-V(hkgzxOt+E3oc?yVCtjsM@lUefRyCRAUsITultAjNI~$m9k3#?Mf$_QB>{@)cLe=8l@g{urdC z4?Fa?zdP3TT{aJ3h!KJy$?OmPL*H+ z=x0=3oHV_&gJ$sZSIywpf86w6{Tlx5akF_cZnln5{CBY1Je_Vg&(H(#lx0l>UiE(> z?jrKZF}{m!cPSGWPqE@c^iM$E54gJR+tHimkG6i%{BrQJ`KJG>IY(Rl1=rP0_qh&m z4+MXY1$#$?m_8DUpa3vvF8ynBxgLnV0^tY<%-4`GZ--z%M3P8j2VJRrp>+&P+yM$0 z(OMcre#Ajg%>hyu$G|Z*=jR>;FhAqZ;<#D>ko$_~(F4HPjE}}{<$UlhHx2xfAWJ8^ z_9>z+;f@r5njPbLzp+dM^c3u)kdV6}nk~vvF(&WyxWbH^Fy?Pyo8tQ3)H6WZ#*?P^ z{Ks)cTC;(&!63dV-8 zQRI&SYjT@MH~j5;+w9gS`XoP47F}glo``J&I>n7KK02QtKcF|=sQuqa^eHG&)I)px z2yO8r#K(sNZpWdI)%L&7@4wXip!x0jSIyJ;E|6qQ%m#`@x0^pR|6%jxd_Qg(*@}Zl zsRKZEfUri=^}Cp;a;E@K>wEm*HPRny^mpgq@Ck(fZ#G{w|7`#3=8vBIY4eI}E02^C zVog0~ZU1)uGIAF%~GvX441{2sjB9@B3x+Mg57;cRmL-#ZK< z4$=SVXulckebw|(`qyw9K(mDo0GV04&ykT-p(bPdt?}|bG-&aoCJE3+5>gM0$VQmTQPI&e7C794eJ6-9AUD*AQ?RkL%N#6zc8ApNWWf{jf zaw@V?n+rg(Q7)xvFbDFxF2->Jo?m0f1gujvm1dlBK`mFXKpCcEix8O^cq-K}({%mdfyf z5pE$90h73P#~|K-iD4nL@5(+-TTYDF)m_w=2IA?(Oh!A~PS3|qGrjAjygmhYl$nd; z$0T5650rx(PiWGLN|`zt*gguC^?~Ks&=)y8Feu3VNxzS!>(VdEZAKBGeXL;YAXB>$r1p0*AzG>%7mcsIwTU$TaF-lD34Y{ zPa&^au^tI{!i663N3m+KK=%rSi+-B!c>bp;0*mzON2THj-(j^3Yx+)Z=ZiA@As%et6FNFdmC9eUcQ@u6Q|CcqtVHm!x~Q zkl9(2Mdeq&M@N+nn}Y2fEt`IjttcG*uL`jiShJk#c}6!#CB1 z)l1((ngr=R>+pxyx)GpTWWVvK{0n!p5p0&`=Qx?x8P4f6+-I*zduYvz>AT1y{OGi-K_BT|ojn63+7Z5ll3G0-G!bm7 z3D{7DTadx{lVW94J&oha@)s^y@m&@u@9#lYo(SnJN>a9#fA0CQ<4OY+YFY=-c9HdGHPVi0Q?51P z-bwvf-YnuJ@ddBG`{z5;u$J4KjZ3`!1hab`7BK}3)0Zu9li}NRx=vso!!fC3|IBHS zER~%UeHZtun6L#7OXC&yMP)sN3q8hO#^lAsb%*PG>vG^!Yd@{J2nQN!CqJUNvkx~_ zzASx0=REoiN)h48nHxl#v^~iw2TXY$$d;2ZP6|rI-UJUm~Y_0`z#0dg*$L%CbGAI!7uWD-eJFza!~639_=seiHb= zcGA@pm-@`6K8+o6YQzYuK-I8V#Tkm{H|9{AlQD1=l=iHPs)B(&SH1lPGwDInnSyOE zt<{Zk69${#2e=d7_Fo|*PH#!qGM`hx%*OBog+stpzR}|K#+lM=_LGu#U_rzx`9U@U zXJBPc2_>Uys`#ck1cbIiy_-2FIFOAz5wD4?4GW7S|12}(B zt9LJy!i90>zu$(mC^rVqcAREc$t^H=-%BcNe+Qm3#bl8|-f;E1vAv3C`D;Yd97>>q zmFar#n0t|3gW$u~!Sf5|icG-v3fT&XCQ1)DO^M)5ws@yS#12;19NT2}?wo>$?Rf7N zN&mJR;dP@|n%1a`_oits zOL%~KapZc-Qv>`Df%tPwbLH$>k0`CqMWZg5plzX0N3C|tWIx;V4Y@^USwC*X5GO>~ z;d5%mTI2Jgxe`V&8|d&%oeoq2w=&gzzN&bPnWCulBz#nRG3*xOz4}UFm9tjAy%Wwp zugVJylJ~#+h^GC6iODBZY17=ia4qsbuF{?C>Qq*Vx!Z&tu5bKhgYS7j>slIwCKBYJ zqIRakgUH1h>m<#}K!QBXUgHokyMZ?rIpH)etCY+~85UM}rUQgBJymM>zY5!DFGjGG zEqVR7D&mqe%$lw$k-?cuRnbUFB^X}tnQWiS;KeOH!kVoxA?58RvO@S=3jg2T&B4>A z?&7UR5}Hu}y9A3u3SGF6g}w@BXL`_<`5KTtS(!y>e~y**N-bFdeoBGNO^g3?j~K$PAJ8jPtKk|22*UQ z0`lW^@-xt72bpM3JErgpgF2s@r0@rMG{{UrfO6i3m+S0Of@}%rv1N8{Su{b?L69c3 z+w)UP7gml;ZtH|AyBupjcSWddSFiY7mgm=JuE#UNEkP+mtYZ1U>QvKI&g!OJ9f;HK zpD#OK-VrcEK_N~>qrn*{GVNV1y`l{z<%0O^3A2r+DCeP_(GcB1pDeX(zDcE5f=E^I zpZ5?Vm^8BQpFL@G<>C4Zi^kz6*h=HSyEiKX&!5efc+$|c>90l=?uN?)-HZy|nnQ2s zD?L=Xs}wR}TwkiIVqDOXw1E zweZEF(y=jzFc6_cR=Nr6foLO_Fwv5zDN|pF5>)8Qj)n+ZQzPn4H-qmx) z@A8P@4q%(MBb5rzvc1ywx7gdMkPVP!04x(An#OgDCK;dDM}yN3JSTU_fNN>$mMww{ zF!wz@lhV5+bKG*ND0ZErSj*8YqM|*Me+KKAnit&6lz*-I86U55#V3P31)q_F!hW5$ zxinomSyfF{L_caXGKd<&swsZd6}0pYa?DQiHwlphL>1USVe@cKDqIXTY+8T$sNyvG zSyRNG#nF(R{|H|DUFe6xq!PcfI4OG{N2k-gw^(-<1R`V2@1|E1-4WI~+f%MrXa#}D;Hzdn5QX6B zcqH|%jd!TXp|kCJkOG*+kNZz{UYmANs}1t)V7ngD=*_|+h48wMQUgJw^OUEKS=9$I|L%xCO6R`j?<*=KqtSGTxDWnC@t&Yto^|4-xHjh8 z6_S=p)>-Lnq@fG%oMPg9zlzerTf=&!#$5oGzW|Boe_*Wwvc~Sx;7!qh74T7x6+6wP zKXV^8r1yEQlD(qLyAP&$Ps)Ww@cMo&r{HL3+w;o&O8v^sXPg=@HjUpyrgcGlTY>N+ z+Ua;dO$S)rE3=r#Q}ucj%13s5-)yaL&ncmID9aLkihcy?_Qhxw8U7s;w%XIbTH{<( zaSA^GS%>_nd5Oq1#9fx1krC$syqd60iM`P>-ph7gA$Bo?&%d>OFG;Kt?S)yKTrjsA zQlzJRKC}i+`pp!7+cM8WoieZ9{;rwcK_4S8WI{i({q03^sR{e{{L+J>^fNgjzJ`OH zIYCHjMaL#>?GpthK=+h`52aoiDybFAc?N$wzddchFn{qO6}6~lSlGl25(%f8|DU(? zNsS`uW4sE{-&2vy5C%L&#*iH9&&B-NGPcV1#1JV-haN$0DOg%*fjp^C=jg;oAGC0{ z^rM)dh|L;xHb0E-!d4UD(7|*y;q(xGlH?4{G>fIs+v7T4dP({`uA<*bPJ}nR6ouY< z$DjZB3kSiA79hUku+bskE5pkA^y11a;e>>fU2Lq!s|Ss%rJBs$1&0tr;Nzr@1><`U z$l34jAo}3S50%Nk?!;upMlw6(2oZV~B>pE8m|!c{Rf~(&T$*u5R0>cCtA0_b3P7&i z^2*mc-B2(f!0Ft8;lINrk}CU1Nc|(_(@&+l+Kq8i!mD7Bn*G{eQ4>US6?o(}9vwa) zm=vlfu?N#zcMy}QAMD$Iws6je}=0wJYq{W)@c3ktGO0tb3=?sY9Y(LpMDV zM6QrM3+@7lv+zkUDL^LwcV+*z2DroUW#8!D)spxfGtA@`Kh5OUgnn@#HORF4OO&)Q zK|0v)mOBjs+sPJKb81t#SOX16LFt}&UOD7Z8Q1}iUFA^#qg$$db& z`)LstathnUcjZP;4~|W%tTh^)B7D_1qV>kK>wHQao>z1!MQzT&ok3{EgqqJ2a${ia@Dsi3%w;-a#g z_^=bq_}S%4(_7TnF@hL=@}q*z{M4_IIz?AaCk z8YI=9w}$8HiYU3ry&zXh&wt9rY%?VFEpflHe9|vcaN>T!p*Z$;xs%)%qLpaZI;VZ^ z3O~Sd50B@chvIYw-D(c7M3GN3W%i zXL;F3=6(|K^f9835701x)!<~-^cE)9+@q3z1@@y?4 zWCgFq_JwsSS@e=$z2{D<@(~Kxm+$wf!|B@i2`*NqXP>bFS`o&rl&&p_rA?vN zdwL{VU%l8}cL&?rJn3z9EFuUjvG5zQEia26MsA08 zmsaLRR4YP`yMX-@5W)JM%~#?;N`NPRd*d#YoEB3l7I~w0AEx5b`^|fPO!j&azSq5e zPDN&oZ3V^6%P9ak{rYfZ{(LM%)4%h9p5Upkvy z8J?Wv^{truemwJRZ^4PQ>lT_g-CV2x^o-Y!29iWM`NTcsJ3`#A7 zc@{GrPZk-PSx-0X>Yqr0WY9ABN3CNay>0$XWrMA=MiATY2Eu3B?q_4+P3>u3?PJ}g z#keZ)tTWy-nxU1wfH2#aXy7P@rzn4Z-De^-Z+CC|KPKzdw60E3`$&CfG!e~RgX8!P z9ZKA`N|rrs4<|xo=+HBc;eyI5(WiPFCA z({0>VgP07$CgEU~#Pj9$IPm$)!Qk7d@w%f$ni_m>I8BvP+Jg@rdaw z5U3q4?vBAf?+FSajirrsQwJ<+vK;~GXG&N~`XwUWLn}c|?|5S7?tNS3aBV$!am}IjYKiI0>+%&j-wR9p#t%OQ$u{FP~(a zt|Yq)4;tmY683H>!Pl@)3;B533}J-rpF4dIB7(p&ro^qQv-~k7J<`=KTyAhdwPbZd zcQu$&cT0i$qFq83uN5eKfy`*499ABFN?Vl~n^f)QsDARQ;SC?~Q?=m{l%}?H@r^ZF zbUeztvRrauE+$#W0rBEHlkO)>JWo$(WRHqdsaMH7OF=H5@7mEeUp z!?^h0#yPczRUdmC#7f&h|H$|c0y($eJdP|HJ-JQVkcA^`F$J#gIEK2<$sCz$c`9-+ zS9wUe8mKDQ?g>)k3Iq33{ppa;bvsA|?Bl&U1N?6f^i)j~z_rl4>s{I(5JpoQHgwXD zOuPpNPkDxtbgp$H&&(^GeDd!c`)9-mb*p!r1oMh?af#IcCa1;MsI(~g^Iw6x0(spoIKGcy*YwEx$@BI+!C^?-!mX8A^$ej+}&^4{|(7weP1O!YO7}}$Mpjw zJNE~F%4sf;d0|I(D7Y*b9Ek_o+TkG--wBKkWDKr=LH+E z-cOdn$s6Nkqy&j80S?)5T8zySvLu^3Y68d)SVoO*@ct%lf5Y8uNE#G03@4U%k7Kwe zc$#0u7Jr7+VT&WDur*z3X zTf@Wt6JGbIqh&X(h$)?2D(QaO;8L!g4|UHx$81Hm3A|5diFy4=3pcA`1FdVwCy%ir zeXOzKf>OO{=PZm}<8C7Lw9(%q=1gE7G|@-ZYzDV--_ayl8;F^sFmZ2s-dcD9_SvSA z@H>nrI*ZC-AR>}wPu(${ZQ8Zu9p!okjgn=2YJn(axrR>c-EvCxgvu%2Gohs@G!z;A zHArQdY%s$*CF>VW=B_Gif#D@0TuX)4{b!)*^5XIoEn%dhoc9})?coYF=<3BM{`KJs zr6)3R&!sA8{r#h1Bir!@wFZ5_yJ==Ld-0|wE9*{Y8JXhV?tCBE_t)h1;XHF!#{{0R zi&Bt%@^}37gpD=|>0(&)VB~b#?9{M;T5SNdxmvxdOMg2p%}AktD(d6ay|wBAKaR$% zrXJ^0-2Kx`=0%{E9BD=@y9D;j!k@S%m@vWXmFh)q&y*sw+k_vg%NJg@Y+kE-HNcza zX8m<`{wPMrQ}FH(01Tm+Nz8^6e+OlyORC~iKFOMIerHzI#r_@2foi@Vi760wG3NV z?wFo0qi%|2DPolsY1)MkDE8ELy#$g;cLeuVELzkG!#94F7Exjp@vZJPJ8Lw`JHh~RK3v1oGxZ11lq37gj zw_a(uLNJU-IQ+X85zta3D(+XdE@GSk>oZ2cR%Sj=Tz7IFgFI0`y-z|1;eUIP0^=P< z=yw=6FpKqXWVe9c0Q+*91cYLCj_D-_M?NKdGBR~dmF4!YWQ_e_1X8^p)yU*yPcAq| zNfAqj4!%sjuUVwx%Mvz*zMGpyf8f6TWf4Dhb7OH6&=hxoNh4(mf&v#}N}K~KZ1EYR z$$xAmaT?jWaCr>=L+caWg~-FU*fyn%^rZK&@FhNCOL~FyMbGu64=VtBfj6c3lu`4j zByaZ@XK0P&v|cT2&3t~6xNh<&$>g<++0F1$r(g8iOSetF2mmJC#2r416>^IpQtCFi z_t`RSgf}FQKy|)+Y(B>tPh;ACkIZjFCAtBxR+SLAXR~{iO7^Jm|t{w?g>rD zQUuDS-OAjHj`Y)S4%_K}12CNsA#Ipm=mdg?&=bGCCGI^Iqy=6F?5*ZQ_0fl49Il2c~KfeI3%T5hDM@2x)kfCFV^E z*ZlsdAaD09G9rV)jULclh`XRtHfO`+UDDFQDA7FH?gs{u8phCC{C&68il(x78aU_F z)U5HMBTZ-z_~_Oj3q*MZUV4y#uMr>xBq`gK#=`uoN%!qg&2m=}5FSm(P+;o?SS0(m zs=X(kN@(7g0Kd_XI)?z=N9Md(Q0ac?t6*euko$^N+t$OGTz+gw5`>SBW2CdB>py!u zpDRvNlEoD8aqtOms1glKzq13t%%Dm77J;s1jHZS*;}X!rGIibQ-Hu7kAGjX$Y+R>W z)c;Sd-wd}OiLZvddwe?Z53xRYg12cE9HoIYUU?gv3AOiM#rJrf``$I5Z@eRL-V#`!KD%-xyfj2iIs(@?!Th252J;jr82qq zk{Z)isABi<6j3{`RtbylOsi66U^kyG)MOGPc#+x*8=|<^=^kh0cSd zF{)7Xw*M=Z!lqi4JnOx^rkv&WfGyGE>79N{Nef^g=fy zZykp%34DcahWuWzTt&wFw+4jR!NJ_W2y=S9I6(0VZ+SX(&{-u>a79P8E=vxy>&dGsu+Q`eKALiCzeEAb z>Pb)<1Id>>DO+rgxWN(q2p4l0nw0z#Tj*)QkrO zU^x^$EdPn$-ub(nmS^NV+E-gSIllvRwFK{~Z1L=tPnC?_K&580DD#yNx3R>8ZpTsX z9XV|?OL3=wjqgQvjEq)!4lVphEZ!r(@oqiu+TX=$NKWG{oA}onzX{b!W>p z)W(EGjp2LlQwC@W5*KSQ%HIQ&%$Pan&O6Ks^`rJNRr+Lh%jVr>E=&cu3OJ zi?T%vkl>z8oTI&x}V>+$v;7kSC*b9!Gb1VC7lp`>150D z1X$)ecs=D&8Gn5*grxJm-qj$vCO83x`lupwGzf8dP=hr_&)ByxZd8}hZoG2pT@H-& zv5Q**1Yk|kM?*CnZ?PHwP&UR_9ijj7t@Q9JLhx#==kU_Mr#g%E2$q{sMfzy=5JGlJ z2&VIUoZGby-s(8NU6Z5lyf-28d~DdQp}bgTzGV8bxIU>r^@G))gW#g85_>1ZX4!tU z>A>!5Gb?w})k8A*)e2)8Sf_o2+jA;&Q3Bbrgo=k>-o7kjFO647;VEac#b9M?J%S)j zQWi~)ADI5D#D0_feYg0&m6%BG{p{enI2e7)ak(W9>W${)zcp1IbX*`d!`B zE#l4DN8@F&s~e?@MhAq)d0N9)H)KQRU8V#g7Z-s2LV;TR4n-ln5sRA{<468})2V#x zueN?eyNi2nV4V$-@8uy3Vk|^v{32XelX>K>tl@S4;jJP0eX>acfQ#Yj2VsAR9~4tl z3RJ6*oI+i5n>-Nz`KQG3=Y(Ex6BIi2U?PI`dhNUGwvQ;1GtL%&Es2(J9It@G+)R>{ z#g_2aan4(InAMyvI0(pGv+6kIihcV{Na>Fx(&_{6+Ws!&3b+yONKXqI^hxorzX~2t z2Aw;jT!BmKAKboGq6b6KcYTM5%u#MxaWSDP67;uU9lwZk0I%pf9^wLq44~`6eV5kt z_3lN3z5sfdu&3F*znnu~L{VT~H^AABV!P@FWfRG}ZW<19y~oTNB*Pb}o?HUULV1t6 z{oK{=FYed++-&S^dzVdi>5eC?Rdk*zceHLFxqbZv1L>d6=DB6TuEDaMO~c?LHv%yc zz>zL={VZqfCH|qYzvIyj0tdgkhoV7)eh%|AzRuq+BW+N@pkxl&Cqb8a zuQ?f7gemoW5b0yYtLyX1V24iq@vDxZ|1f*cVVaq$XgJ~((mC6ezgvRi*55Lhg`~)! z<+@cb2C8+l2q3>_)$VWqcDtd{_N5DHjhFb20(_T~A!FwBq{cxrhnMCJyr31Q`S)=1 zsF$e+Mr4i&qd=3v)xi63GwU}4HXxFzDbJ5>XwfL8cjuq;t-hiZt*X)s!-+0Th>@c2 zWuPJJ4qYH@-V~~TOesoB$4&J=y1WDNC!6$3wFM1-un2G^dQwnqJveAKpMR}wjN&AgK5YM^$X&kk4;X=$(8ZX?KbN0;3J1MkYVP4K5w9Q*0r~K^`ph!nl88c6HDFG0>hT~ zdfKMwF%A4ZI4t-3grEbW{%j^{2D%NQny-*~Dcpa;URsgPAzIZKSTHWHk$Lc)l_X@U zZRknlZ2Buuag}@l_DLFn5m7{e7t8MG+UC`>k2$CMrB=7B%MSKxU+jiy?uJB&vwIPm z(I4oJb~Mv{PkvhGTNU3zNxrv%=Z|Z`Tz;j3(~ydA@`ItSgzH~V5+f;dMRI5;RN)5? zqd^AC?=~X|j%Y^_-HK$pNXKEsl0N7c$G0&ZDQ#u${J#yyw0~fH2+!R$Ph|D&S|*1F zK!G3immT=k^Ow^L9>Sjf0k=Yfq&5=81?Z+6xTYExML!-fj?i_7 zn9oFa0>+--(i**^xGdFm%l6nduJl7T@?;!iXW;L&BK-*u&zzBE)ZAWB><#)Is(3yC8mhblN+Eq+e{4=tgPmAS5 zl74bkC|2Rnb@4fHPre#3aZIdl-gRk2KQrO!QSWfMf>E7-!ef&@*;62Pxbi-Q0=e+; zYf;&!z*_3!oBjdY6*;UbnZyISu1}{D^zZ1$QBAy3>x~eeOS1G3S9G7e(dB~^NPYHf z9K`5^B)F3BT*dj_o1glL^V8ZGwX3tJ8rTx^yJlQ{Dy#m}7&U|8 z+g*x}qsU%{WXfLjjkS=x)=mja-QGuip z@hGx1ez>O7M~B(VTg-kMqH7;>YDay?0wi&!aZuE9k0*v zwldA{wEJh(-l(3V`Ki)IL9I-Hd6Lm|YmyzGVWl_PmiX`Pd+#4f9Lgf*ocFY95Nm9? zdCIMMdE~iz96IQQzzwCNjFRu74jSUdWQb+M1pAmC5wp*Z z;mxg6v*r+HsQ7<37o6L=5b=A;SMN{VMkCRonI4{~{o>XV>@SC=oABC|$~ebBkO_sZ zUjY4RSt#(Z?9NaJUdO=jrFZsPe4xX+N%8*ksnDTa{?CB#kumw_=@V98=0VS9y_6!*|a)eQTO>a>4ZuY|o6K>QL#+Yu6TM-esQODjmR4qX zAv=Mk@FDuefMVn!q88_kA>!*5_ymQ}V2sFaPc;Xw^3D$O9-xc+(vH>w?tH_UDkC@Wsx!(lprdg%K-{#wVauWYM3h>R=Iq#zjDWi4UCuGDGhzzNUO+{?}#bFNo>|G~b8|GZk%2@S@jMlOz| zaxo0Xh=DTle)4P3&(B<|5+BvP7ky#4Il)SFm0^c;h!^Ub^uf*b#k z#+cHZxY+T@n1%^Rp37WA^WVMt1pbuvNL82SdEj8uoLbxCbCJOp*1Bt;pqgqAdwEIp zWk5yM<{cKMhCyLSXAOqSG1#eLu?+LuIaAQi*8om!BKfz5dV9GXRH|=w^a`_x9o~zk z)&@D2KlY6Lix6T!?YG6^>ilrXna=%;yd6SGBZ(^68$8iBiOs|?2Q9Y`R1hE8;4x8} zbD@eP0MIL}&+iQslp|YyF%m~MzQ8{0iMi!dCJqrvBO^EIA<)IKl}I^M6}-+bNr-pR!8V!Jwo6V&P_H*axU`cR41vGin%UKK8n zKtF##5%KC;#6y8Z)>MW_&3S$?+{_!&It3l2Jc#8zRlx6bz;C*dkL{cOR|R4SHec;d zs~DZ(S7F|gs9;SZFZ%ZON9Nnz~p=?H^2^PHY!@q8#~BiVpU9)PvMpBXoOPr*Io(xNrdh+Ze76NB*W#|L|UJnwV_~()uPTJ$H4DJM$cNu zoFJl}<~9}QpYZHZM|*X_mjQjyK5i!k3RJ0P*F>l#mhbRE)qzo4wQpQ+IFQBiS4hs^ z_U3iIYsvl#o`*^UPlunMt(8{Cd3ZuwV`Ww`-GvEHhSWOtHL?x_);=DJcmxawU>jS% zvHd$Y1Y; z%Gh&pLveZ%yGm9`Z#d+-6b}`r|BQgp->sl$xt^;2+5YghXk|P5f$M#5apKg82AO<_ zwWtRv%KRtw#&?p0XjCRj-R&>Y8jEVw+qFf#JWQOB9@9J729S=2k??L<=>~aks4z{C z8G@ke%qxf(9k6>8k=t66yVMRFrXD$>?#Hv=sg)jTuyj0okNL*y&u{~FO1YEokB*0A zCj*yf?+1mbLW2(N1M4>adCz3Z`gc+s9=q9J@pGIye|g~V>dFA=6UYK+T{pV;w}k~T zec2v;)JzK4+?qU~*o^#V^SF16hjO~-lJ4!DKK_EbJ7)P%lNcfhCrmSsxh&QaAA6OI zWVjk1Ap`r4iy?DP_B1geVt2#oaGFBY6!_bAhg|^#mYGSZW~s;NK(RTa+_|FhKLn0e zW<%N9t>eznS&3@%){)B&^GbV@`V?wI6DD;-9+r-ql|;*l2|)&NT9C~~{VPbGZLGfj z>}bc~9j*thM6f3Mo!A~B1}Fvi|V!c(y)nV*QOH8ZpugObanuxJfu8Qy3%d$@zR)|$zq*aJVs_kG_x!R5MUJr zV4Epl8O`3OJ9Ez8I*WC=3$NNuY_Ax`O|^yga8abvptan^TR5KAk>V(g<7SF(e|~E; z@U$a5-bKFT%e(z23tS0b8%UkYAC-~k1nqVnC3PmK>4Z`S`^Po!In0LHpvJ+H|rfD%-z{ zcQF3*|UTMoRK}senHN{oKmtW zu9)344AMSNb2!i!uLO{BH;B>GWa#qYlz^%Gk=%odxi?ZnUU-+;&+={U`)!*}wNvkf zaE|!4o632Cs)H}MH_&HWkv$eHPRmOfX1M2v^tVA69d*R~oDix#XR%5i+2qAV|1|1; zSQn~qfJc`bj`YH`hHO|zU;KN;8u-oA12M3i-vr5^ayFa#w-46lM<%u6TSt)vDJ5dQ z?4ukRVoJTE9tsOaQC+auNpm~a*=cNie7pClZ0~3Ve zab{2;ggvmvotx%X+y;5xhuivRL?(@ZHor4aAsLwB@$q#4onQgFWd}~V8?agSq`8ib zu>}c4njb)zJT}p4(iLwH&jjhZA7|^|wa?QPJ)DNr`g~DJJUN>+qK4npcLrt`<|7mx z&?Bt22^pY>&#!w)j{Ak6iDS7=O+Ol5?9z$oy`i|mIomy@ubx@EstvkC|F%dQ!mTe7 zl2ZjXD&pMK?8qvLTX-;y223NywZ;&4(uFSX8rx6-j)gDeR}ULWQZZSC+3|WjA#iNh_UM5$yX23 zj~UAol(tUzb*1?gPE)(!aEZDJjF9XLBk z9=-m0KV&&}ynRTxD>aUa@@Ytie6c?%-!-GtC4g4vhG+%I5U;)K8m|lmsMfRM&e<=k z_|@;4pRiC!fT~))*cK{4ypaBNRRCv~@7KZ}KIF=(0uSPn1P6r##lzh8l@Q*vl>q{+ zD|35w@q;gQh(sK$coc~PMl;9q_|Hzjr_7iu)6C#9OYib|x^&}K!taP8IgSMw6JVfd z&{Uwy4!D8d{LeJ0&o%C+KDZe8Qv!8FrXwQm_mui?t5NQ=2a$@s?q74TNr6yd#4a+5838hPn&Zp~-qe5ur6vm6IH1l#K+}4+fAm7-vMclU`Lt)Zu&>aEaXR)S1}>140+adyybIpk$F=4 zjnGtzIu|}CpMGbe`60c0@n!IDvgctb4jIGTq9;o1G0O4Wh203hlP5taI#8s}K9UZ7 z@fB1mR|e=mwa>3HI2AF~cc@C5+6^97UKrH_p%-)?mw+hjuA{C`hj?0FIz0)p^=_-U zEzr0l=%#NmgG@=6R`V0H0x5NYa`aWichuqLaNFJic~9lkx7DCBq)D7e zdt_(45txji)1QuEo_3NY1%7@z)(j~JnG1m>T{CMA>dQyZwF8`GeP=kjFQ{IT?pemq z6cO-ZL)r^v$rrF7>Eq9P#|F%T5l^CmTL|W3@>k<(H=AglbuOH68k< zaw8bfXn7mz*S;v_W+^sT`~IIT`Zx|dRN8I)0?Q(w7W5@HHZx(A4xvR`+WY>8#jF+|2nr4%TZO z$GEN=q(Whi7??7CQ33TEnMhJ9a*B>Y!zRe70<%CRWPLzZRS{|cGBukF1MSnd9^|!6 zEoa+?n5_7$(9!|2$-GAo(|1^S zt9oyi-*>6JoOd>`oTFfmwKoWW+?W%U}yf|&rRiT_C1J;Efa8m%StY-(eqGx`0po*C2dVp5xyz9 zzNC{ep9~<(hV{l*Q-VhM?m~V|> zOJ~pX5Cvc04N#?K>=oL^*=H=HcM580&q{oyV~*$~E!ssDC^4Fxy8hUv&0Xv{Vl+C7 zdMm+O8^DDsomrf~%>fv=qXAd%4lRm*i&nBD2B39*NHbu#yy zRdww(O4s1pK)TJn@Ql?$#e5QRRgD>8~MKF{i)K6mN`6jy9!NM`2ytd#=2IaJTykC#QH zyK`)oeg7zztK?U3>{DkL{Agx7?YV259KY@%r~6TIVzez`>Y+UJXn@8Tpw@{8Y>&R2 z6HD{S$gTK+AC{f0jWw8*J@DMcU4ygDNIg=T`uC3LPm0Xh4PluJm8hoH&syHLhQx8ZULSCoA^|8VLP}x$4(hu6;gA6pe#Ra z4!-W!S)EJe^wXGW-!KqVW$BEKomfocMN-P=!~T8_;4~_dT198ZgpS+e6EDaO%JQMOvOgXrP&75k0$KV_8*&W+(2F>nJC9= ztjK|sK@NS4^SQrB;>}b!fj^ItGQY3!6&`)sV*e8_vo~(Rps!WVQcK965&A+nw|A_A zc%(?ij5zkI=qfMYcH2vMfzNLNT$dX9Ad=;wqwUnRub>cT+rv z@7iB!EA|eboOMS`RM`=!+)(P0-U)a^`(U;0+hCTJC^dN%b-i2VVkQKC;!=>qG#9*#Jw#J2 zF*@ubpUQ&?)e$$^z)e+f?|_UDh&z5!?w5y*Z&%graT=jFAYTK?0BZo zNcTQW?8eYGjJD0F>@#gc6d10@57<(j6O( zl1ev9OH1cyL`oV&V026O;)BjI_Emqd0rg{7Z=+9UROJwzNHYx%6(y> zfQNtMbGbKr!xB#~c(?W^JV^L6eO}NYcw^x(=gvax7lEO|L`Uy|iuUNkDB?k%HpaY? zbg~>9xrE?K!!11{_4qVXyWc`WuireXW-lBq&`)=N?0G$_mUlAYB2nr2PFCZ|9R7*3 zrKw+a0F2U{i5x@jdOH`j)`}a_+_D#`So*uz{oQpw?k=aG@JhJjPKZ@#9{F6xlRq88 zOKO$dD~VC_gLjbG)3N~Av!igHj^8`ZcZaY?b0};(S7rVD6utK+tD6n;U@G|U`RajI zkEuY{Ll$bMP5gC?4Tc{@Ji5#r?@gZAIxbato=tUmGnR91z5U@&7$&pUzy;eTJlwrn z>%N+t7*iYxUP$X0Y>#;E6C~X2uy{4$&D{0#_28FA(LD@#&*y^22c)**st3K4C(^S@ z{97=nlDMp=c-rpN#B%tNCI#T%J->g*Vr%wHn>Wk?6w<%0Y1nDr1RhXnyeE(8ji(>p z)HHMsq|kNGM!hEIfCfz-5+70Xj+qh#=9LiXd-Me;lrQlT zoiv?U^PVj5_e#-n(FXn`}eAddPyKyTWQn zLe_QXSKNwB8y-Ntd$Aom7=vdz-+whImb1M(*P)CcY(iSmQ?>;L)}gp%{EtcPpi}jX zqx5&Nn;`v11rAGA(k_&5S5zeyj4joMWB1OqJx*A;-5N@-ihe3S$$8qDz+#xfI2dY23+nTzkqKWYA%mi(TYXA=WN;0R=ZRSy8l0n{mtSFOHXqs;^BL7WfX+gY* zQ7XLx1JRe-XI%Aa&W$Ioc7TRop^n$DbtRQb)_;2%3B%PJ%53?D!A!Z$IX?;dHgE>q zSc;*r#I?C$(?57baVlZpZ#3Q`jG+PyFE&q8gsWN{{((dS@skzzDM%gGhRFe*oPbf+ zaN2+Xs{xYFklYVHXb`r4-t8l`NB|Vbnho{{rrvBCyiHt7|NcySrZ(+Qd(h9D5+t+v z!BHyoPQ7`2p%)w7S$EE{ICYNq4gK<9cS$2Ei^1Ut-SOGwp7#G|0i3UOql8%!CI#y; z@ockbmlZYT0_Xbr_crw3#3$8B@PIqWfCTV&nN-P{=y9K}zGLbOZl9^ow&MrfFgj2y zP=`Q%&ju{Qlq58+|6O1=CHg|?BZ_n{J5XU0`tMN|!FDV4Q){o&4$-WK6^?A`drmcf zF`9-;C^ph9yRHXg7~v-C1y!8oNpN#0payo;!r>1N?%CfsJ==i0@=&mOe z!=IjEMyqx1ZuDcrf{wem!xBRSca=-ZRnW$`D^|2N*pUxEo`Y;6Vot2i^Kj=k5G%>AL<@JlQV79Kn zW|e?N!d;?eGzC;zL)jOtrC4RP6NTS}J8<^kvlgy@fgprq@=Nu1ULiNzt4j%<%pPNX zeuRze(YLG9yBm(-BOjVGS_@bk5Z*dLp_4!xWZ+?fmF1cV_jX`qEK^WMbZz@i9XhzR zSFlgxm&_VDPKeY}@3h@BIptOp)fKnW?F6nB32IVl57qQrA-x>^HNJL~Vy(r={7bqe z3%ksD5G$B=490%?P(TZX8vC8Ul2o!P&6hOz4A0i$n1_L^(^JCq*F`+P8Kfk6xTUz7 z_#&Wv@0#%4w(xAY*cA+>8+D~4o0HmhUoO>O=&0cfI@e`^6JfM1F*{sjlv;nCe2sr{ z_0jGD;L01OdyfsfACnlSo)f4^*(i$?K30itnSaWfX-OR?y7@kgXOgfB{A7pvjrUdMlIau|9z>p?K-j;qD)*Y&puT>}K zET)*Dwtp-c+LAr{s5J@Ar)Geb(6LZWJu`yPKjs3H_g8CwG(j#D`*x(q{v%*LV`(;w z^_dDuBT0f5b7FO73_W3Guj+dyRy^MmFEBydl;2)Rq1aXH?)rAvIj&99**9X+x#x{O3!V&n$lk?DGXRWa9OZY?E*sp zBSHr^im%HLSlrdmg?0uQXvr*+N~Rv}tB}6^LUMG>#fi^Nq}9N=&NwKZUF-0#1z9@m z?~hGI3wD-wc&%x672p@-_1Rl=PFTj3T84FWF{+r!ipH0)e=bO!qsjc*1V?J%xm>0` z3t$K&fBu*L+zS2b4|gcr&*`++8L0409!#?9FFxzskXe;pPELLq$iN+;Yz(W*`h1_F6e1`39Es*-#v_f%MZm+53)B41q% zy#9TQIWHhm*?969TX8;_%wj)_QYx#;j(Ixo=QRfwpmCbqu}9+qFq6|YuLS+wQ&Xbj zVg15Tzg%-O9Yq0jJ|?gZgjmhu-2{P}9UYr%9@QQxLGRrbM|HJh+mCd6A1SVS%eqow48 znpPCnDPGI=GWx``nn$d|u@X0auZyn981DL!C%to}SaU8^O{;Tp)iL0AMAj~C(9BAN z%e?VCR@ulW>^Y^8e6c;Jm`s(4*{3jnaZvkYc73w{g35H<%$ru+#wOzHIJae#F-N4M z6pMTU*L`rIPoS(_UbO{A&b0VFMoVSWO|F7yP#{-%!Eq&^e$ zt%(HYf3Nd`EF5@47yx?nstT~|FosncKh6(umYDl7=O5=cM3V4M)P~C5l6oinyGSD* zvb@la{GEcnRL;bElbhj$t&_}$sy}l)gy;SReyvET6S6*SV}-QIkvX^&QOiZ(+=5FV z8K>C!M(Dg5dLdOoG&h0ULpWa6y!c>@wr7=PKaje1R1=WAe$QuuAvY_aAv7zsKNAK< z*K*43%gM?!l^?5>+25virKo|7=gI-|0X!+INty8IyqcmpP&hJVfL~@Hgfv4vEmk%j zPy{HKT|#vBMKEbMY0q>49SKmyCC+*}Wu{S=24FWt>)|X8Yhv=2+J}q5+bf!pnh6g}TuwZ7N8vTUCAb3cO@ZAiq^awR*pf}V8W;^b zImQLP{_+)TTma?A6{$s)USW7~V9ZA=Q8z3<6bGU=DHxK)j>QW2C<|;c3pZv|fbqrM zM+Qx9;0Fz?r~7es=shYhbI&ou1#XSyyWigizX+#-D{sLhk?ru$Y)r4Y06WKFf#&K~ z)X_HTFjL(nUC@PJ#dNQVPIz-^$82n()0 zsq5iN$Z+rXD$LmR$<93nXe@OF^erne<1Q)q1dWyLn;Cy@n#$`o95$S5Vx+dbp5#8+ z)lkbl5K!RU2$rY3m_AcmaO9o~8_YaTWwuwDn)68nJReSK&E@b0i0$u91QA7vov zn$u0-V)D3;7Cp%mKy>yHBNBdM+WKM$TmG@~&p5d=6olu1zHw8+{*2n&PMhv(eF!D( zh}Xhqk(mLb`NmwEx24Wc3XdHp9I7z-b&@3&4RXODT+VAz0cXGe5q_nK)fR= zqV0F%{rR?#W$muF3L=*mr+FgCyAc|&quce|?COg3mw_k*ZmNif+Fw>XN^l z&?^1q+A=49M9?m1A}rD<+NaxF{QNQBLEF*=0V%w`asa$K9Do?jGwYHdJ1wfp^`{-i`Qh6YNK~?~w%{>JTg*btU)40$ zAUGev{=ldNu8O4XBf;9E%_Ezg>iXZLbE?@}7VJF;DW_pvYBD_uO^}?j>16Js$qa6| zMbmr2Cd0((Lg>U6s)Gp6Mwq?0%OgBJszZ5SWLM4j<^`%6&moQ7DeyiMpi}5sSKMRx zW>Ma%ga^`!|?Y5)^qml$2h{6HZKWZc%`P{H&<}k2`=?kaN-HlJ0I^Of+2`y%=Sz4Bt zr2Ap^^T8sTZRQQQre}49Y9GsxsK->PlEgtAv@icop1;owzR7XJ^{IF43p5O#De!v8 zNN~n-7Q?UCZz~87;hT{@eeN%Jo?mQMhqmCq^54LjQA~2GMXz`QL5m!RUrTrF55EI2 zkKuc;a{IZaqal@)c=;V}Ez0OPKaT1fea^()JSY4_Wv|Yt8xMRx+OYOmX^oNWLLEiH zo78^NRFVkm1?^ug$>UtxnW;M`?i#AYBG|LGR(7-hwMgLQ_=E-2cCJDcz$v} z6;5ZFSHz8&OUHI&cGj=}e)&n^C{M`7D}e^9;0xYh;%pLtItShyGlj1mkVJY%$q`K|*_95y{xaBfMk4xkH{=SNfIJ27ckdmi zbVw`Q&=cQIV-96K%eDsH=$0<#XKP0OuQWj@pftM}s-TcT)~lfpUW4*j;6@Rr9x z2(j9KQGL(|qR}rl05k##Vat_z(QD-@g%Efx`vADM7da7h(pQ;j|JMJI`WY5gt4s!Vb(~VfUS_(BY0uMo#xu~z{4tp-g z&CwjSn|TT$xQIYnc2t%;BuL;xNp+(X7=WdNV$>qT>gN~K&!n!VCg>ue(U+#I$zSb^ z!&zCmu}HMH$IZ3joF0GAqSU{nF45*(ne`r5(}GKj-v^hKNDBA2!?tPcLv%iGxb zq6(R+Yo5r1`FlHl(Yr`Yq7AV#mhkknh$u5#F z9rKFvEz2{n^tMK{``z+dOh{wFTq`ShNWeP{>g3(x&6W={Mzi-b}S&q#4U z`=d}Mq5}YRd>U<|lYLY@A)r4P*=5X`!H{rGC~RMjrv)B(&r0VET9~aAObJjnkh41v z3&D{o`(1jH}rlPf;&awv8U3r^y>S5`^2{VW(rtoaFDEI$~X&Z=9O@J zLLs{X2F3_+aNY!E&kk?lYfD7q_~M)Qli_sCrFy8x&89hWOYw6nh8AL##PDn77cvgt z^ThRQ*kUcA(SF*>1x#7w-U%lx+kXEOyRU*girf2+}=)TGF zQ`{D-sUPLSBCiTz$ldJSi9HV(YafmexvaJrW8zEC^b$GL;HnF)Z*hqxf7)LB&@4 z0m^gcQW()4`wS0UC&tP>@GHx3UnF0n65l%Adh33A7x1*co6W4irH7u;ihCAQ{);OP zI#rov)zm~t44m>G0}U`|hMIlJbIX8I^W&-(B7sgF$-UjE@Gmyaxv8rHdl$-o;)$}r_94Q7| zQ^gD3rDNLuK?3d)K6?{O8KW7_UdChE+fo5uTx~EvzH%ulYSWGoNFyFSxlD)#UOaHb z2;AA>ymC$@*v+dYTR%FdOCne7Byu?lnbau0*h!JZkyZ*FyfMt-5c#jrH4{Ez`auEQ z*GDj?;lzFg5j_9FStnQF?s*tG+jDGZGvCnZEh66AXJ!kjU=}*divS|XPy0yl{Zb&` ztB^!xf$Ty90#ip_eC-KkwbL2DsOk3xE5wpLJa*~Ik}VY-n6CQh1%uPs+gk|n+NZGI zX{$0wQ2eI9$xzmV{M0?J5xCdZQwen*F7P$kTHYg7DeUaxl8C`wYYA01kT(9v9A-iS zFm&jx(dl$@-%kX4-Tg>Hyw#`H%ys|9MxF=Ms|tOWOQ&?W9m$-c#!YXPttAnp>Hg#P zbpBVlql4cs!Y`>~q#(e&blar>2Y96U1KZcfi@(^tjdUR{!?qPi? z#FjT)g;5sotIln=>l#iLFZe(_Q8i#z4E?l=VH?Ac2auM@+E>|y|FDygtGMzZgUfHJ zu`loZ^eq7LC3$ga6#(Xqi*!k;!OC|Ba9gH&$1Z(eITzeIL)`GF>&YhBIwI_^2B{f2 zwL&6&pPae34sv6DYax!hbc$$E0O}<}ZE&%JBWyQA9%K;oA{Ras5Bi4PNmk8iC=M-pm*QqN$#nea zKmYK$c!Ou2Q+6>BdjHj{x6?DjMPt*5TC8N&;XrLVg{xDg;Tu2!Hm+tM$EhqR1ktd& zHw(q8bta}h=RE#XPF56A6|=YYtRZIM{=JW`r1J$iL9GO*l8@hx3Ct@=Iji0&luYCjvlr8NK%0#)eu;^Zqv?f+66&3!;Gk#ay7zjkD)HKuPv`m^d9Ll>3y4cAXyN7d-5aE!(9iPm><% z_aH&!lyKk1WVF19k63cCy!H*+=L#@ESpDbf+pR~yX%m}@z3>aR z*@CVC!VEWX=AXl1e3`c)uizO8<223PCh~uYUJRHyJ?e!<7efa!p-or1lr=9{UBjC& zPi@s}XUyb@#v1!h{o+}uw3=^OR-P=g!*xdN20xv;AM9nhd1)QnJh~OUK+eegXz`fB z)t|w&%=bT+_(qxXM({T1SRK-iE^nXQhY0grY(5-^-?Bak7bNk_cvheP17~Qng;NN< zRb=tKbzRT2v_X^i^f`eatsmWkF(#qgQ}Nu##X>xO!%7Kh$ldy2-je^i`7F}&%2 zO_ds9$65_+^Czc+#HQzh|Ng6rJPuZpo#m1Z`XIhdnW~M0rf7ILQJxk4vDp{Q(MLOS zay09ck)O@l(F2b&MvQ>eO1XBMiJwW|hz#qP&n45Ld8E(C7|QU0T%D)W{6n$|N%i5i zmQ7{#6ZAEW#6m7$O_{dEGVjFLJpHVu$63d`GIG@lNRC-#i8%oP5f0`_hs9??K0@m= zAKwPxvUO3`j(}@p2ReyCg5qWeH-3rM&d`=H_V&!Hwpl0zuIb#lVaWhAH0h_y@4qq+ zJ*TW1Pp0l65|JPr81C#XU*mCSXT;@O5+DNuip?;+qrtiF43*wtJS5llV06*FiCIC1qAHj>BDA5Ew&kq*d6;3+UoTS<7d5WasDGPTnEz?zkG02+}5e;X*K z!Y;e?Fed&nQi^eP7wQ*XpxlAvB1J5+R32I3gyiEA>dpBHB8Xu1^SC#`Y4oScQmEZNVq&5a^O&G-3cyL<*;ufD{CZ`_ zN${VQ^iZK_Crn8b=7y=NYaNrhq>%W$B-IpCgqT5R-M*{3n@X;dya-KcziU>#u$?*E zJk3&5b5wV{u^Lzjc@ad)dDdzFQEYB+Ye<74yMz#@^=21-iWJaYEl zmaqQMbA3gL7yIt4nw3==P5U>CudUTAQm=TWpkF$rJ~Lp};xgfo{Z~@sm?ozq8{@j3 zZ1)-O12mUk%HHJ4la#2>D$gf|2JIK#;AxNR#%fcB?e4m^Rwb+X-y(~VnauWhK=p3A z?hJm7W&-hkrBsf8OV?ra^Et!RMap@NN-;yTZ-ec{$r@i-tw`edR58pa#yCLMoTXe- zy02o-AXzrdD7|X$*eb5+Y6h@Xjf6-WpQzAbHt#9yf-QfyI)Wo^;9*VE8sG+e!?z;E z0Zz}n#zh(spCt@S6Lx;sc~Z37XR@;T{_;zZ@c$VwW@^~uN*0Ial~GVhR-K`~j;Yp_ z^nIW%PcpUgFP7+F;nC6xW{fDOeNWXWgxe2s%Ol!#jDIu;4`#5vNTV>zoQIVMzk<#rC}^Q7rN zMHI&mR+w2YR*JRQzz^>344$xRhuwftU6;VN?OQTZr?fuD1r6LwaMl|vJygCHdI7j@D~luV$kcy^NMt~LOh4zl z`w*GyRR0fjKFe<;Hy&7LI5l!b;QJA}~>x6q8OUI#SFw747uGq7W zw|~roFue{^sD6&a^R!&)z9VH47YzRm*kb8qy{=!B93x5z-q1i#3k==TPC*Ytd8Mv1 zh=VDW={~`Z=PF$$w<|enxuS7GP!sZhmSk1n$W_|im~rMJ+z7x474`0&;Snps?`IS0 zz9V5caM)>;l|`jUwZ$EHGm5nklfUDxjz&J&8hF>KAvDrk?_k4{lp~$zkmYyv+V^WePN!#CBbPw=QhzNTJ{*w9fE))V<_S;r zQ|3#5TGf5@?~UT!cpvVcvDeHc8yYVyp8AipUl5!{>WG@{X_hc^bz5!vmN`!9pUdSC z2luZQ?}=d1BC5>Unlek0pxFsMSWR--C-a4U{A+iXGt+f}GbQD(yJoDxAFZ83X}VU} zFadoY;h(g@c!_)-HOkgCF|6*os-NG#V%SdA2dNsTd@F{d7=DL!aZYQ(i)E| zKuW&aOLAZQRgC3+KG!?<&AWW|G3DB+r|lAu*&C!F0l+p9AbYe|-*4MdJ|tH_K;57i z>-RUmo??xD>F=+z@TWd zzEmu1)uSC%?VX5GSux-J{0|h+N0p0?0t21^X9bbZ2O)Yrj<+}07vkP-Ji{j@V|gd| z^y{64eEXSD9$@3J>>kT3Jx-z=7jxI6#O z=KN*kQ@wNb-|lbnSXz)wxjxz#>n=&Z+QffqsC6dygP*#*=l;q_Qt|q&|6g~k)l!mY zFzcLDh7~Eg>LjBL9G=(IEVsJ#D{GjRNOA+oYju*4$1(Wvl*eE1oH2C3FT;yf6to{$X)7vGuy%lss}US zN!ZH6;KVq_6I=q2kc+vntK>;G>ceCrr@WxHE5buhm`GQ<`@bez6vjXLv8XzFE=aiE z;ya%wWln9%2L{uJ6fJvB@V~vaY`-`2J}vZGMtt;)QxwnXd5RB`ejm4R?mwi>JC(-g zP@@`ox>l6!n6;9%7eb8R8c{F|#Lw^X83BpkI*dG1JW!Xc8sOSW%y{L8IZ?-! zKomd5=)=`u^oks%_%tC<6pH)G!_q#vC#BHl_eOWJ8@??HL3|R{tRTNyNY=R%%0~bu zJ24QqD~I>93lXmCxL}ynF;bbxb^h};;%YVj?!A=wm00ya_75yB@5qfO*Q*XiOBPYT z+}l?hM9TcMv8%dC+;3h5zMAh9aF*Ji)ybZJ@BE(sE)Ii{wl++w_t__ zHQt_#kJH|L!ni3g9>XGJM|R3i;73!qDql=1JCHFGDAKFcNs9D0Jk5Ui)l}5%8{z)o z+J^3+nn_Y;G2uf{m!sqs&J2zfy}%Z}=ZV5lQXK1;E30qSHr+43Sz2Qqg4kal_LECx zLO(;}v2}|BGZ(#0TI46o7>?jf*nyS2W39r*O3kcq$i*eA5b;^1=-iDte8?DS-(U=B zq%#(Za1#N)v3pJo`jJet%%b}SEM8Q-p|#A->ln;CiR&$GxHqd42^iU1N=MB_^og*wO~UC>nB1iFz+gw4*boS8P7%2s%QF9!E#X+=x5{CXoE+Jf2-eN#&sy7 zy*rTO1}oVAdx#IFANU+T(wU2n+lmu3e|q1SZ!@M4WIxmVY);B;U?YRfEbMHM%U_g_ zF!$Z}&@}Pe)O|e1BY6Q_{}$CGQ&kFU*MOVZwvtRTpVp5Ah?TM z`N#DP$!e|1lH7BUqtUBK3Q(6tnzTSWs*cfa^fZfR8U5C`l8W*4xhDUOlmxSjmpB=u zWVosMU=7DOxwcXKxYvMO%u+_( zbm(E{AO0VgL2O8pv%I^`zy>ktB*h+WwCIh#jw$uBqRd^B@n$tx&JId4;=53{c!)Ca zfLM7lDs=2`LIoc7`(wOVA}cuR_@>MR(A|OfiSQP-w4iBKy~y$Hwu*rXrwtjw??0`E z2628+5y$3MZl8*b9^v}~qz{7*wP_LnDUZYRNRo1MkPl zbNLMIZ?WF>trJGpf!Qx$kTu%m;kT3_hu>`<6ByPPXe&c)=!4r)O`gZQYIXf~F}2GX z8m`Aa=>uTd+w>cslT*kGpr&jN^J@`468zv=V$B9Q{Byk8h}pxh%$biVZRPPgSsDRP zf?K#(|01S6s+c8dF(VgqqS!zOQzhW;?bfkBY=z3cCh4{)-7B1rJ9^6rdwaVnV;|`7 zUO0yZ-{RuBvip>|U3aRFqLt8kjpPg>cPt(+IQ&>~AA0`*@VqjV7axMZqilHWrdr*~ z@by>W8HtHb_=G&m&@H~3!h4bxiJwVy)5zg+m2>g(Uu|@o4uNh~WgHBHucDHt{S`Z$ zI!&usASOq(?Ac%cD?jv-W!|qq^;3@ru#@iI(=Gf!<&2xD33-G_uGOBOO@4B_&A7+0 zN)-}+4bz<;981%MwH*!j`G8ponZoNY%*PJpDIG-=`TZPc`D!f$uNoZ&ozRXFb+bcP>ovE{P4EERbPPJ#8E)%)H*nrGE~bskNs`zAduMR&o%r*KbgMWZ zvyIaEainjHDLW6=_=j~+tr@hG2TgJPd=gcJ7R;)9&LuO z8^5QBrkGxfVTtvYC{xF{<1kB1*F)wi&0+c;-mDo2t+nXNCn2YAD?YziU$M-AHnTl- zZh1~Z2o*$2-db^daz%15_BD0xy6mZ?r4_06Fp-;GoUYjBK(RvGR^G`nB)fREJJ_G! zxrogXbtm3nohFS3EG%Nk9Z^x4$X<#4Lo+JGNB;a!M`pJaHt3Ibo>H|?;fwLm9xp^3 zZN*0j~9w3|HGCt`URo6s`6WbiNj21v8l#y3sc<^F)*r{(O7AXS<_4^lp zH`X=CXaAF$#&AoOPYrcPCqCzlY2W49Mb>qgd+1H!hAh3!*iG6af1sR2nfr_82vPD& zT!}Kj;rkf+#~f5H7pY;7d7FnHS6u)}<9tqu#ZGCyw=x~R?-O+2)LaD}BCU%5@RUWcT26lO8r%lX7Z|EwL;Kr%Gr=o&6xJ2@h|u$Gj^AYiTrP}b=k=lV!Vf7l&V%6 z<{>tpopR3scxg6kzleF&7`S-C=pbxs3#1U`XDHe}xO%&}IYNl2iU0Gz^LI_eBHU+i z+Y?6yg$X8*p7`tcA&6Z9`y{z>gh-f(hHn|+uPfch_F6Bac6TV8Sw}ECy9Lt$ z=P$)^J-BLk=t2&AD?=X8i zF%JKvhSmwwnb)1)?b~f4J;46BG^<-0!gMv6=0mWXMj@+8t${8x>apf~w++7=vUBjp z1RJ^tJ?Z(&vc=VoD)`Ey03#W(<=_d{7z>bmKFr|5i73_Cg37??8NXTdhg!xFxR2hh z^NY+%l6R|e&+go8%x^-z)c#d zWbzN(0oRy6=*6y5a2WZu99!dnExHhp(X`?>K!R62@p(!NpMDCy;G<+krt z9%3es2P1sP5~_d1L^egSwYbZMCcou&q!+x50rJP)^XopL$1stBG3zlSv{;iwFGOS9 z@UC{&>wiSY);ml-xP*7jE^N)_`=C%A7i?)@X#5rPg;xcFe}@c8+PYcF~gl zbGg`kf{ofhWKGuS^<;Ilg0{>j*(&<)W7B+mVoOI#6+-BKis4$ye6*gO{|gVDDO|BX zxPljww`~c~&n$9j%VE1minJ~bC%0Nl9m~Sm0C{OzFij5@VK9_Qcy%FSrUYMNs=MdT zbw6lKgBZ{Fbg|pPUFtr}+-{sRMxmKR8z8du4Vk|udtK~4g_`(HO zL_+9m%&@8>*0%MZm4Q&oIy)M$Y}$OFBFupYP{t{%sl(qfw91CMD$tn=Szl(4C72I9 z9T?dz&O5^%lgK2Iws=U-i0Bcs{R?~Z8c#8~Zi^v)53uyKl8B^pDjH|gp(xcScI1>I z!FPEn?{jjbbuM3!2z@J>*h&WB+*1`cj`5TfeF z8#245u-GL!SVx%x@Eq@s-ViFhTsMAWoIv?pruQ!kwQt8|wf~}hEEFr0yyO<2f7C!> zQZQiMHFnR)=|wAkoDi^ee#ys}e8fk3|GKSgEcGSjW)3yGxDrreJ)M}q+VB5-%ND`3TO)0j7X-Y$VEfxb z_9FENMa?dn1S2Q1Pd&R5vKTL9(;P%)TL{p)qFwxtiD7WC2RUZB2J(4?4|!pyV+bl+ ze;i&^tn_odCcVYk#l7?D!x*~8U(OavJ%FZeEJs&%2jAWwo)$>`h`aNq1EW^{L062l z8)n_M!|r7MGe!7&^*P7vjnJ4R7-$W9-v((w6NBV}bC$u3265f_cD%ym7=6FbdoMRM z7%wAMs|y7EGIearA_zev!ZG14U^P&1i+OKRucyD;qI9Mqp!D!Nz zGP3Vsl=&?v`sY0ud8`}0IT(2a6%tLsU+TB{B{luskaoVG&g z9|)raQIwi&2d@!U;9@g^63a-JUS%@#v;OkZH}wx!h(@6XxFZ~eu?}=-QKO*v+D~+K z2adSgQHnW1f`_q`jnBb5pK$5U&<_s$8>)9nk~z}HUsrrZXmdTn|F}jP0eIv@cnjPe zwO!`T+eOOtuJjz3t>^P!&8@Deo@sp;U&?ZQDTCmM9XAjxne;#Tl==H_<8H|C0m#nX zLDLpI&1!%v7e;=9&l*Jh_TDS5AiW3{SeFq;sS>xh2^)mumitN0`x~0z+``ExUvHpI z1Sq?i&2(7;mq+7k1)EkI`mb81GYtQeQF5)xkC&y%Ed9WJ@oA!4ySQ7&#pI<1Gex0$?vvPkC$vP^6$#xHCIboAlGaaz z5aV@OouEURqTu=T7NLMAf)PuOWw>Dyy`)CWoAR2v+=KwwUM^6wTM_V4u{yXx+sMuz$AR62%2 zqSmeqh&(u$BEA4#1=F_n#Kq z8~gy-K}1tpSL;WFFYnh_XP$tbMaX%Y6~otDc8qgs@wwggjkt9b#To$Wiq;*tmPtHW z!I};2fb}Cu=p53{qU+;6{Is-Oy`NcA`CURbPt=byxQ)}vc4|Ih3I{BRJCc0F>joG-wuwNPD@!$ z!xOW;k9J@1*!zz_9eSg~d*k1dtv~5rk(_lNE92@fDZOsPf^@+7TRz}k##hGl7B+P@ zN`ln+RFvzq!6RiaT}?{4&!~-!oymYsjYszr%Mty>LII3*Np9X+Z}h0Duu?J8PbyGF zso^_4Q6U>Dt~BA|Y>w1UEG;t(CQ^`+$74_cB~~u$d$s@g`V@C?3;fKM|GP5lKbHc8 zqy2fn3D}=_Ku!zMEwD?KJuj>CDGrLC9_({XPUKUV!A7YR9ziP5xwGpY><15fh(5Ke z)NGrc)kx>0IG%Qvkh&`%#S+`<23QE7@$6pRhI^Z^hWTDHX}{iN8VZbw_H1pW37w3C zYVau;>X+|A-hnn1mCJrb!H^%fo@E-b=CjHUp3%;)%dOW|_!Z9??bM2KY?@ASuOIcb z2Ja=86&!HI-ey%H9k9r5Qz1ZtTw8^#*Cauhsnf33`f^?}QpHY(ae6L@Noa#AF zv&AFDaWOcqKR&4bk6v8;mSWhi6|1%yF#WcQfmdY)-&$aI7z};E_IEaSbusXf)3%=+ zBruYLRAm#Jy=`4-&S1)@9ibK1#^JG}lKfUt2EdhO&_rOq{ zSGVbSeTB6B&MmeX-aAH9G0e;v&(y2qEgAZ`~jh#RI7_y#Z9IZy;& ze`#ZM2x`crcgLsosM^wF<8^Eix1?CA75!W7*AY6r+Xg0kd)vvkI{I2NaH8!4EM3BN zj67g;7srhL=&2duPj__yLjToITl{(D72}zyUHzE6bbLK3vTs6;e7|YFIUZ&5 z`TXQSzQPey)8AU&R;Z@aR5~?C>(85w>)%*eEab31bk}L6*h!r>#Sp9_63$QX4(Pfx zub}_OiZ^c#KjRt6yK{W9CJ-9-#m@yb9<~StN;4nUV36(Ak{;P54dzt5n^$y9If3&-}84Iib+cgD=pPhY=oM~^(tp|fF zEzcIj=nmA_)bog|+LWd;ABf{vKU3T|w2E@|q=LNF-;}tHTnr9dy3|aF=e>&3ZZ%Ve zhGN4XQTM%X4B1)OeOe%0Sh^MW$Wqu1g$u^%A}SRs@}jG-1)}b@=WLFKr_3@OSPS<| zLH5x}nmRT}T=b_T$mb z{%23MM1K{}ruY-a&dm^h^fGmPe&%xftoA?Z9l{s~7At(JXr=Fyn3ZrLW)Zq%(Xsz2 zC}jp+G4r0_jL&QI-4@fnyiGv&3_cI}k46@1E@tWh3~SQ^_9`jLdyrTqzht#MleoQRm#yqPT0-%9h0VD!FL)UXf8v2(pOT8g->iMY%{3Q zz*>r5{JTK>BS=s8KB}P#V?a)+{aM~f{JET|zx<`yBYx?ds9cC6Hjj7OM_>l^^2p)# zdsEhBhIk1W@B9Gc>6qBr-u77*dhM1;T8r295CP_Eh^fpGZo7Le`KYQE+?7QJ{G<+J zv*Pg<|01~*I{Af5J#4r7A0KYF{ZhopR>IR(0C%5Vc~2cRr=;75&jjud{>qnI2CmlN@`v)%7(qTfqpw}~=qSCuSy zOEzQvo^wrDcN(BSsJZ^lcA;u!X&3!JqR#p)>MmOQGt>+{NOyxsgGjduN{L8Fhm^E* z&d?wd0@B?b(%qoa(p}QsHF4%S?{%*CFPQmZfA?B@t^5Am7D(fua(DU+UTX+rxXzQ- zAkXi(lLu!yP%8bo5aM!Bi1OTd`FxfT7d{P$8cG(So0(HHnm>jq>Eu#oY;@{z|34i{<&^PzR zA6Ke>^8a2j!RY?wY$e!Gt9sC>6n{$W0V*KqE^(^4yoaybw|&m$(_`kw9WIJ}{(EU3 z#Cbl&3)zg0_bHb!P4aFHSa!wouy)rP|E`K=ggVnb-}a(5+?HZ@Isu=N>j0q2NLh|7 zRv1>Ec8jh0hLDcqNm25u2gp1*z711OO}Ju(0g_p{`ZMo@F1B^Ow2?=(teaaO_{pKO zLCF?h>pa}cATwXBbGQ~)d9f1E6&T@8-K_;)QjE*onQO7*pN}|QwEU6kY*T6t%5i)i zCP0z~zWsQMG8I(K=4o;Pa|qXjAQ%gLZH13bv2$bughA9+N4lBtuUInw9uT?f)CvW!xMPAEKJlGx=Ex)x?hHzzarqkL_{n$T+H%D^6S6+lw@(!Nc4 z$D9#P&aF)_%-0_K9n?q0uc50qp%$+n-m(#)A-%1 zF?rHtYr?7H8c|QfZK$xsXmAHKxl7i&&9w`g=5l^=0)JQA7Ba-1w;Jiy8nQ~c^Q@Va z5+qYp0eQ;__0@R4dtR-~Xn`#-a0UGy#uGT7)i9-z6R?0Cdu5v*)B-KRWt(2gbkm zR|z`4ZsWSkyga;%1UKuQW+GKLqT z8^gxOzA2Q^-dOmG;(KYNhPi>yszNF9d)F zHHh@9RVqG}N)(4B1$M~m3EMt&68h8wt+jugeOG_ZA(EY_Z-J2jB^&~XmGI@kPAQTu z*jG|6;k4JPYnxO7NqSDvp&{->s845eJeYc{SbBtd3A|Eo<&tvP9ygyHeMweP4pj~- zrsG=FNv$z`xCYkb5cL2WpFSrSi;0ww6}mOuA5yUy1UcjTO1Qo*@Mw9ag?gol2P9hH zI{~~1d7goctm_61i_5Sl-6eFlT1GQ*&m!6?3J5P{Uru#-%L+gACilnd2Q;9_Hxk>D zoXCTU4Pe@NtZz*|)Nl@!OyHUs+l7Urf~`wCqS)~iN@G+20*{On#Kc9k`>Yp^x1tKl zWi2R3?k}9-4%N%2lzhVWS?$N}J)awy@Sx15#HnvaQMV+RNAbRayfCzz2XmR1?d9zA zFEI8=Ks1zc7s{Jo!onk}8fy}+N?Mf%!g>?h#i;_&-v?Xmf!nP+Mv(e-P;5Y86TOBZ z*?qZTs(a}|n%f;=8K7vB0(7UAw9?m( z8{3YOMoH=Z?pM+M6fL97Uk}%QYaE3RO}gHHG7Rj+fN{RW51_9>mpeF z4G_({V&HyJBBtPis9n7q8m-u5*S8Co$S3F7K>!Byp!4<@inAX-G$p)z_N(f1%D>Ad zwt2XGo2=Evnl=YHeOsYr@crc0cdW)PngOq81Y!(MV2P5?KLg&c%0Y6v^YHs-f;CW4lVbEeSD?CT(ncB09oZ3t{|zDNaa=E~F_<;4Pw24S`PG{& zZ_UasjC$pkqE&Yfv&c{B?+ycnWK{HtCNrJMdX|S8{h9La=-eK^HXLv4IU!MXw;Z)e zymscZi;r%P^$W`*OC67k&vZ2{@i0k4s04&bX;saBl;A$|Hcbr#s!(Am6A1Py52D5V z6!D={%uASTAK39}4Kd>klZ@u8c4o?NR~>#zubkW(`>in^qPxYG)LW}8tLy}C&kRz@ z|1$H?;R{1+1B?~NLyU5IfaXTVFsRI29ZDwR2Bs6-BI@z!Oq25P&ME47Qu2fx9&p)M zNEN|e@UpIn>1DRvftj%iLvof_m=VtU7XTf~J@T-BlzF6f6?y(pZ8=Vqe6mU4LW}}E zP7#hEMD;fFUB|B>7yGAu+tTr0pZplc4HX~p zH0UYJBmqUZ*(x~LnC^42B09l5!1(#w0HfcB0(1QHAy}>J*YR&8VgcQ$T4R^)dR`lh zSSq0`zj8YY%}tTxGR%?$+vPRS!HF&1EsbCoyi2FYzasg*+w*SUMD8gen}5q%eJ1fR z_~l@$;0L)B<y~7yt!|`(6;2~ z9{1HjuR~1P0bYbm9UJT(Z-=0g4zesRidnZA-k@Nwq5Hq4t6yR}hNi#UKhGXAE@nG9 zWl8l#3yMrws+rc!14To{zhep7MPRtgdFhK&pX4+q3IstcY++6=;&K9VhCL0*LxM6_ z<-zWn7p=G~CuTY)=Mp2jl$-CSu7gFAag@I@LDn@TKxC%H8R3RIpQ*yC0|wfBXB*@1 zhg6$s)^o;04lGQ?%(-cAafa+#i+Ut^isRh>vguu-%z@6c{wl=-|7d=FE-EjVZL2Lp z3L#@>1+O_7@&{b$_eczX)s1>zUzrw5h|iZi(7N87gxw9bJ^VX)thnw%hYVl^@AQ*f zq43iEoH`#l(!-n*56J>d8~8a(j8XV+